From e7410ea2206bca806e95a4f45cf28a1240af80d7 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 3 Mar 2019 19:52:36 +0100 Subject: [PATCH 001/248] Experimental calibration for MAG gain --- src/main/fc/settings.yaml | 12 ++++++++++++ src/main/sensors/compass.c | 26 +++++++++++++++++++++----- src/main/sensors/compass.h | 1 + 3 files changed, 34 insertions(+), 5 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 12d6f9a367c..5e8272a0bb2 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -303,6 +303,18 @@ groups: field: magZero.raw[Z] min: INT16_MIN max: INT16_MAX + - name: maggain_x + field: magGain[X] + min: INT16_MIN + max: INT16_MAX + - name: maggain_y + field: magGain[Y] + min: INT16_MIN + max: INT16_MAX + - name: maggain_z + field: magGain[Z] + min: INT16_MIN + max: INT16_MAX - name: mag_calibration_time field: magCalibrationTimeLimit min: 30 diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index 0a0173dce82..6d8ae40b62f 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -57,7 +57,7 @@ mag_t mag; // mag access functions -PG_REGISTER_WITH_RESET_TEMPLATE(compassConfig_t, compassConfig, PG_COMPASS_CONFIG, 3); +PG_REGISTER_WITH_RESET_TEMPLATE(compassConfig_t, compassConfig, PG_COMPASS_CONFIG, 4); #ifdef USE_MAG #define MAG_HARDWARE_DEFAULT MAG_AUTODETECT @@ -334,6 +334,7 @@ void compassUpdate(timeUs_t currentTimeUs) static sensorCalibrationState_t calState; static timeUs_t calStartedAt = 0; static int16_t magPrev[XYZ_AXIS_COUNT]; + static int magGain[XYZ_AXIS_COUNT] = {-4096, -4096, -4096}; // Check magZero if ((compassConfig()->magZero.raw[X] == 0) && (compassConfig()->magZero.raw[Y] == 0) && (compassConfig()->magZero.raw[Z] == 0)) { @@ -375,9 +376,15 @@ void compassUpdate(timeUs_t currentTimeUs) float diffMag = 0; float avgMag = 0; - for (int axis = 0; axis < 3; axis++) { + for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { diffMag += (mag.magADC[axis] - magPrev[axis]) * (mag.magADC[axis] - magPrev[axis]); avgMag += (mag.magADC[axis] + magPrev[axis]) * (mag.magADC[axis] + magPrev[axis]) / 4.0f; + + int32_t sample = ABS(mag.magADC[axis]); + if (sample > magGain[axis]) { + magGain[axis] = sample; + } + } // sqrtf(diffMag / avgMag) is a rough approximation of tangent of angle between magADC and magPrev. tan(8 deg) = 0.14 @@ -396,14 +403,23 @@ void compassUpdate(timeUs_t currentTimeUs) compassConfigMutable()->magZero.raw[axis] = lrintf(magZerof[axis]); } + /* + * Scale calibration + * We use max absolute value of each axis as scale calibration with constant 1024 as base + * It is dirty, but worth checking if this will solve the problem of changing mag vector when UAV is tilted + */ + for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { + compassConfigMutable()->magGain[axis] = magGain[axis] - compassConfig()->magZero.raw[axis]; + } + calStartedAt = 0; saveConfigAndNotify(); } } else { - mag.magADC[X] -= compassConfig()->magZero.raw[X]; - mag.magADC[Y] -= compassConfig()->magZero.raw[Y]; - mag.magADC[Z] -= compassConfig()->magZero.raw[Z]; + for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { + mag.magADC[axis] = (mag.magADC[axis] - compassConfig()->magZero.raw[axis]) * compassConfig()->magGain[axis] / 1024; + } } if (mag.dev.magAlign.useExternal) { diff --git a/src/main/sensors/compass.h b/src/main/sensors/compass.h index 87cbfaa48cf..7c9a0fca63b 100644 --- a/src/main/sensors/compass.h +++ b/src/main/sensors/compass.h @@ -58,6 +58,7 @@ typedef struct compassConfig_s { sensor_align_e mag_align; // on-board mag alignment. Ignored if externally aligned via *DeciDegrees. uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device flightDynamicsTrims_t magZero; + int16_t magGain[XYZ_AXIS_COUNT]; uint8_t mag_to_use; uint8_t magCalibrationTimeLimit; // Time for compass calibration (seconds) int16_t rollDeciDegrees; // Alignment for external mag on the roll (X) axis (0.1deg) From b66a7d7be31a7b0e6e77204ec3862d3e4464b9f5 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 4 Mar 2019 09:07:34 +0100 Subject: [PATCH 002/248] Fix math --- src/main/sensors/compass.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index 6d8ae40b62f..eda1fab967a 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -418,7 +418,7 @@ void compassUpdate(timeUs_t currentTimeUs) } else { for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { - mag.magADC[axis] = (mag.magADC[axis] - compassConfig()->magZero.raw[axis]) * compassConfig()->magGain[axis] / 1024; + mag.magADC[axis] = (mag.magADC[axis] - compassConfig()->magZero.raw[axis]) * 1024 / compassConfig()->magGain[axis]; } } From f30a21237829fcb6d6d5950d5398b38be8710ca4 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 19 Jan 2020 20:50:39 +0100 Subject: [PATCH 003/248] Attenuate VEL_XY when UAV is traveling at high speed --- src/main/fc/settings.yaml | 12 ++++ src/main/flight/pid.c | 3 + src/main/flight/pid.h | 4 +- src/main/navigation/navigation.c | 19 +++-- src/main/navigation/navigation_fixedwing.c | 2 +- src/main/navigation/navigation_multicopter.c | 73 +++++++++++++++++--- src/main/navigation/navigation_private.h | 12 +++- 7 files changed, 107 insertions(+), 18 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 26b1fe49f73..27a2a28efa3 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1203,6 +1203,18 @@ groups: field: navVelXyDTermLpfHz min: 0 max: 100 + - name: nav_mc_vel_xy_dterm_dyn_scale + field: navVelXyDtermDynScale + min: 0 + max: 1 + - name: nav_mc_vel_xy_dterm_dyn_scale_min_at + field: navVelXyDtermDynScaleMinAt + min: 0 + max: 1 + - name: nav_mc_vel_xy_dterm_dyn_scale_max_at + field: navVelXyDtermDynScaleMaxAt + min: 0 + max: 1 - name: nav_fw_pos_z_p field: bank_fw.pid[PID_POS_Z].P condition: USE_NAV diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index ce7e6579828..862ec618977 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -246,6 +246,9 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .loiter_direction = NAV_LOITER_RIGHT, .navVelXyDTermLpfHz = NAV_ACCEL_CUTOFF_FREQUENCY_HZ, + .navVelXyDtermDynScale = 0.2f, + .navVelXyDtermDynScaleMinAt = 0.6f, + .navVelXyDtermDynScaleMaxAt = 0.2f, .iterm_relax_type = ITERM_RELAX_SETPOINT, .iterm_relax_cutoff = MC_ITERM_RELAX_CUTOFF_DEFAULT, .iterm_relax = ITERM_RELAX_RP, diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 343ecf21e5d..0ce8b3e94fd 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -137,7 +137,9 @@ typedef struct pidProfile_s { uint8_t loiter_direction; // Direction of loitering center point on right wing (clockwise - as before), or center point on left wing (counterclockwise) float navVelXyDTermLpfHz; - + float navVelXyDtermDynScale; // VEL_XY dynamic Dterm scale: Dterm will be attenuated by this value when velocity is at navVelXyDtermMaxAt and 1.0 when velocity is at navVelXyDtermMinAt + float navVelXyDtermDynScaleMinAt; // VEL_XY dynamic Dterm scale: Dterm will be scaled down fully to navVelXyDtermDynScale when velocity in setpoint and measurement is above this value. It is a factor of max. velocity processed by the controller + float navVelXyDtermDynScaleMaxAt; // VEL_XY dynamic Dterm scale: Dterm will be not scaled when velocity in setpoint and measurement is below this value. It is a factor of max. velocity processed by the controller uint8_t iterm_relax_type; // Specifies type of relax algorithm uint8_t iterm_relax_cutoff; // This cutoff frequency specifies a low pass filter which predicts average response of the quad to setpoint uint8_t iterm_relax; // Enable iterm suppression during stick input diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 3cfe2459ef1..2956b6e962d 100755 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -1711,8 +1711,17 @@ static fpVector3_t * rthGetHomeTargetPosition(rthTargetMode_e mode) // Implementation of PID with back-calculation I-term anti-windup // Control System Design, Lecture Notes for ME 155A by Karl Johan Åström (p.228) // http://www.cds.caltech.edu/~murray/courses/cds101/fa02/caltech/astrom-ch6.pdf -float navPidApply3(pidController_t *pid, const float setpoint, const float measurement, const float dt, const float outMin, const float outMax, const pidControllerFlags_e pidFlags, const float gainScaler) -{ +float navPidApply3( + pidController_t *pid, + const float setpoint, + const float measurement, + const float dt, + const float outMin, + const float outMax, + const pidControllerFlags_e pidFlags, + const float gainScaler, + const float dTermScaler +) { float newProportional, newDerivative, newFeedForward; float error = setpoint - measurement; @@ -1736,11 +1745,13 @@ float navPidApply3(pidController_t *pid, const float setpoint, const float measu } if (pid->dTermLpfHz > 0) { - newDerivative = pid->param.kD * pt1FilterApply4(&pid->dterm_filter_state, newDerivative, pid->dTermLpfHz, dt) * gainScaler; + newDerivative = pid->param.kD * pt1FilterApply4(&pid->dterm_filter_state, newDerivative, pid->dTermLpfHz, dt); } else { newDerivative = pid->param.kD * newDerivative; } + newDerivative = newDerivative * gainScaler * dTermScaler; + if (pidFlags & PID_ZERO_INTEGRATOR) { pid->integrator = 0.0f; } @@ -1780,7 +1791,7 @@ float navPidApply3(pidController_t *pid, const float setpoint, const float measu float navPidApply2(pidController_t *pid, const float setpoint, const float measurement, const float dt, const float outMin, const float outMax, const pidControllerFlags_e pidFlags) { - return navPidApply3(pid, setpoint, measurement, dt, outMin, outMax, pidFlags, 1.0f); + return navPidApply3(pid, setpoint, measurement, dt, outMin, outMax, pidFlags, 1.0f, 1.0f); } void navPidReset(pidController_t *pid) diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index f7d08917616..6b4bfe8f08c 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -134,7 +134,7 @@ static void updateAltitudeVelocityAndPitchController_FW(timeDelta_t deltaMicros) const float minDiveDeciDeg = -DEGREES_TO_DECIDEGREES(navConfig()->fw.max_dive_angle); // PID controller to translate energy balance error [J] into pitch angle [decideg] - float targetPitchAngle = navPidApply3(&posControl.pids.fw_alt, demSEB, estSEB, US2S(deltaMicros), minDiveDeciDeg, maxClimbDeciDeg, 0, pitchGainInv); + float targetPitchAngle = navPidApply3(&posControl.pids.fw_alt, demSEB, estSEB, US2S(deltaMicros), minDiveDeciDeg, maxClimbDeciDeg, 0, pitchGainInv, 1.0f); targetPitchAngle = pt1FilterApply4(&velzFilterState, targetPitchAngle, NAV_FW_PITCH_CUTOFF_FREQENCY_HZ, US2S(deltaMicros)); // Reconstrain pitch angle ( >0 - climb, <0 - dive) diff --git a/src/main/navigation/navigation_multicopter.c b/src/main/navigation/navigation_multicopter.c index 596b47f646b..aee57bffca1 100755 --- a/src/main/navigation/navigation_multicopter.c +++ b/src/main/navigation/navigation_multicopter.c @@ -437,7 +437,7 @@ static float getVelocityExpoAttenuationFactor(float velTotal, float velMax) return 1.0f - posControl.posResponseExpo * (1.0f - (velScale * velScale)); // x^3 expo factor } -static void updatePositionVelocityController_MC(void) +static void updatePositionVelocityController_MC(const float maxSpeed) { const float posErrorX = posControl.desiredState.pos.x - navGetCurrentActualPositionAndVelocity()->pos.x; const float posErrorY = posControl.desiredState.pos.y - navGetCurrentActualPositionAndVelocity()->pos.y; @@ -446,9 +446,6 @@ static void updatePositionVelocityController_MC(void) float newVelX = posErrorX * posControl.pids.pos[X].param.kP; float newVelY = posErrorY * posControl.pids.pos[Y].param.kP; - // Get max speed from generic NAV (waypoint specific), don't allow to move slower than 0.5 m/s - const float maxSpeed = getActiveWaypointSpeed(); - // Scale velocity to respect max_speed float newVelTotal = sqrtf(sq(newVelX) + sq(newVelY)); if (newVelTotal > maxSpeed) { @@ -472,12 +469,20 @@ static void updatePositionVelocityController_MC(void) #endif } -static void updatePositionAccelController_MC(timeDelta_t deltaMicros, float maxAccelLimit) +static void updatePositionAccelController_MC(timeDelta_t deltaMicros, float maxAccelLimit, const float maxSpeed) { + const float measurementX = navGetCurrentActualPositionAndVelocity()->vel.x; + const float measurementY = navGetCurrentActualPositionAndVelocity()->vel.y; + const float measurementXY = sqrtf(powf(measurementX, 2)+powf(measurementY, 2)); + + const float setpointX = posControl.desiredState.vel.x; + const float setpointY = posControl.desiredState.vel.y; + const float setpointXY = sqrtf(powf(setpointX, 2)+powf(setpointY, 2)); + // Calculate velocity error - const float velErrorX = posControl.desiredState.vel.x - navGetCurrentActualPositionAndVelocity()->vel.x; - const float velErrorY = posControl.desiredState.vel.y - navGetCurrentActualPositionAndVelocity()->vel.y; + const float velErrorX = setpointX - measurementX; + const float velErrorY = setpointY - measurementY; // Calculate XY-acceleration limit according to velocity error limit float accelLimitX, accelLimitY; @@ -508,11 +513,55 @@ static void updatePositionAccelController_MC(timeDelta_t deltaMicros, float maxA // TODO: Verify if we need jerk limiting after all + /* + * This PID controller has dynamic dTerm scale. It's less active when controller + * is tracking setpoint at high speed. Full dTerm is required only for position hold, + * acceleration and deceleration + * Scale down dTerm with 2D speed + */ + + //Normalize the setpoint and measurement between 0.0f and 1.0f where 1.0f is currently used max speed + const float setpointNormalized = constrainf(scaleRangef(fabsf(setpointXY), 0, maxSpeed, 0.0f, 1.0f), 0.0f, 1.0f); + const float measurementNormalized = constrainf(scaleRangef(fabsf(measurementXY), 0, maxSpeed, 0.0f, 1.0f), 0.0f, 1.0f); + + /* + * Map normalized speed of setpoint and measurement between 1.0f and nav_mc_vel_xy_dterm_dyn_scale + * 1.0f means that Dterm is not attenuated + * navVelXyDtermDynScale means full allowed attenuation + * + * Dterm can be attenuated when both setpoint and measurement is high - UAV is moving close to desired velocity + */ + const float setpointScale = constrainf(scaleRangef(setpointNormalized, pidProfile()->navVelXyDtermDynScaleMinAt, pidProfile()->navVelXyDtermDynScaleMaxAt, 1.0f, pidProfile()->navVelXyDtermDynScale), pidProfile()->navVelXyDtermDynScale, 1.0f); + const float measurementScale = constrainf(scaleRangef(measurementNormalized, pidProfile()->navVelXyDtermDynScaleMinAt, pidProfile()->navVelXyDtermDynScaleMaxAt, 1.0f, pidProfile()->navVelXyDtermDynScale), pidProfile()->navVelXyDtermDynScale, 1.0f); + + //Use the higher scaling factor from the two above + const float dtermScale = MAX(setpointScale, measurementScale); + // Apply PID with output limiting and I-term anti-windup // Pre-calculated accelLimit and the logic of navPidApply2 function guarantee that our newAccel won't exceed maxAccelLimit // Thus we don't need to do anything else with calculated acceleration - float newAccelX = navPidApply2(&posControl.pids.vel[X], posControl.desiredState.vel.x, navGetCurrentActualPositionAndVelocity()->vel.x, US2S(deltaMicros), accelLimitXMin, accelLimitXMax, 0); - float newAccelY = navPidApply2(&posControl.pids.vel[Y], posControl.desiredState.vel.y, navGetCurrentActualPositionAndVelocity()->vel.y, US2S(deltaMicros), accelLimitYMin, accelLimitYMax, 0); + float newAccelX = navPidApply3( + &posControl.pids.vel[X], + setpointX, + measurementX, + US2S(deltaMicros), + accelLimitXMin, + accelLimitXMax, + 0, // Flags + 1.0f, // Total gain scale + dtermScale // Additional dTerm scale + ); + float newAccelY = navPidApply3( + &posControl.pids.vel[Y], + setpointY, + measurementY, + US2S(deltaMicros), + accelLimitYMin, + accelLimitYMax, + 0, // Flags + 1.0f, // Total gain scale + dtermScale // Additional dTerm scale + ); int32_t maxBankAngle = DEGREES_TO_DECIDEGREES(navConfig()->mc.max_bank_angle); @@ -589,8 +638,10 @@ static void applyMulticopterPositionController(timeUs_t currentTimeUs) if (!bypassPositionController) { // Update position controller if (deltaMicrosPositionUpdate < HZ2US(MIN_POSITION_UPDATE_RATE_HZ)) { - updatePositionVelocityController_MC(); - updatePositionAccelController_MC(deltaMicrosPositionUpdate, NAV_ACCELERATION_XY_MAX); + // Get max speed from generic NAV (waypoint specific), don't allow to move slower than 0.5 m/s + const float maxSpeed = getActiveWaypointSpeed(); + updatePositionVelocityController_MC(maxSpeed); + updatePositionAccelController_MC(deltaMicrosPositionUpdate, NAV_ACCELERATION_XY_MAX, maxSpeed); } else { resetMulticopterPositionController(); diff --git a/src/main/navigation/navigation_private.h b/src/main/navigation/navigation_private.h index a11e9a0f62c..f56048e8abf 100755 --- a/src/main/navigation/navigation_private.h +++ b/src/main/navigation/navigation_private.h @@ -373,7 +373,17 @@ extern navigationPosControl_t posControl; const navEstimatedPosVel_t * navGetCurrentActualPositionAndVelocity(void); float navPidApply2(pidController_t *pid, const float setpoint, const float measurement, const float dt, const float outMin, const float outMax, const pidControllerFlags_e pidFlags); -float navPidApply3(pidController_t *pid, const float setpoint, const float measurement, const float dt, const float outMin, const float outMax, const pidControllerFlags_e pidFlags, const float gainScaler); +float navPidApply3( + pidController_t *pid, + const float setpoint, + const float measurement, + const float dt, + const float outMin, + const float outMax, + const pidControllerFlags_e pidFlags, + const float gainScaler, + const float dTermScaler +); void navPidReset(pidController_t *pid); void navPidInit(pidController_t *pid, float _kP, float _kI, float _kD, float _kFF, float _dTermLpfHz); From 9538e65dc9598e548114af67bfa7e2f6214e0b35 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sat, 25 Jan 2020 18:08:57 +0100 Subject: [PATCH 004/248] Add basic debug --- src/main/navigation/navigation_multicopter.c | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/src/main/navigation/navigation_multicopter.c b/src/main/navigation/navigation_multicopter.c index aee57bffca1..13eea54dfee 100755 --- a/src/main/navigation/navigation_multicopter.c +++ b/src/main/navigation/navigation_multicopter.c @@ -524,6 +524,9 @@ static void updatePositionAccelController_MC(timeDelta_t deltaMicros, float maxA const float setpointNormalized = constrainf(scaleRangef(fabsf(setpointXY), 0, maxSpeed, 0.0f, 1.0f), 0.0f, 1.0f); const float measurementNormalized = constrainf(scaleRangef(fabsf(measurementXY), 0, maxSpeed, 0.0f, 1.0f), 0.0f, 1.0f); + DEBUG_SET(DEBUG_ALWAYS, 0, setpointNormalized * 100); + DEBUG_SET(DEBUG_ALWAYS, 1, measurementNormalized * 100); + /* * Map normalized speed of setpoint and measurement between 1.0f and nav_mc_vel_xy_dterm_dyn_scale * 1.0f means that Dterm is not attenuated @@ -534,8 +537,12 @@ static void updatePositionAccelController_MC(timeDelta_t deltaMicros, float maxA const float setpointScale = constrainf(scaleRangef(setpointNormalized, pidProfile()->navVelXyDtermDynScaleMinAt, pidProfile()->navVelXyDtermDynScaleMaxAt, 1.0f, pidProfile()->navVelXyDtermDynScale), pidProfile()->navVelXyDtermDynScale, 1.0f); const float measurementScale = constrainf(scaleRangef(measurementNormalized, pidProfile()->navVelXyDtermDynScaleMinAt, pidProfile()->navVelXyDtermDynScaleMaxAt, 1.0f, pidProfile()->navVelXyDtermDynScale), pidProfile()->navVelXyDtermDynScale, 1.0f); + DEBUG_SET(DEBUG_ALWAYS, 2, setpointScale * 100); + DEBUG_SET(DEBUG_ALWAYS, 3, measurementScale * 100); + //Use the higher scaling factor from the two above const float dtermScale = MAX(setpointScale, measurementScale); + DEBUG_SET(DEBUG_ALWAYS, 4, dtermScale * 100); // Apply PID with output limiting and I-term anti-windup // Pre-calculated accelLimit and the logic of navPidApply2 function guarantee that our newAccel won't exceed maxAccelLimit From 0ae860faf64ceaad7e18f88ef607107b9aeeaa00 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 6 Mar 2020 15:27:59 +0100 Subject: [PATCH 005/248] Refactor Dterm atenuation --- src/main/fc/settings.yaml | 18 ++++++------ src/main/flight/pid.c | 6 ++-- src/main/flight/pid.h | 6 ++-- src/main/navigation/navigation.c | 13 +++++++-- src/main/navigation/navigation_multicopter.c | 29 ++++++++------------ src/main/navigation/navigation_private.h | 8 ++++++ 6 files changed, 46 insertions(+), 34 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 2484bd4f540..e59925478de 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1184,18 +1184,18 @@ groups: field: navVelXyDTermLpfHz min: 0 max: 100 - - name: nav_mc_vel_xy_dterm_dyn_scale - field: navVelXyDtermDynScale + - name: nav_mc_vel_xy_dterm_attenuation + field: navVelXyDtermAttenuation min: 0 - max: 1 - - name: nav_mc_vel_xy_dterm_dyn_scale_min_at - field: navVelXyDtermDynScaleMinAt + max: 100 + - name: nav_mc_vel_xy_dterm_attenuation_start + field: navVelXyDtermAttenuationStart min: 0 - max: 1 - - name: nav_mc_vel_xy_dterm_dyn_scale_max_at - field: navVelXyDtermDynScaleMaxAt + max: 100 + - name: nav_mc_vel_xy_dterm_attenuation_end + field: navVelXyDtermAttenuationEnd min: 0 - max: 1 + max: 100 - name: nav_fw_pos_z_p field: bank_fw.pid[PID_POS_Z].P condition: USE_NAV diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 07734efdac4..3897ecac334 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -257,9 +257,9 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .loiter_direction = NAV_LOITER_RIGHT, .navVelXyDTermLpfHz = NAV_ACCEL_CUTOFF_FREQUENCY_HZ, - .navVelXyDtermDynScale = 0.2f, - .navVelXyDtermDynScaleMinAt = 0.6f, - .navVelXyDtermDynScaleMaxAt = 0.2f, + .navVelXyDtermAttenuation = 80, + .navVelXyDtermAttenuationStart = 20, + .navVelXyDtermAttenuationEnd = 60, .iterm_relax_type = ITERM_RELAX_SETPOINT, .iterm_relax_cutoff = MC_ITERM_RELAX_CUTOFF_DEFAULT, .iterm_relax = ITERM_RELAX_RP, diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index cb53cc220c2..51e6469d9d1 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -138,9 +138,9 @@ typedef struct pidProfile_s { uint8_t loiter_direction; // Direction of loitering center point on right wing (clockwise - as before), or center point on left wing (counterclockwise) float navVelXyDTermLpfHz; - float navVelXyDtermDynScale; // VEL_XY dynamic Dterm scale: Dterm will be attenuated by this value when velocity is at navVelXyDtermMaxAt and 1.0 when velocity is at navVelXyDtermMinAt - float navVelXyDtermDynScaleMinAt; // VEL_XY dynamic Dterm scale: Dterm will be scaled down fully to navVelXyDtermDynScale when velocity in setpoint and measurement is above this value. It is a factor of max. velocity processed by the controller - float navVelXyDtermDynScaleMaxAt; // VEL_XY dynamic Dterm scale: Dterm will be not scaled when velocity in setpoint and measurement is below this value. It is a factor of max. velocity processed by the controller + uint8_t navVelXyDtermAttenuation; // VEL_XY dynamic Dterm scale: Dterm will be attenuatedby this value (in percent) when UAV is traveling with more than navVelXyDtermAttenuationStart percents of max velocity + uint8_t navVelXyDtermAttenuationStart; // VEL_XY dynamic Dterm scale: Dterm attenuation will begin at this percent of max velocity + uint8_t navVelXyDtermAttenuationEnd; // VEL_XY dynamic Dterm scale: Dterm will be fully attenuated at this percent of max velocity uint8_t iterm_relax_type; // Specifies type of relax algorithm uint8_t iterm_relax_cutoff; // This cutoff frequency specifies a low pass filter which predicts average response of the quad to setpoint uint8_t iterm_relax; // Enable iterm suppression during stick input diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 6400c95c9c3..634aae2c049 100755 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -171,8 +171,9 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, } ); -navigationPosControl_t posControl; -navSystemStatus_t NAV_Status; +EXTENDED_FASTRAM navigationPosControl_t posControl; +EXTENDED_FASTRAM navSystemStatus_t NAV_Status; +EXTENDED_FASTRAM multicopterPosXyCoefficients_t multicopterPosXyCoefficients; #if defined(NAV_BLACKBOX) int16_t navCurrentState; @@ -3231,6 +3232,14 @@ void navigationUsePIDs(void) ); } + /* + * Set coefficients used in MC VEL_XY + */ + multicopterPosXyCoefficients.dTermAttenuation = pidProfile()->navVelXyDtermAttenuation / 100.0f; + multicopterPosXyCoefficients.dTermAttenuationStart = pidProfile()->navVelXyDtermAttenuationStart / 100.0f; + multicopterPosXyCoefficients.dTermAttenuationEnd = pidProfile()->navVelXyDtermAttenuationEnd / 100.0f; + multicopterPosXyCoefficients.breakingBoostFactor = (float) navConfig()->mc.braking_boost_factor / 100.0f; + // Initialize altitude hold PID-controllers (pos_z, vel_z, acc_z navPidInit( &posControl.pids.pos[Z], diff --git a/src/main/navigation/navigation_multicopter.c b/src/main/navigation/navigation_multicopter.c index 13eea54dfee..b0130f3a112 100755 --- a/src/main/navigation/navigation_multicopter.c +++ b/src/main/navigation/navigation_multicopter.c @@ -50,7 +50,6 @@ #include "navigation/navigation.h" #include "navigation/navigation_private.h" - /*----------------------------------------------------------- * Altitude controller for multicopter aircraft *-----------------------------------------------------------*/ @@ -470,11 +469,9 @@ static void updatePositionVelocityController_MC(const float maxSpeed) } static void updatePositionAccelController_MC(timeDelta_t deltaMicros, float maxAccelLimit, const float maxSpeed) -{ - +{ const float measurementX = navGetCurrentActualPositionAndVelocity()->vel.x; const float measurementY = navGetCurrentActualPositionAndVelocity()->vel.y; - const float measurementXY = sqrtf(powf(measurementX, 2)+powf(measurementY, 2)); const float setpointX = posControl.desiredState.vel.x; const float setpointY = posControl.desiredState.vel.y; @@ -522,26 +519,25 @@ static void updatePositionAccelController_MC(timeDelta_t deltaMicros, float maxA //Normalize the setpoint and measurement between 0.0f and 1.0f where 1.0f is currently used max speed const float setpointNormalized = constrainf(scaleRangef(fabsf(setpointXY), 0, maxSpeed, 0.0f, 1.0f), 0.0f, 1.0f); - const float measurementNormalized = constrainf(scaleRangef(fabsf(measurementXY), 0, maxSpeed, 0.0f, 1.0f), 0.0f, 1.0f); + const float measurementNormalized = constrainf(scaleRangef(fabsf(posControl.actualState.velXY), 0, maxSpeed, 0.0f, 1.0f), 0.0f, 1.0f); DEBUG_SET(DEBUG_ALWAYS, 0, setpointNormalized * 100); DEBUG_SET(DEBUG_ALWAYS, 1, measurementNormalized * 100); /* - * Map normalized speed of setpoint and measurement between 1.0f and nav_mc_vel_xy_dterm_dyn_scale - * 1.0f means that Dterm is not attenuated - * navVelXyDtermDynScale means full allowed attenuation - * * Dterm can be attenuated when both setpoint and measurement is high - UAV is moving close to desired velocity */ - const float setpointScale = constrainf(scaleRangef(setpointNormalized, pidProfile()->navVelXyDtermDynScaleMinAt, pidProfile()->navVelXyDtermDynScaleMaxAt, 1.0f, pidProfile()->navVelXyDtermDynScale), pidProfile()->navVelXyDtermDynScale, 1.0f); - const float measurementScale = constrainf(scaleRangef(measurementNormalized, pidProfile()->navVelXyDtermDynScaleMinAt, pidProfile()->navVelXyDtermDynScaleMaxAt, 1.0f, pidProfile()->navVelXyDtermDynScale), pidProfile()->navVelXyDtermDynScale, 1.0f); + float setpointScale = scaleRangef(setpointNormalized, multicopterPosXyCoefficients.dTermAttenuationStart, multicopterPosXyCoefficients.dTermAttenuationEnd, 0, multicopterPosXyCoefficients.dTermAttenuation); + setpointScale = constrainf(setpointScale, 0, multicopterPosXyCoefficients.dTermAttenuation); + + float measurementScale = scaleRangef(measurementNormalized, multicopterPosXyCoefficients.dTermAttenuationStart, multicopterPosXyCoefficients.dTermAttenuationEnd, 0, multicopterPosXyCoefficients.dTermAttenuation); + measurementScale = constrainf(measurementScale, 0, multicopterPosXyCoefficients.dTermAttenuation); DEBUG_SET(DEBUG_ALWAYS, 2, setpointScale * 100); DEBUG_SET(DEBUG_ALWAYS, 3, measurementScale * 100); - //Use the higher scaling factor from the two above - const float dtermScale = MAX(setpointScale, measurementScale); + //Choose smaller attenuation factor and convert from attenuation to scale + const float dtermScale = 1.0f - MIN(setpointScale, measurementScale); DEBUG_SET(DEBUG_ALWAYS, 4, dtermScale * 100); // Apply PID with output limiting and I-term anti-windup @@ -574,8 +570,7 @@ static void updatePositionAccelController_MC(timeDelta_t deltaMicros, float maxA #ifdef USE_MR_BRAKING_MODE //Boost required accelerations - if (STATE(NAV_CRUISE_BRAKING_BOOST) && navConfig()->mc.braking_boost_factor > 0) { - const float rawBoostFactor = (float)navConfig()->mc.braking_boost_factor / 100.0f; + if (STATE(NAV_CRUISE_BRAKING_BOOST) && multicopterPosXyCoefficients.breakingBoostFactor > 0.0f) { //Scale boost factor according to speed const float boostFactor = constrainf( @@ -584,10 +579,10 @@ static void updatePositionAccelController_MC(timeDelta_t deltaMicros, float maxA navConfig()->mc.braking_boost_speed_threshold, navConfig()->general.max_manual_speed, 0.0f, - rawBoostFactor + multicopterPosXyCoefficients.breakingBoostFactor ), 0.0f, - rawBoostFactor + multicopterPosXyCoefficients.breakingBoostFactor ); //Boost required acceleration for harder braking diff --git a/src/main/navigation/navigation_private.h b/src/main/navigation/navigation_private.h index f56048e8abf..e97d76311d5 100755 --- a/src/main/navigation/navigation_private.h +++ b/src/main/navigation/navigation_private.h @@ -363,11 +363,19 @@ typedef struct { float totalTripDistance; } navigationPosControl_t; +typedef struct { + float dTermAttenuation; + float dTermAttenuationStart; + float dTermAttenuationEnd; + float breakingBoostFactor; +} multicopterPosXyCoefficients_t; + #if defined(NAV_NON_VOLATILE_WAYPOINT_STORAGE) PG_DECLARE_ARRAY(navWaypoint_t, NAV_MAX_WAYPOINTS, nonVolatileWaypointList); #endif extern navigationPosControl_t posControl; +extern multicopterPosXyCoefficients_t multicopterPosXyCoefficients; /* Internally used functions */ const navEstimatedPosVel_t * navGetCurrentActualPositionAndVelocity(void); From f7961f3b0712590a5c77f35873ee28a53abdebea Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 9 Mar 2020 18:58:18 +0100 Subject: [PATCH 006/248] Move updatePIDCoefficients to a separate task --- src/main/fc/fc_core.c | 3 --- src/main/fc/fc_tasks.c | 13 +++++++++++++ src/main/flight/pid.c | 14 ++++++++------ src/main/flight/pid.h | 4 +++- src/main/scheduler/scheduler.h | 1 + 5 files changed, 25 insertions(+), 10 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 64329dbe174..c54f3319588 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -805,9 +805,6 @@ void taskMainPidLoop(timeUs_t currentTimeUs) // FIXME: throttle pitch comp for FW } - // Update PID coefficients - updatePIDCoefficients(dT); - // Calculate stabilisation pidController(dT); diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index e8ba6f432a5..a9151461014 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -269,12 +269,19 @@ void taskUpdateOsd(timeUs_t currentTimeUs) } #endif +void taskUpdateAux(timeUs_t currentTimeUs) +{ + UNUSED(currentTimeUs); + updatePIDCoefficients(); +} + void fcTasksInit(void) { schedulerInit(); rescheduleTask(TASK_GYROPID, getLooptime()); setTaskEnabled(TASK_GYROPID, true); + setTaskEnabled(TASK_AUX, true); setTaskEnabled(TASK_SERIAL, true); #ifdef BEEPER @@ -576,4 +583,10 @@ cfTask_t cfTasks[TASK_COUNT] = { .staticPriority = TASK_PRIORITY_LOW, }, #endif + [TASK_AUX] = { + .taskName = "AUX", + .taskFunc = taskUpdateAux, + .desiredPeriod = TASK_PERIOD_HZ(TASK_AUX_RATE_HZ), // 300Hz @3,33ms + .staticPriority = TASK_PRIORITY_HIGH, + }, }; diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 1fb455f3363..0ea8ebd8b73 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -56,6 +56,8 @@ #include "sensors/pitotmeter.h" #include "common/global_functions.h" +#include "scheduler/scheduler.h" + typedef struct { float kP; // Proportional gain float kI; // Integral gain @@ -337,7 +339,7 @@ bool pidInitFilters(void) } #ifdef USE_ANTIGRAVITY - pt1FilterInit(&antigravityThrottleLpf, pidProfile()->antigravityCutoff, refreshRate * 1e-6f); + pt1FilterInit(&antigravityThrottleLpf, pidProfile()->antigravityCutoff, TASK_PERIOD_HZ(TASK_AUX_RATE_HZ) * 1e-6f); #endif #ifdef USE_D_BOOST @@ -354,7 +356,7 @@ bool pidInitFilters(void) void pidResetTPAFilter(void) { if (usedPidControllerType == PID_TYPE_PIFF && currentControlRateProfile->throttle.fixedWingTauMs > 0) { - pt1FilterInitRC(&fixedWingTpaFilter, currentControlRateProfile->throttle.fixedWingTauMs * 1e-3f, getLooptime() * 1e-6f); + pt1FilterInitRC(&fixedWingTpaFilter, currentControlRateProfile->throttle.fixedWingTauMs * 1e-3f, TASK_PERIOD_HZ(TASK_AUX_RATE_HZ) * 1e-6f); pt1FilterReset(&fixedWingTpaFilter, getThrottleIdleValue()); } } @@ -446,13 +448,13 @@ void schedulePidGainsUpdate(void) pidGainsUpdateRequired = true; } -void FAST_CODE NOINLINE updatePIDCoefficients(float dT) +void updatePIDCoefficients() { STATIC_FASTRAM uint16_t prevThrottle = 0; // Check if throttle changed. Different logic for fixed wing vs multirotor if (usedPidControllerType == PID_TYPE_PIFF && (currentControlRateProfile->throttle.fixedWingTauMs > 0)) { - uint16_t filteredThrottle = pt1FilterApply3(&fixedWingTpaFilter, rcCommand[THROTTLE], dT); + uint16_t filteredThrottle = pt1FilterApply(&fixedWingTpaFilter, rcCommand[THROTTLE]); if (filteredThrottle != prevThrottle) { prevThrottle = filteredThrottle; pidGainsUpdateRequired = true; @@ -1040,8 +1042,6 @@ pidType_e pidIndexGetType(pidIndex_e pidIndex) void pidInit(void) { - pidResetTPAFilter(); - // Calculate max overall tilt (max pitch + max roll combined) as a limit to heading hold headingHoldCosZLimit = cos_approx(DECIDEGREES_TO_RADIANS(pidProfile()->max_angle_inclination[FD_ROLL])) * cos_approx(DECIDEGREES_TO_RADIANS(pidProfile()->max_angle_inclination[FD_PITCH])); @@ -1117,6 +1117,8 @@ void pidInit(void) } else { pidControllerApplyFn = nullRateController; } + + pidResetTPAFilter(); } const pidBank_t FAST_CODE NOINLINE * pidBank(void) { diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 8bc148e2be4..f0bf6964edd 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -53,6 +53,8 @@ FP-PID has been rescaled to match LuxFloat (and MWRewrite) from Cleanflight 1.13 #define ANTI_GRAVITY_THROTTLE_FILTER_CUTOFF 15 // The anti gravity throttle highpass filter cutoff +#define TASK_AUX_RATE_HZ 100 //In Hz + typedef enum { /* PID MC FW */ PID_ROLL, // + + @@ -180,7 +182,7 @@ struct motorConfig_s; struct rxConfig_s; void schedulePidGainsUpdate(void); -void updatePIDCoefficients(float dT); +void updatePIDCoefficients(void); void pidController(float dT); float pidRateToRcCommand(float rateDPS, uint8_t rate); diff --git a/src/main/scheduler/scheduler.h b/src/main/scheduler/scheduler.h index b9cf88bd212..2b7c3a243ce 100755 --- a/src/main/scheduler/scheduler.h +++ b/src/main/scheduler/scheduler.h @@ -119,6 +119,7 @@ typedef enum { #ifdef USE_RPM_FILTER TASK_RPM_FILTER, #endif + TASK_AUX, /* Count of real tasks */ TASK_COUNT, From 784ddc626342e4b35439ba6bebce775f6adf4f40 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 9 Mar 2020 19:03:34 +0100 Subject: [PATCH 007/248] Move computation of antigravity gain to TASK_AUX --- src/main/flight/pid.c | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 0ea8ebd8b73..fd3e3d19ecf 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -470,6 +470,7 @@ void updatePIDCoefficients() #ifdef USE_ANTIGRAVITY if (usedPidControllerType == PID_TYPE_PID) { antigravityThrottleHpf = rcCommand[THROTTLE] - pt1FilterApply(&antigravityThrottleLpf, rcCommand[THROTTLE]); + iTermAntigravityGain = scaleRangef(fabsf(antigravityThrottleHpf) * antigravityAccelerator, 0.0f, 1000.0f, 1.0f, antigravityGain); } #endif @@ -1009,10 +1010,6 @@ void FAST_CODE NOINLINE pidController(float dT) // Prevent strong Iterm accumulation during stick inputs antiWindupScaler = constrainf((1.0f - getMotorMixRange()) / motorItermWindupPoint, 0.0f, 1.0f); -#ifdef USE_ANTIGRAVITY - iTermAntigravityGain = scaleRangef(fabsf(antigravityThrottleHpf) * antigravityAccelerator, 0.0f, 1000.0f, 1.0f, antigravityGain); -#endif - for (int axis = 0; axis < 3; axis++) { // Apply setpoint rate of change limits pidApplySetpointRateLimiting(&pidState[axis], axis, dT); From 6aec1d7d924c4bfc623d7fcfad90577190e0a3c0 Mon Sep 17 00:00:00 2001 From: ShikOfTheRa Date: Thu, 7 May 2020 12:51:33 +0100 Subject: [PATCH 008/248] Update Building in Windows 10 with Linux Subsystem.md Added a bit more detail. --- ...ding in Windows 10 with Linux Subsystem.md | 56 +++++++++++++++---- 1 file changed, 46 insertions(+), 10 deletions(-) diff --git a/docs/development/Building in Windows 10 with Linux Subsystem.md b/docs/development/Building in Windows 10 with Linux Subsystem.md index 228c4787aa9..5ed64eb83fb 100644 --- a/docs/development/Building in Windows 10 with Linux Subsystem.md +++ b/docs/development/Building in Windows 10 with Linux Subsystem.md @@ -2,17 +2,53 @@ Linux subsystem for Windows 10 is probably the simplest way of building INAV under Windows 10. -1. Enable WSL (_Windows Subsystem for Linux) using any guide from internet. [This](https://winaero.com/blog/enable-wsl-windows-10-fall-creators-update/) is up to date step by step (January 2018) -1. From _Windows Store_ install `Ubuntu` -1. Start `Ubuntu` and run: -1. `sudo add-apt-repository ppa:team-gcc-arm-embedded/ppa` -1. `sudo apt-get update` -1. `sudo apt-get install gcc-arm-embedded make ruby` +## Setting up the environment -At the moment (January 2018) it will install `gcc-arm-none-eabi` in version _7 q4_ +Enable WSL: +run `windows features` +enable `windows subsytem for linux` +reboot -From this moment INAV can be build using the following command -`make TARGET={TARGET_NAME}` +Install Ubuntu: +1. Go to Microsoft store https://www.microsoft.com/en-gb/store/b/home +1. Search and install most recent Ubunto LTS version +1. When download completed, select `Launch Ubuntu` +1. When prompted enter a user name and password which you will need to remember +1. When complete, the linux command prompt will be displayed -Of course, replace `{TARGET_NAME}` with a target you want to compile \ No newline at end of file +NOTE: from this point all commands are entered into the Ubunto shell command window + +Update the repo packages: +1. `sudo apt update` + +Install Git, Make, gcc and Ruby +1. `sudo apt-get install git` +1. `sudo apt-get install make` +1. `sudo apt-get install gcc-arm-none-eabi` +1. `sudo apt-get install ruby` + +## Downloading the iNav repository (example): + +Mount MS windows C drive and clone iNav +1. `cd /mnt/c` +1. `git clone https://github.com/iNavFlight/inav.git` + +You are ready! +You now have a folder called inav in the root of C drive that you can edit in windows + + +## Building (example): + +Launch Ubuntu: +Click Windows Start button then scroll and lauch "Ubunto" + +Building from Ubunto command line +`cd /mnt/c/inav` +`make clean TARGET=OMNIBUSF4PRO` (as an example) +`make TARGET=MATEKF405` (as an example) + + +## Flashing: +Launch windows configurator GUI and from within the firmware flasher select `Load firmware[Local]` +Hex files can be found in the folder `c:\inav\obj` From 6976d464c8e866f316fb752ac1697eb6e85379a5 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sun, 10 May 2020 16:21:07 +0100 Subject: [PATCH 009/248] Removed Air from OSD mode display --- src/main/io/osd.c | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index a61947d4e3d..1e5fbe14bc6 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1655,8 +1655,6 @@ static bool osdDrawSingleElement(uint8_t item) p = "ANGL"; else if (FLIGHT_MODE(HORIZON_MODE)) p = "HOR "; - else if (STATE(AIRMODE_ACTIVE)) - p = "AIR "; displayWrite(osdDisplayPort, elemPosX, elemPosY, p); return true; From b8a5c661e5708f9851dd4e472c247466cbb0f990 Mon Sep 17 00:00:00 2001 From: LinJieqiang <517503838@qq.com> Date: Fri, 15 May 2020 09:19:02 +0800 Subject: [PATCH 010/248] [Target] Add IFLIGHT_SucceX_D board support. --- src/main/target/IFLIGHT_SucceX_D/target.c | 37 ++++++ src/main/target/IFLIGHT_SucceX_D/target.h | 148 +++++++++++++++++++++ src/main/target/IFLIGHT_SucceX_D/target.mk | 17 +++ 3 files changed, 202 insertions(+) create mode 100644 src/main/target/IFLIGHT_SucceX_D/target.c create mode 100644 src/main/target/IFLIGHT_SucceX_D/target.h create mode 100644 src/main/target/IFLIGHT_SucceX_D/target.mk diff --git a/src/main/target/IFLIGHT_SucceX_D/target.c b/src/main/target/IFLIGHT_SucceX_D/target.c new file mode 100644 index 00000000000..142812dd399 --- /dev/null +++ b/src/main/target/IFLIGHT_SucceX_D/target.c @@ -0,0 +1,37 @@ +/* +* This file is part of Cleanflight. +* +* Cleanflight is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* Cleanflight is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with Cleanflight. If not, see . +*/ + +#include +#include +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/pinio.h" + +const timerHardware_t timerHardware[] = { + DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), + + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MC_MOTOR, 0, 0), + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR, 0, 0), + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR, 0, 0), + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR, 0, 0), + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/IFLIGHT_SucceX_D/target.h b/src/main/target/IFLIGHT_SucceX_D/target.h new file mode 100644 index 00000000000..e47b9c76381 --- /dev/null +++ b/src/main/target/IFLIGHT_SucceX_D/target.h @@ -0,0 +1,148 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "IFSD" +#define USBD_PRODUCT_STRING "IFLIGHT_SucceX_D" + +#define LED0 PC13 +#define LED1 PC14 + +#define BEEPER PB2 +#define BEEPER_INVERTED + +// *************** SPI1 Gyro & ACC ********************** +#define USE_SPI +#define USE_SPI_DEVICE_1 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW180_DEG +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_BUS BUS_SPI1 + +#define USE_EXTI +#define GYRO_INT_EXTI PA1 +#define USE_MPU_DATA_READY_SIGNAL + +// *************** SPI2 OSD ***************************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_OSD +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +// *************** SPI3 FLASH ************************** +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +#define M25P16_CS_PIN PA15 +#define M25P16_SPI_BUS BUS_SPI3 + +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +// *************** UART ***************************** +#define USE_VCP +#define VBUS_SENSING_PIN PC15 +#define VBUS_SENSING_ENABLED + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define SERIAL_PORT_COUNT 3 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART2 + +// *************** I2C /Baro/Mag/Pitot ******************** +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#define DEFAULT_I2C_BUS BUS_I2C1 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_BMP085 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL +#define USE_MAG_AK8975 + +#define PITOT_I2C_BUS BUS_I2C1 +#define TEMPERATURE_I2C_BUS BUS_I2C1 + +#define USE_RANGEFINDER +#define USE_RANGEFINDER_MSP +#define USE_RANGEFINDER_HCSR04_I2C +#define RANGEFINDER_I2C_BUS BUS_I2C1 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 + +#define ADC_CHANNEL_1_PIN PB0 +#define ADC_CHANNEL_2_PIN PB1 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 + +// *************** LED2812 ************************ +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +// *************** OTHERS ************************* +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_BLACKBOX) + +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) + +#define MAX_PWM_OUTPUT_PORTS 4 diff --git a/src/main/target/IFLIGHT_SucceX_D/target.mk b/src/main/target/IFLIGHT_SucceX_D/target.mk new file mode 100644 index 00000000000..ff3c58d4a0f --- /dev/null +++ b/src/main/target/IFLIGHT_SucceX_D/target.mk @@ -0,0 +1,17 @@ +F411_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH MSC + +TARGET_SRC = \ + drivers/accgyro/accgyro_mpu6000.c \ + drivers/barometer/barometer_bmp085.c \ + drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_ms56xx.c \ + drivers/compass/compass_hmc5883l.c \ + drivers/compass/compass_mag3110.c \ + drivers/compass/compass_qmc5883l.c \ + drivers/compass/compass_ist8310.c \ + drivers/compass/compass_ist8308.c \ + drivers/compass/compass_lis3mdl.c \ + drivers/compass/compass_ak8975.c \ + drivers/light_ws2811strip.c \ + drivers/max7456.c From 83c9346607e7efa2d0403a282cbc340b8ca03a10 Mon Sep 17 00:00:00 2001 From: "Miguel.Alvarez" Date: Mon, 13 Jan 2020 17:21:53 -0600 Subject: [PATCH 011/248] Added functions to retrieve the UART Idle state --- src/main/drivers/serial.c | 8 ++++++++ src/main/drivers/serial.h | 3 +++ src/main/drivers/serial_softserial.c | 3 ++- src/main/drivers/serial_uart.c | 12 ++++++++++++ src/main/drivers/serial_uart.h | 1 + src/main/drivers/serial_uart_hal.c | 12 ++++++++++++ src/main/drivers/serial_uart_stm32f30x.c | 5 +++++ src/main/drivers/serial_uart_stm32f4xx.c | 6 ++++++ src/main/drivers/serial_usb_vcp.c | 3 ++- 9 files changed, 51 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/serial.c b/src/main/drivers/serial.c index 696e464512a..165f9c31698 100644 --- a/src/main/drivers/serial.c +++ b/src/main/drivers/serial.c @@ -111,3 +111,11 @@ bool serialIsConnected(const serialPort_t *instance) // If API is not defined - assume connected return true; } + +bool serialIsIdle(serialPort_t *instance) +{ + if (instance->vTable->isIdle) + return instance->vTable->isIdle(instance); + else + return false; +} diff --git a/src/main/drivers/serial.h b/src/main/drivers/serial.h index b61c5877d59..c908fd0c035 100644 --- a/src/main/drivers/serial.h +++ b/src/main/drivers/serial.h @@ -95,6 +95,8 @@ struct serialPortVTable { bool (*isConnected)(const serialPort_t *instance); + bool (*isIdle)(serialPort_t *instance); + // Optional functions used to buffer large writes. void (*beginWrite)(serialPort_t *instance); void (*endWrite)(serialPort_t *instance); @@ -111,6 +113,7 @@ bool isSerialTransmitBufferEmpty(const serialPort_t *instance); void serialPrint(serialPort_t *instance, const char *str); uint32_t serialGetBaudRate(serialPort_t *instance); bool serialIsConnected(const serialPort_t *instance); +bool serialIsIdle(serialPort_t *instance); // A shim that adapts the bufWriter API to the serialWriteBuf() API. void serialWriteBufShim(void *instance, const uint8_t *data, int count); diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index ddee3e8808e..fd860ad26c7 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -628,7 +628,8 @@ static const struct serialPortVTable softSerialVTable = { .isConnected = NULL, .writeBuf = NULL, .beginWrite = NULL, - .endWrite = NULL + .endWrite = NULL, + .isIdle = NULL, }; #endif diff --git a/src/main/drivers/serial_uart.c b/src/main/drivers/serial_uart.c index 02becdcea51..e670c2a1367 100644 --- a/src/main/drivers/serial_uart.c +++ b/src/main/drivers/serial_uart.c @@ -247,6 +247,17 @@ void uartWrite(serialPort_t *instance, uint8_t ch) USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE); } +bool isUartIdle(serialPort_t *instance) +{ + uartPort_t *s = (uartPort_t *)instance; + if(USART_GetFlagStatus(s->USARTx, USART_FLAG_IDLE)) { + uartClearIdleFlag(s); + return true; + } else { + return false; + } +} + const struct serialPortVTable uartVTable[] = { { .serialWrite = uartWrite, @@ -260,5 +271,6 @@ const struct serialPortVTable uartVTable[] = { .writeBuf = NULL, .beginWrite = NULL, .endWrite = NULL, + .isIdle = isUartIdle, } }; diff --git a/src/main/drivers/serial_uart.h b/src/main/drivers/serial_uart.h index 70690ae99d6..75d04a6d69a 100644 --- a/src/main/drivers/serial_uart.h +++ b/src/main/drivers/serial_uart.h @@ -64,6 +64,7 @@ typedef struct { } uartPort_t; void uartGetPortPins(UARTDevice_e device, serialPortPins_t * pins); +void uartClearIdleFlag(uartPort_t *s); serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_t mode, portOptions_t options); // serialPort API diff --git a/src/main/drivers/serial_uart_hal.c b/src/main/drivers/serial_uart_hal.c index b14f984ef89..4454cde61a5 100644 --- a/src/main/drivers/serial_uart_hal.c +++ b/src/main/drivers/serial_uart_hal.c @@ -246,6 +246,17 @@ void uartWrite(serialPort_t *instance, uint8_t ch) __HAL_UART_ENABLE_IT(&s->Handle, UART_IT_TXE); } +bool isUartIdle(serialPort_t *instance) +{ + uartPort_t *s = (uartPort_t *)instance; + if(__HAL_UART_GET_FLAG(&s->Handle, UART_FLAG_IDLE)) { + __HAL_UART_CLEAR_IDLEFLAG(&s->Handle); + return true; + } else { + return false; + } +} + const struct serialPortVTable uartVTable[] = { { .serialWrite = uartWrite, @@ -259,5 +270,6 @@ const struct serialPortVTable uartVTable[] = { .writeBuf = NULL, .beginWrite = NULL, .endWrite = NULL, + .isIdle = isUartIdle, } }; diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c index b8d79fd2149..d65ebea646e 100644 --- a/src/main/drivers/serial_uart_stm32f30x.c +++ b/src/main/drivers/serial_uart_stm32f30x.c @@ -371,6 +371,11 @@ void usartIrqHandler(uartPort_t *s) } } +void uartClearIdleFlag(uartPort_t *s) +{ + USART_ClearITPendingBit(s->USARTx, USART_IT_IDLE); +} + #ifdef USE_UART1 void USART1_IRQHandler(void) { diff --git a/src/main/drivers/serial_uart_stm32f4xx.c b/src/main/drivers/serial_uart_stm32f4xx.c index dc9f0ddc502..2c47baa0392 100644 --- a/src/main/drivers/serial_uart_stm32f4xx.c +++ b/src/main/drivers/serial_uart_stm32f4xx.c @@ -253,6 +253,12 @@ void uartGetPortPins(UARTDevice_e device, serialPortPins_t * pins) } } +void uartClearIdleFlag(uartPort_t *s) +{ + (void) s->USARTx->SR; + (void) s->USARTx->DR; +} + uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c index 452941386b3..f32a8be24f5 100644 --- a/src/main/drivers/serial_usb_vcp.c +++ b/src/main/drivers/serial_usb_vcp.c @@ -187,7 +187,8 @@ static const struct serialPortVTable usbVTable[] = { .isConnected = usbVcpIsConnected, .writeBuf = usbVcpWriteBuf, .beginWrite = usbVcpBeginWrite, - .endWrite = usbVcpEndWrite + .endWrite = usbVcpEndWrite, + .isIdle = NULL, } }; From 91775e03998dab5618fa87d524650826413616d0 Mon Sep 17 00:00:00 2001 From: marbalon Date: Sun, 31 May 2020 17:12:19 +0200 Subject: [PATCH 012/248] Extended telemetry for radar and pos hold --- src/main/rx/eleres.c | 78 +++++++++++++++++++++++++++++++++++++++++++- 1 file changed, 77 insertions(+), 1 deletion(-) diff --git a/src/main/rx/eleres.c b/src/main/rx/eleres.c index c4a8b90b17a..638818c5315 100755 --- a/src/main/rx/eleres.c +++ b/src/main/rx/eleres.c @@ -97,6 +97,24 @@ static uint8_t rfRxBuffer[DATA_PACKAGE_SIZE]; static uint8_t txFull = 0; static uint8_t statusRegisters[2]; static uint8_t *eleresSignaturePtr; +static uint32_t lastIrqTime = 0; + +typedef struct { + uint8_t idx; + int32_t lat; // lat 10E7 + int32_t lon; // lon 10E7 + int32_t alt; // altitude (cm) + uint16_t heading; // � + uint16_t speed; //cm/s + uint8_t lq; // Link quality, from 0 to 4 +}__attribute__((packed)) eleres_radar_packet_t; + +typedef struct { + uint8_t idx; + int32_t lat; // lat 10E7 + int32_t lon; // lon 10E7 + int32_t alt; // altitude (cm) +}__attribute__((packed)) eleres_wp_packet_t; static uint8_t rfmSpiRead(uint8_t address) { @@ -381,6 +399,7 @@ rx_spi_received_e eleresDataReceived(uint8_t *payload, uint16_t *linkQuality) if (rxSpiCheckIrq()) { + lastIrqTime = millis(); statusRegisters[0] = rfmSpiRead(0x03); statusRegisters[1] = rfmSpiRead(0x04); //only if RC frame received @@ -424,6 +443,49 @@ static void parseStatusRegister(const uint8_t *payload) channelHoppingTime = (rfRxBuffer[20] & 0x0F)+18; dataReady |= DATA_FLAG; + } else if ((rfRxBuffer[0] & 127) == 'R') { //radar poi info + eleres_radar_packet_t p; + uint8_t idx=0; + + firstRun = 0; + goodFrames++; + + if ((rfRxBuffer[21] & 0xF0) == 0x20) + hoppingChannel = rfRxBuffer[21] & 0x0F; + channelHoppingTime = (rfRxBuffer[20] & 0x0F)+18; + + //parse plane info + memcpy(&p, &rfRxBuffer[1], sizeof(p)); + idx = MIN(p.idx, RADAR_MAX_POIS - 1); // Radar poi number, 0 to 3 + radar_pois[idx].gps.lat = p.lat; + radar_pois[idx].gps.lon = p.lon; + radar_pois[idx].gps.alt = p.alt; + radar_pois[idx].heading = p.heading; + radar_pois[idx].speed = p.speed; + radar_pois[idx].lq = p.lq; + if (p.lat == 0 || p.lon == 0) + radar_pois[idx].state = 0; + else + radar_pois[idx].state = 1; + } else if ((rfRxBuffer[0] & 127) == 'W') { //WP info + eleres_wp_packet_t p; + navWaypoint_t tp; //targetPoint + + firstRun = 0; + goodFrames++; + + if ((rfRxBuffer[21] & 0xF0) == 0x20) + hoppingChannel = rfRxBuffer[21] & 0x0F; + channelHoppingTime = (rfRxBuffer[20] & 0x0F)+18; + + //parse plane info + memcpy(&p, &rfRxBuffer[1], sizeof(p)); + + tp.action = NAV_WP_ACTION_WAYPOINT; + tp.alt = p.alt; + tp.lat = p.lat; + tp.lon = p.lon; + setWaypoint(p.idx, &tp); } else if (eleresConfig()->eleresLocEn && eleresConfig()->eleresTelemetryEn && bkgLocEnable==2) { if ((rfRxBuffer[0] == 'H' && rfRxBuffer[2] == 'L') || rfRxBuffer[0]=='T' || rfRxBuffer[0]=='P' || rfRxBuffer[0]=='G') { @@ -498,6 +560,20 @@ void eleresSetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload) else led_time = cr_time; + //watch IRQ - if not received, restart RFM + if (eleresConfig()->eleresTelemetryEn && millis() - lastIrqTime > 2000) + { + if (lastIrqTime < 4000) + { + rfmSpiWrite(0x07, 0x80); //restart rfm22 in case of problems only at startup + delay(1); + } + + rfm22bInitParameter(); + toRxMode(); + lastIrqTime = millis(); + } + if ((dataReady & LOCALIZER_FLAG) == 0) { if (cr_time > nextPackTime+2) { if ((cr_time-lastPackTime > 1500) || firstRun) { @@ -699,7 +775,7 @@ void eleresInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) rfmSpiWrite(0x07, 0x80); delay(100); - eleresSignaturePtr = (uint8_t*)&eleresConfigMutable()->eleresSignature; + eleresSignaturePtr = (uint8_t*)&eleresConfig()->eleresSignature; rfm22bInitParameter(); bindChannels(eleresSignaturePtr,holList); From fe7a429992ebf7bf827aebc013c676eb9700dcbc Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Sun, 7 Jun 2020 15:15:24 +0200 Subject: [PATCH 013/248] Bump version to 2.6.0 --- src/main/build/version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/build/version.h b/src/main/build/version.h index bc3988d8418..7946ad85e91 100644 --- a/src/main/build/version.h +++ b/src/main/build/version.h @@ -16,7 +16,7 @@ */ #define FC_VERSION_MAJOR 2 // increment when a major release is made (big new feature, etc) -#define FC_VERSION_MINOR 5 // increment when a minor release is made (small new feature, change etc) +#define FC_VERSION_MINOR 6 // increment when a minor release is made (small new feature, change etc) #define FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed #define STR_HELPER(x) #x From 2c6ae039053ecfbcff91f24e84b08e57ae1bce06 Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Mon, 8 Jun 2020 09:03:59 +0200 Subject: [PATCH 014/248] [VTX] Always process VTX driver updates, regardless of arming state --- src/main/io/vtx.c | 63 ++++++++++++++++++++++++----------------------- 1 file changed, 32 insertions(+), 31 deletions(-) diff --git a/src/main/io/vtx.c b/src/main/io/vtx.c index 972162264c4..6a2fffa66ca 100644 --- a/src/main/io/vtx.c +++ b/src/main/io/vtx.c @@ -86,29 +86,30 @@ static vtxSettingsConfig_t * vtxGetRuntimeSettings(void) static bool vtxProcessBandAndChannel(vtxDevice_t *vtxDevice, const vtxSettingsConfig_t * runtimeSettings) { + uint8_t vtxBand; + uint8_t vtxChan; + // Shortcut for undefined band if (!runtimeSettings->band) { return false; } - if(!ARMING_FLAG(ARMED) && runtimeSettings->band) { - uint8_t vtxBand; - uint8_t vtxChan; - if (!vtxCommonGetBandAndChannel(vtxDevice, &vtxBand, &vtxChan)) { - return false; - } + if (!vtxCommonGetBandAndChannel(vtxDevice, &vtxBand, &vtxChan)) { + return false; + } - if (vtxBand != runtimeSettings->band || vtxChan != runtimeSettings->channel) { - vtxCommonSetBandAndChannel(vtxDevice, runtimeSettings->band, runtimeSettings->channel); - return true; - } + if (vtxBand != runtimeSettings->band || vtxChan != runtimeSettings->channel) { + vtxCommonSetBandAndChannel(vtxDevice, runtimeSettings->band, runtimeSettings->channel); + return true; } + return false; } static bool vtxProcessPower(vtxDevice_t *vtxDevice, const vtxSettingsConfig_t * runtimeSettings) { uint8_t vtxPower; + if (!vtxCommonGetPowerIndex(vtxDevice, &vtxPower)) { return false; } @@ -117,6 +118,7 @@ static bool vtxProcessPower(vtxDevice_t *vtxDevice, const vtxSettingsConfig_t * vtxCommonSetPowerByIndex(vtxDevice, runtimeSettings->power); return true; } + return false; } @@ -129,25 +131,28 @@ static bool vtxProcessPitMode(vtxDevice_t *vtxDevice, const vtxSettingsConfig_t bool currPmSwitchState = false; static bool prevPmSwitchState = false; - if (!ARMING_FLAG(ARMED) && vtxCommonGetPitMode(vtxDevice, &pitOnOff)) { - if (currPmSwitchState != prevPmSwitchState) { - prevPmSwitchState = currPmSwitchState; + if (!vtxCommonGetPitMode(vtxDevice, &pitOnOff)) { + return false; + } - if (currPmSwitchState) { - if (0) { - if (!pitOnOff) { - vtxCommonSetPitMode(vtxDevice, true); - return true; - } - } - } else { - if (pitOnOff) { - vtxCommonSetPitMode(vtxDevice, false); + if (currPmSwitchState != prevPmSwitchState) { + prevPmSwitchState = currPmSwitchState; + + if (currPmSwitchState) { + if (0) { + if (!pitOnOff) { + vtxCommonSetPitMode(vtxDevice, true); return true; } } + } else { + if (pitOnOff) { + vtxCommonSetPitMode(vtxDevice, false); + return true; + } } } + return false; } @@ -167,25 +172,21 @@ void vtxUpdate(timeUs_t currentTimeUs) // Build runtime settings const vtxSettingsConfig_t * runtimeSettings = vtxGetRuntimeSettings(); - bool vtxUpdatePending = false; - switch (currentSchedule) { case VTX_PARAM_POWER: - vtxUpdatePending = vtxProcessPower(vtxDevice, runtimeSettings); + vtxProcessPower(vtxDevice, runtimeSettings); break; case VTX_PARAM_BANDCHAN: - vtxUpdatePending = vtxProcessBandAndChannel(vtxDevice, runtimeSettings); + vtxProcessBandAndChannel(vtxDevice, runtimeSettings); break; case VTX_PARAM_PITMODE: - vtxUpdatePending = vtxProcessPitMode(vtxDevice, runtimeSettings); + vtxProcessPitMode(vtxDevice, runtimeSettings); break; default: break; } - if (!ARMING_FLAG(ARMED) || vtxUpdatePending) { - vtxCommonProcess(vtxDevice, currentTimeUs); - } + vtxCommonProcess(vtxDevice, currentTimeUs); currentSchedule = (currentSchedule + 1) % VTX_PARAM_COUNT; } From 008720eb0a5bdfd2d854cf6c1f7890040a746ab9 Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Mon, 8 Jun 2020 09:07:02 +0200 Subject: [PATCH 015/248] Version bump to 2.5.1 --- src/main/build/version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/build/version.h b/src/main/build/version.h index bc3988d8418..dc1d10f6421 100644 --- a/src/main/build/version.h +++ b/src/main/build/version.h @@ -17,7 +17,7 @@ #define FC_VERSION_MAJOR 2 // increment when a major release is made (big new feature, etc) #define FC_VERSION_MINOR 5 // increment when a minor release is made (small new feature, change etc) -#define FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed +#define FC_VERSION_PATCH_LEVEL 1 // increment when a bug is fixed #define STR_HELPER(x) #x #define STR(x) STR_HELPER(x) From 51e3e1127c6556f75b18547f357b260e18cb59b7 Mon Sep 17 00:00:00 2001 From: giacomo892 Date: Mon, 8 Jun 2020 08:09:43 +0200 Subject: [PATCH 016/248] fix esc sensor --- src/main/fc/fc_init.c | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index 6f7f0b9b6eb..ac4656bcac3 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -275,12 +275,6 @@ void init(void) // to run after the sensors have been detected. mspSerialInit(); -#ifdef USE_ESC_SENSOR - // DSHOT supports a dedicated wire ESC telemetry. Kick off the ESC-sensor receiver initialization - // We may, however, do listen_only, so need to init this anyway - escSensorInitialize(); -#endif - #if defined(USE_DJI_HD_OSD) // DJI OSD uses a special flavour of MSP (subset of Betaflight 4.1.1 MSP) - process as part of serial task djiOsdSerialInit(); @@ -320,6 +314,13 @@ void init(void) systemState |= SYSTEM_STATE_MOTORS_READY; +#ifdef USE_ESC_SENSOR + // DSHOT supports a dedicated wire ESC telemetry. Kick off the ESC-sensor receiver initialization + // We may, however, do listen_only, so need to init this anyway + // Initialize escSensor after having done it with outputs + escSensorInitialize(); +#endif + #ifdef BEEPER beeperDevConfig_t beeperDevConfig = { .ioTag = IO_TAG(BEEPER), From 8eae2a9d0f0c96acb9deda024c5adb75e187aa1b Mon Sep 17 00:00:00 2001 From: Konstantin Sharlaimov Date: Mon, 8 Jun 2020 13:01:18 +0200 Subject: [PATCH 017/248] Update development docs along with deprecation of `development` branch. --- docs/development/Development.md | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/docs/development/Development.md b/docs/development/Development.md index d8fe91f6f47..d18519490fb 100755 --- a/docs/development/Development.md +++ b/docs/development/Development.md @@ -77,24 +77,24 @@ The main flow for a contributing is as follows: 1. Login to github, go to the INAV repository and press `fork`. 2. Then using the command line/terminal on your computer: `git clone ` 3. `cd inav` -4. `git checkout development` +4. `git checkout master` 5. `git checkout -b my-new-code` 6. Make changes 7. `git add ` 8. `git commit` 9. `git push origin my-new-code` -10. Create pull request using github UI to merge your changes from your new branch into `inav/development` +10. Create pull request using github UI to merge your changes from your new branch into `inav/master` 11. Repeat from step 4 for new other changes. -The primary thing to remember is that separate pull requests should be created for separate branches. Never create a pull request from your `development` branch. +The primary thing to remember is that separate pull requests should be created for separate branches. Never create a pull request from your `master` branch. -Later, you can get the changes from the INAV repo into your `development` branch by adding INAV as a git remote and merging from it as follows: +Later, you can get the changes from the INAV repo into your `master` branch by adding INAV as a git remote and merging from it as follows: 1. `git remote add upstream https://github.com/iNavFlight/inav.git` -2. `git checkout development` +2. `git checkout master` 3. `git fetch upstream` -4. `git merge upstream/development` -5. `git push origin development` is an optional step that will update your fork on github +4. `git merge upstream/master` +5. `git push origin master` is an optional step that will update your fork on github You can also perform the git commands using the git client inside Eclipse. Refer to the Eclipse git manual. From 310883f3abb95d394ff25e643de0a342b15e4bcd Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Mon, 8 Jun 2020 13:57:34 +0200 Subject: [PATCH 018/248] Outline the release/development process --- docs/development/Development.md | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/docs/development/Development.md b/docs/development/Development.md index d18519490fb..9be10a3da47 100755 --- a/docs/development/Development.md +++ b/docs/development/Development.md @@ -98,3 +98,13 @@ Later, you can get the changes from the INAV repo into your `master` branch by a You can also perform the git commands using the git client inside Eclipse. Refer to the Eclipse git manual. + +## Branching and release workflow + +Normally, all development occurs on the `master` branch. Every release will have it's own branch named `release_x.y.z`. + +During release candidate cycle we will follow the process outlined below: + +1. Create a release branch `release_x.y.z` +2. All bug fixes found in the release candidates will be merged into `release_x.y.z` branch and not into the `master`. +3. After final release is made, the branch `release_x.y.z` is locked, and merged into `master` bringing all of the bug fixes into the development branch. Merge conflicts that may arise at this stage are resolved manually. From 6c4afd8486438879dea272a78813e83220d9ac35 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Pawe=C5=82=20Spychalski?= Date: Mon, 8 Jun 2020 16:10:24 +0200 Subject: [PATCH 019/248] Drop gyro Noth 1 (#5736) --- src/main/blackbox/blackbox.c | 8 ++++---- src/main/fc/config.c | 7 ++----- src/main/fc/fc_msp.c | 17 ++++++++--------- src/main/fc/settings.yaml | 15 ++++----------- src/main/io/osd_dji_hd.c | 8 ++++---- src/main/sensors/gyro.c | 26 +++++--------------------- src/main/sensors/gyro.h | 6 ++---- src/main/target/FALCORE/config.c | 4 ++-- 8 files changed, 31 insertions(+), 60 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index d023e9c2877..d445561290e 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1728,10 +1728,10 @@ static bool blackboxWriteSysinfo(void) BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchRange", "%d", gyroConfig()->dynamicGyroNotchRange); BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchQ", "%d", gyroConfig()->dynamicGyroNotchQ); BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchMinHz", "%d", gyroConfig()->dynamicGyroNotchMinHz); - BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz", "%d,%d", gyroConfig()->gyro_soft_notch_hz_1, - gyroConfig()->gyro_soft_notch_hz_2); - BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff", "%d,%d", gyroConfig()->gyro_soft_notch_cutoff_1, - gyroConfig()->gyro_soft_notch_cutoff_2); + BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz", "%d,%d", gyroConfig()->gyro_notch_hz, + 0); + BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff", "%d,%d", gyroConfig()->gyro_notch_cutoff, + 1); BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz", "%d", accelerometerConfig()->acc_lpf_hz); BLACKBOX_PRINT_HEADER_LINE("acc_hardware", "%d", accelerometerConfig()->acc_hardware); BLACKBOX_PRINT_HEADER_LINE("baro_hardware", "%d", barometerConfig()->baro_hardware); diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 20b08e5ca2d..8178417ec42 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -167,11 +167,8 @@ uint32_t getLooptime(void) { void validateAndFixConfig(void) { - if (gyroConfig()->gyro_soft_notch_cutoff_1 >= gyroConfig()->gyro_soft_notch_hz_1) { - gyroConfigMutable()->gyro_soft_notch_hz_1 = 0; - } - if (gyroConfig()->gyro_soft_notch_cutoff_2 >= gyroConfig()->gyro_soft_notch_hz_2) { - gyroConfigMutable()->gyro_soft_notch_hz_2 = 0; + if (gyroConfig()->gyro_notch_cutoff >= gyroConfig()->gyro_notch_hz) { + gyroConfigMutable()->gyro_notch_hz = 0; } if (pidProfile()->dterm_soft_notch_cutoff >= pidProfile()->dterm_soft_notch_hz) { pidProfileMutable()->dterm_soft_notch_hz = 0; diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 36427cc0957..d3482616945 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -1155,14 +1155,13 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU8(dst, gyroConfig()->gyro_soft_lpf_hz); sbufWriteU16(dst, pidProfile()->dterm_lpf_hz); sbufWriteU16(dst, pidProfile()->yaw_lpf_hz); - sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_hz_1); //masterConfig.gyro_soft_notch_hz_1 - sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_cutoff_1); //BF: masterConfig.gyro_soft_notch_cutoff_1 - + sbufWriteU16(dst, gyroConfig()->gyro_notch_hz); + sbufWriteU16(dst, gyroConfig()->gyro_notch_cutoff); sbufWriteU16(dst, pidProfile()->dterm_soft_notch_hz); //BF: pidProfile()->dterm_notch_hz sbufWriteU16(dst, pidProfile()->dterm_soft_notch_cutoff); //pidProfile()->dterm_notch_cutoff - sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_hz_2); //BF: masterConfig.gyro_soft_notch_hz_2 - sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_cutoff_2); //BF: masterConfig.gyro_soft_notch_cutoff_2 + sbufWriteU16(dst, 0); //BF: masterConfig.gyro_soft_notch_hz_2 + sbufWriteU16(dst, 1); //BF: masterConfig.gyro_soft_notch_cutoff_2 sbufWriteU16(dst, accelerometerConfig()->acc_notch_hz); sbufWriteU16(dst, accelerometerConfig()->acc_notch_cutoff); @@ -2039,8 +2038,8 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) pidProfileMutable()->dterm_lpf_hz = constrain(sbufReadU16(src), 0, 500); pidProfileMutable()->yaw_lpf_hz = constrain(sbufReadU16(src), 0, 255); if (dataSize >= 9) { - gyroConfigMutable()->gyro_soft_notch_hz_1 = constrain(sbufReadU16(src), 0, 500); - gyroConfigMutable()->gyro_soft_notch_cutoff_1 = constrain(sbufReadU16(src), 1, 500); + gyroConfigMutable()->gyro_notch_hz = constrain(sbufReadU16(src), 0, 500); + gyroConfigMutable()->gyro_notch_cutoff = constrain(sbufReadU16(src), 1, 500); } else { return MSP_RESULT_ERROR; } @@ -2052,8 +2051,8 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) return MSP_RESULT_ERROR; } if (dataSize >= 17) { - gyroConfigMutable()->gyro_soft_notch_hz_2 = constrain(sbufReadU16(src), 0, 500); - gyroConfigMutable()->gyro_soft_notch_cutoff_2 = constrain(sbufReadU16(src), 1, 500); + sbufReadU16(src); // Was gyroConfigMutable()->gyro_soft_notch_hz_2 + sbufReadU16(src); // Was gyroConfigMutable()->gyro_soft_notch_cutoff_2 } else { return MSP_RESULT_ERROR; } diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 9f5880120b4..540dd26006e 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -171,18 +171,11 @@ groups: - name: moron_threshold field: gyroMovementCalibrationThreshold max: 128 - - name: gyro_notch1_hz - field: gyro_soft_notch_hz_1 + - name: gyro_notch_hz + field: gyro_notch_hz max: 500 - - name: gyro_notch1_cutoff - field: gyro_soft_notch_cutoff_1 - min: 1 - max: 500 - - name: gyro_notch2_hz - field: gyro_soft_notch_hz_2 - max: 500 - - name: gyro_notch2_cutoff - field: gyro_soft_notch_cutoff_2 + - name: gyro_notch_cutoff + field: gyro_notch_cutoff min: 1 max: 500 - name: gyro_stage2_lowpass_hz diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index f8f2dd8b0a9..6d0167202b5 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -566,12 +566,12 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms sbufWriteU8(dst, gyroConfig()->gyro_soft_lpf_hz); // BF: gyroConfig()->gyro_lowpass_hz sbufWriteU16(dst, pidProfile()->dterm_lpf_hz); // BF: currentPidProfile->dterm_lowpass_hz sbufWriteU16(dst, pidProfile()->yaw_lpf_hz); // BF: currentPidProfile->yaw_lowpass_hz - sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_hz_1); // BF: gyroConfig()->gyro_soft_notch_hz_1 - sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_cutoff_1); // BF: gyroConfig()->gyro_soft_notch_cutoff_1 + sbufWriteU16(dst, gyroConfig()->gyro_notch_hz); // BF: gyroConfig()->gyro_soft_notch_hz_1 + sbufWriteU16(dst, gyroConfig()->gyro_notch_cutoff); // BF: gyroConfig()->gyro_soft_notch_cutoff_1 sbufWriteU16(dst, pidProfile()->dterm_soft_notch_hz); // BF: currentPidProfile->dterm_notch_hz sbufWriteU16(dst, pidProfile()->dterm_soft_notch_cutoff); // BF: currentPidProfile->dterm_notch_cutoff - sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_hz_2); // BF: gyroConfig()->gyro_soft_notch_hz_2 - sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_cutoff_2); // BF: gyroConfig()->gyro_soft_notch_cutoff_2 + sbufWriteU16(dst, 0); // BF: gyroConfig()->gyro_soft_notch_hz_2 + sbufWriteU16(dst, 1); // BF: gyroConfig()->gyro_soft_notch_cutoff_2 sbufWriteU8(dst, 0); // BF: currentPidProfile->dterm_filter_type sbufWriteU8(dst, gyroConfig()->gyro_lpf); // BF: gyroConfig()->gyro_hardware_lpf); sbufWriteU8(dst, 0); // BF: DEPRECATED: gyro_32khz_hardware_lpf diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 5849833f296..bd6b43db1c6 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -93,8 +93,6 @@ STATIC_FASTRAM filter_t gyroLpf2State[XYZ_AXIS_COUNT]; STATIC_FASTRAM filterApplyFnPtr notchFilter1ApplyFn; STATIC_FASTRAM void *notchFilter1[XYZ_AXIS_COUNT]; -STATIC_FASTRAM filterApplyFnPtr notchFilter2ApplyFn; -STATIC_FASTRAM void *notchFilter2[XYZ_AXIS_COUNT]; #ifdef USE_DYNAMIC_FILTERS @@ -103,7 +101,7 @@ EXTENDED_FASTRAM dynamicGyroNotchState_t dynamicGyroNotchState; #endif -PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 8); +PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 9); PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .gyro_lpf = GYRO_LPF_42HZ, // 42HZ value is defined for Invensense/TDK gyros @@ -114,10 +112,8 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .looptime = 1000, .gyroSync = 1, .gyro_to_use = 0, - .gyro_soft_notch_hz_1 = 0, - .gyro_soft_notch_cutoff_1 = 1, - .gyro_soft_notch_hz_2 = 0, - .gyro_soft_notch_cutoff_2 = 1, + .gyro_notch_hz = 0, + .gyro_notch_cutoff = 1, .gyro_stage2_lowpass_hz = 0, .gyro_stage2_lowpass_type = FILTER_BIQUAD, .dynamicGyroNotchRange = DYN_NOTCH_RANGE_MEDIUM, @@ -259,25 +255,14 @@ static void gyroInitFilters(void) STATIC_FASTRAM biquadFilter_t gyroFilterNotch_1[XYZ_AXIS_COUNT]; notchFilter1ApplyFn = nullFilterApply; - STATIC_FASTRAM biquadFilter_t gyroFilterNotch_2[XYZ_AXIS_COUNT]; - notchFilter2ApplyFn = nullFilterApply; - initGyroFilter(&gyroLpf2ApplyFn, gyroLpf2State, gyroConfig()->gyro_stage2_lowpass_type, gyroConfig()->gyro_stage2_lowpass_hz); initGyroFilter(&gyroLpfApplyFn, gyroLpfState, gyroConfig()->gyro_soft_lpf_type, gyroConfig()->gyro_soft_lpf_hz); - if (gyroConfig()->gyro_soft_notch_hz_1) { + if (gyroConfig()->gyro_notch_hz) { notchFilter1ApplyFn = (filterApplyFnPtr)biquadFilterApply; for (int axis = 0; axis < 3; axis++) { notchFilter1[axis] = &gyroFilterNotch_1[axis]; - biquadFilterInitNotch(notchFilter1[axis], getLooptime(), gyroConfig()->gyro_soft_notch_hz_1, gyroConfig()->gyro_soft_notch_cutoff_1); - } - } - - if (gyroConfig()->gyro_soft_notch_hz_2) { - notchFilter2ApplyFn = (filterApplyFnPtr)biquadFilterApply; - for (int axis = 0; axis < 3; axis++) { - notchFilter2[axis] = &gyroFilterNotch_2[axis]; - biquadFilterInitNotch(notchFilter2[axis], getLooptime(), gyroConfig()->gyro_soft_notch_hz_2, gyroConfig()->gyro_soft_notch_cutoff_2); + biquadFilterInitNotch(notchFilter1[axis], getLooptime(), gyroConfig()->gyro_notch_hz, gyroConfig()->gyro_notch_cutoff); } } } @@ -453,7 +438,6 @@ void FAST_CODE NOINLINE gyroUpdate() gyroADCf = gyroLpf2ApplyFn((filter_t *) &gyroLpf2State[axis], gyroADCf); gyroADCf = gyroLpfApplyFn((filter_t *) &gyroLpfState[axis], gyroADCf); gyroADCf = notchFilter1ApplyFn(notchFilter1[axis], gyroADCf); - gyroADCf = notchFilter2ApplyFn(notchFilter2[axis], gyroADCf); #ifdef USE_DYNAMIC_FILTERS if (dynamicGyroNotchState.enabled) { diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 414d9042cc2..b709294b553 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -66,10 +66,8 @@ typedef struct gyroConfig_s { uint8_t gyro_soft_lpf_hz; uint8_t gyro_soft_lpf_type; uint8_t gyro_to_use; - uint16_t gyro_soft_notch_hz_1; - uint16_t gyro_soft_notch_cutoff_1; - uint16_t gyro_soft_notch_hz_2; - uint16_t gyro_soft_notch_cutoff_2; + uint16_t gyro_notch_hz; + uint16_t gyro_notch_cutoff; uint16_t gyro_stage2_lowpass_hz; uint8_t gyro_stage2_lowpass_type; uint8_t dynamicGyroNotchRange; diff --git a/src/main/target/FALCORE/config.c b/src/main/target/FALCORE/config.c index 8762020de5d..a6acf83bfab 100755 --- a/src/main/target/FALCORE/config.c +++ b/src/main/target/FALCORE/config.c @@ -62,8 +62,8 @@ void targetConfiguration(void) gyroConfigMutable()->gyroSync = 1; gyroConfigMutable()->gyro_lpf = 0; // 256 Hz gyroConfigMutable()->gyro_soft_lpf_hz = 90; - gyroConfigMutable()->gyro_soft_notch_hz_1 = 150; - gyroConfigMutable()->gyro_soft_notch_cutoff_1 = 80; + gyroConfigMutable()->gyro_notch_hz = 150; + gyroConfigMutable()->gyro_notch_cutoff = 80; accelerometerConfigMutable()->acc_hardware = ACC_MPU6500; accelerometerConfigMutable()->acc_lpf_hz = 15; From 839a8773972d900f06a4f353f185b109e34452a5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Pawe=C5=82=20Spychalski?= Date: Tue, 9 Jun 2020 13:37:49 +0200 Subject: [PATCH 020/248] Add setpoint derivative feed forward term to PID controller (#5642) * Add setpoint derivative feed forward term to PID controller * Drop Dterm setpoint weight, FIR filter and dterm notch * Fix FALCORE build * Rename Multirotor FeedForward to Control Derivative * Apply Control Derivative results * Free CCM on F3 * Rename CLI name * Remove Omnibus F3 support * Update CLI.md and rename setting --- docs/Board - OMNIBUS.md | 2 + docs/Cli.md | 5 +- make/release.mk | 2 +- make/targets.mk | 2 +- src/main/blackbox/blackbox.c | 3 - src/main/build/debug.h | 1 + src/main/common/filter.c | 38 +----- src/main/common/filter.h | 5 - src/main/fc/config.c | 3 - src/main/fc/fc_msp.c | 12 +- src/main/fc/settings.yaml | 32 ++--- src/main/flight/pid.c | 114 ++++++++---------- src/main/flight/pid.h | 8 +- src/main/io/osd_dji_hd.c | 4 +- src/main/target/FALCORE/config.c | 3 - .../target/OMNIBUS/{target.mk => target.mk_} | 0 16 files changed, 85 insertions(+), 149 deletions(-) rename src/main/target/OMNIBUS/{target.mk => target.mk_} (100%) diff --git a/docs/Board - OMNIBUS.md b/docs/Board - OMNIBUS.md index 3caa5611670..7918e8a5bf5 100644 --- a/docs/Board - OMNIBUS.md +++ b/docs/Board - OMNIBUS.md @@ -1,5 +1,7 @@ # Board - OMNIBUS F3 +> This board is not supported in recent INAV releases + ## Hardware Features Refer to the product web page: diff --git a/docs/Cli.md b/docs/Cli.md index f580fdc288b..eb6360a5485 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -399,12 +399,15 @@ A shorter form is also supported to enable and disable functions using `serial < | mc_p_pitch | 40 | Multicopter rate stabilisation P-gain for PITCH | | mc_i_pitch | 30 | Multicopter rate stabilisation I-gain for PITCH | | mc_d_pitch | 23 | Multicopter rate stabilisation D-gain for PITCH | +| mc_cd_pitch | 60 | Multicopter Control Derivative gain for PITCH | | mc_p_roll | 40 | Multicopter rate stabilisation P-gain for ROLL | | mc_i_roll | 30 | Multicopter rate stabilisation I-gain for ROLL | | mc_d_roll | 23 | Multicopter rate stabilisation D-gain for ROLL | +| mc_cd_roll | 60 | Multicopter Control Derivative gain for ROLL | | mc_p_yaw | 85 | Multicopter rate stabilisation P-gain for YAW | | mc_i_yaw | 45 | Multicopter rate stabilisation I-gain for YAW | | mc_d_yaw | 0 | Multicopter rate stabilisation D-gain for YAW | +| mc_cd_yaw | 60 | Multicopter Control Derivative gain for YAW | | mc_p_level | 20 | Multicopter attitude stabilisation P-gain | | mc_i_level | 15 | Multicopter attitude stabilisation low-pass filter cutoff | | mc_d_level | 75 | Multicopter attitude stabilisation HORIZON transition point | @@ -505,7 +508,6 @@ A shorter form is also supported to enable and disable functions using `serial < | baro_cal_tolerance | 150 | Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]. | | mc_airmode_type | STICK_CENTER | Defines the Airmode state handling type for Multirotors. Default **STICK_CENTER** is the classical approach in which Airmode is always active if enabled, but when the throttle is low and ROLL/PITCH/YAW sticks are centered, Iterms is not allowed to grow (ANTI_WINDUP). **THROTTLE_THRESHOLD** is the Airmode behavior known from Betaflight. In this mode, Airmode is active as soon THROTTLE position is above `mc_airmode_threshold` and stays active until disarm. ANTI_WINDUP is never triggered. For small Multirotors (up to 7-inch propellers) it is suggested to switch to **THROTTLE_THRESHOLD** since it keeps full stabilization no matter what pilot does with the sticks. Fixed Wings always use **STICK_CENTER** mode. | | mc_airmode_threshold | 1300 | Defines airmode THROTTLE activation threshold when `mc_airmode_type` **THROTTLE_THRESHOLD** is used | -| use_dterm_fir_filter | ON | Setting to **OFF** disabled extra filter on Dterm. **OFF** offers faster Dterm and better inflight performance with a cost of being more sensitive to gyro noise. Small and relatively clean multirotors (7 inches and below) are suggested to use **OFF** setting. If motors are getting too hot, switch back to **ON** | | sim_ground_station_number | Empty string | Number of phone that is used to communicate with SIM module. Messages / calls from other numbers are ignored. If undefined, can be set by calling or sending a message to the module. | | sim_pin | Empty string | PIN code for the SIM module | | sim_transmit_interval | 60 | Text message transmission interval in seconds for SIM module. Minimum value: 10 | @@ -521,3 +523,4 @@ A shorter form is also supported to enable and disable functions using `serial < | antigravity_accelerator | 1 | | | antigravity_cutoff_lpf_hz | 15 | Antigravity cutoff frequenct for Throtte filter. Antigravity is based on the difference between actual and filtered throttle input. The bigger is the difference, the bigger Antigravity gain | | sim_pin | | PIN for GSM card module | +| mc_cd_lpf_hz | 30 | Cutoff frequency for Control Derivative. Lower value smoother reaction on fast stick movements. With higher values, response will be more aggressive, jerky | \ No newline at end of file diff --git a/make/release.mk b/make/release.mk index b96d1deacc4..f80fa989a24 100644 --- a/make/release.mk +++ b/make/release.mk @@ -10,7 +10,7 @@ RELEASE_TARGETS += KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KAKUTEF7HDV RELEASE_TARGETS += SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPRACINGF4EVO SPRACINGF7DUAL -RELEASE_TARGETS += OMNIBUS AIRBOTF4 ASGARD32F4 ASGARD32F7 FIREWORKSV2 AIRBOTF7 OMNIBUSF7NANOV7 +RELEASE_TARGETS += AIRBOTF4 ASGARD32F4 ASGARD32F7 FIREWORKSV2 AIRBOTF7 OMNIBUSF7NANOV7 RELEASE_TARGETS += OMNIBUSF4 OMNIBUSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 DYSF4PRO DYSF4PROV2 RELEASE_TARGETS += OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS RELEASE_TARGETS += OMNIBUSF7 OMNIBUSF7V2 OMNIBUSF7NXT YUPIF7 diff --git a/make/targets.mk b/make/targets.mk index 4416acc7d8e..aa0544bffdf 100644 --- a/make/targets.mk +++ b/make/targets.mk @@ -66,7 +66,7 @@ endif GROUP_1_TARGETS := AIRHEROF3 AIRHEROF3_QUAD LUX_RACE SPARKY REVO SPARKY2 COLIBRI FALCORE FF_F35_LIGHTNING FF_FORTINIF4 FF_PIKOF4 FF_PIKOF4OSD GROUP_2_TARGETS := SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPRACINGF4EVO CLRACINGF4AIR CLRACINGF4AIRV2 BEEROTORF4 BETAFLIGHTF3 BETAFLIGHTF4 PIKOBLX -GROUP_3_TARGETS := OMNIBUS AIRBOTF4 BLUEJAYF4 OMNIBUSF4 OMNIBUSF4PRO FIREWORKSV2 SPARKY2 MATEKF405 OMNIBUSF7 DYSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 OMNIBUSF7NXT OMNIBUSF7V2 ASGARD32F4 +GROUP_3_TARGETS := AIRBOTF4 BLUEJAYF4 OMNIBUSF4 OMNIBUSF4PRO FIREWORKSV2 SPARKY2 MATEKF405 OMNIBUSF7 DYSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 OMNIBUSF7NXT OMNIBUSF7V2 ASGARD32F4 GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ALIENFLIGHTNGF7 PIXRACER YUPIF7 MATEKF405SE MATEKF411 MATEKF722 MATEKF405OSD MATEKF405_SERVOS6 NOX GROUP_5_TARGETS := ASGARD32F7 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF3 FURYF3_SPIFLASH FURYF4OSD GROUP_6_TARGETS := MAMBAF405 OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS AIKONF4 diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index d445561290e..2a989784424 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1717,8 +1717,6 @@ static bool blackboxWriteSysinfo(void) BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_type", "%d", pidProfile()->dterm_lpf_type); BLACKBOX_PRINT_HEADER_LINE("dterm_lpf2_hz", "%d", pidProfile()->dterm_lpf2_hz); BLACKBOX_PRINT_HEADER_LINE("dterm_lpf2_type", "%d", pidProfile()->dterm_lpf2_type); - BLACKBOX_PRINT_HEADER_LINE("dterm_notch_hz", "%d", pidProfile()->dterm_soft_notch_hz); - BLACKBOX_PRINT_HEADER_LINE("dterm_notch_cutoff", "%d", pidProfile()->dterm_soft_notch_cutoff); BLACKBOX_PRINT_HEADER_LINE("deadband", "%d", rcControlsConfig()->deadband); BLACKBOX_PRINT_HEADER_LINE("yaw_deadband", "%d", rcControlsConfig()->yaw_deadband); BLACKBOX_PRINT_HEADER_LINE("gyro_lpf", "%d", gyroConfig()->gyro_lpf); @@ -1747,7 +1745,6 @@ static bool blackboxWriteSysinfo(void) BLACKBOX_PRINT_HEADER_LINE("acc_notch_hz", "%d", accelerometerConfig()->acc_notch_hz); BLACKBOX_PRINT_HEADER_LINE("acc_notch_cutoff", "%d", accelerometerConfig()->acc_notch_cutoff); BLACKBOX_PRINT_HEADER_LINE("gyro_stage2_lowpass_hz", "%d", gyroConfig()->gyro_stage2_lowpass_hz); - BLACKBOX_PRINT_HEADER_LINE("dterm_setpoint_weight", "%f", (double)pidProfile()->dterm_setpoint_weight); BLACKBOX_PRINT_HEADER_LINE("pidSumLimit", "%d", pidProfile()->pidSumLimit); BLACKBOX_PRINT_HEADER_LINE("pidSumLimitYaw", "%d", pidProfile()->pidSumLimitYaw); BLACKBOX_PRINT_HEADER_LINE("axisAccelerationLimitYaw", "%d", pidProfile()->axisAccelerationLimitYaw); diff --git a/src/main/build/debug.h b/src/main/build/debug.h index 283032b2973..f3360e8e045 100644 --- a/src/main/build/debug.h +++ b/src/main/build/debug.h @@ -71,5 +71,6 @@ typedef enum { DEBUG_DYNAMIC_FILTER, DEBUG_DYNAMIC_FILTER_FREQUENCY, DEBUG_IRLOCK, + DEBUG_CD, DEBUG_COUNT } debugType_e; diff --git a/src/main/common/filter.c b/src/main/common/filter.c index c2eb1cf4cca..387d478d39f 100644 --- a/src/main/common/filter.c +++ b/src/main/common/filter.c @@ -231,40 +231,4 @@ FAST_CODE void biquadFilterUpdate(biquadFilter_t *filter, float filterFreq, uint filter->x2 = x2; filter->y1 = y1; filter->y2 = y2; -} - -/* - * FIR filter - */ -void firFilterInit2(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs, uint8_t coeffsLength) -{ - filter->buf = buf; - filter->bufLength = bufLength; - filter->coeffs = coeffs; - filter->coeffsLength = coeffsLength; - memset(filter->buf, 0, sizeof(float) * filter->bufLength); -} - -/* - * FIR filter initialisation - * If FIR filter is just used for averaging, coeffs can be set to NULL - */ -void firFilterInit(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs) -{ - firFilterInit2(filter, buf, bufLength, coeffs, bufLength); -} - -void firFilterUpdate(firFilter_t *filter, float input) -{ - memmove(&filter->buf[1], &filter->buf[0], (filter->bufLength-1) * sizeof(float)); - filter->buf[0] = input; -} - -float firFilterApply(const firFilter_t *filter) -{ - float ret = 0.0f; - for (int ii = 0; ii < filter->coeffsLength; ++ii) { - ret += filter->coeffs[ii] * filter->buf[ii]; - } - return ret; -} +} \ No newline at end of file diff --git a/src/main/common/filter.h b/src/main/common/filter.h index fadae7ba48e..258b13dbe1f 100644 --- a/src/main/common/filter.h +++ b/src/main/common/filter.h @@ -81,8 +81,3 @@ float biquadFilterReset(biquadFilter_t *filter, float value); float biquadFilterApplyDF1(biquadFilter_t *filter, float input); float filterGetNotchQ(float centerFrequencyHz, float cutoffFrequencyHz); void biquadFilterUpdate(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate, float Q, biquadFilterType_e filterType); - -void firFilterInit(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs); -void firFilterInit2(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs, uint8_t coeffsLength); -void firFilterUpdate(firFilter_t *filter, float input); -float firFilterApply(const firFilter_t *filter); \ No newline at end of file diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 8178417ec42..627fd350b5a 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -170,9 +170,6 @@ void validateAndFixConfig(void) if (gyroConfig()->gyro_notch_cutoff >= gyroConfig()->gyro_notch_hz) { gyroConfigMutable()->gyro_notch_hz = 0; } - if (pidProfile()->dterm_soft_notch_cutoff >= pidProfile()->dterm_soft_notch_hz) { - pidProfileMutable()->dterm_soft_notch_hz = 0; - } if (accelerometerConfig()->acc_notch_cutoff >= accelerometerConfig()->acc_notch_hz) { accelerometerConfigMutable()->acc_notch_hz = 0; } diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index d3482616945..066e02dd5ff 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -1157,8 +1157,8 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU16(dst, pidProfile()->yaw_lpf_hz); sbufWriteU16(dst, gyroConfig()->gyro_notch_hz); sbufWriteU16(dst, gyroConfig()->gyro_notch_cutoff); - sbufWriteU16(dst, pidProfile()->dterm_soft_notch_hz); //BF: pidProfile()->dterm_notch_hz - sbufWriteU16(dst, pidProfile()->dterm_soft_notch_cutoff); //pidProfile()->dterm_notch_cutoff + sbufWriteU16(dst, 0); //BF: pidProfile()->dterm_notch_hz + sbufWriteU16(dst, 1); //pidProfile()->dterm_notch_cutoff sbufWriteU16(dst, 0); //BF: masterConfig.gyro_soft_notch_hz_2 sbufWriteU16(dst, 1); //BF: masterConfig.gyro_soft_notch_cutoff_2 @@ -1176,7 +1176,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU8(dst, 0); //BF: pidProfile()->deltaMethod sbufWriteU8(dst, 0); //BF: pidProfile()->vbatPidCompensation sbufWriteU8(dst, 0); //BF: pidProfile()->setpointRelaxRatio - sbufWriteU8(dst, constrain(pidProfile()->dterm_setpoint_weight * 100, 0, 255)); + sbufWriteU8(dst, 0); sbufWriteU16(dst, pidProfile()->pidSumLimit); sbufWriteU8(dst, 0); //BF: pidProfile()->itermThrottleGain @@ -2044,8 +2044,8 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) return MSP_RESULT_ERROR; } if (dataSize >= 13) { - pidProfileMutable()->dterm_soft_notch_hz = constrain(sbufReadU16(src), 0, 500); - pidProfileMutable()->dterm_soft_notch_cutoff = constrain(sbufReadU16(src), 1, 500); + sbufReadU16(src); + sbufReadU16(src); pidInitFilters(); } else { return MSP_RESULT_ERROR; @@ -2082,7 +2082,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) sbufReadU8(src); //BF: pidProfileMutable()->deltaMethod sbufReadU8(src); //BF: pidProfileMutable()->vbatPidCompensation sbufReadU8(src); //BF: pidProfileMutable()->setpointRelaxRatio - pidProfileMutable()->dterm_setpoint_weight = constrainf(sbufReadU8(src) / 100.0f, 0.0f, 2.0f); + sbufReadU8(src); pidProfileMutable()->pidSumLimit = sbufReadU16(src); sbufReadU8(src); //BF: pidProfileMutable()->itermThrottleGain diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 540dd26006e..e5b3d3471d5 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -84,7 +84,7 @@ tables: "FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE", "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "ITERM_RELAX", "ERPM", "RPM_FILTER", "RPM_FREQ", "NAV_YAW", "DYNAMIC_FILTER", "DYNAMIC_FILTER_FREQUENCY", - "IRLOCK"] + "IRLOCK", "CD"] - name: async_mode values: ["NONE", "GYRO", "ALL"] - name: aux_operator @@ -969,6 +969,10 @@ groups: field: bank_mc.pid[PID_PITCH].D min: 0 max: 200 + - name: mc_cd_pitch + field: bank_mc.pid[PID_PITCH].FF + min: 0 + max: 200 - name: mc_p_roll field: bank_mc.pid[PID_ROLL].P min: 0 @@ -981,6 +985,10 @@ groups: field: bank_mc.pid[PID_ROLL].D min: 0 max: 200 + - name: mc_cd_roll + field: bank_mc.pid[PID_ROLL].FF + min: 0 + max: 200 - name: mc_p_yaw field: bank_mc.pid[PID_YAW].P min: 0 @@ -993,6 +1001,10 @@ groups: field: bank_mc.pid[PID_YAW].D min: 0 max: 200 + - name: mc_cd_yaw + field: bank_mc.pid[PID_YAW].FF + min: 0 + max: 200 - name: mc_p_level field: bank_mc.pid[PID_LEVEL].P min: 0 @@ -1073,15 +1085,9 @@ groups: - name: dterm_lpf2_type field: dterm_lpf2_type table: filter_type - - name: use_dterm_fir_filter - field: use_dterm_fir_filter - type: bool - name: yaw_lpf_hz min: 0 max: 200 - - name: dterm_setpoint_weight - min: 0 - max: 2 - name: fw_iterm_throw_limit field: fixedWingItermThrowLimit min: FW_ITERM_THROW_LIMIT_MIN @@ -1102,14 +1108,6 @@ groups: field: fixedWingItermLimitOnStickPosition min: 0 max: 1 - - name: dterm_notch_hz - field: dterm_soft_notch_hz - min: 0 - max: 500 - - name: dterm_notch_cutoff - field: dterm_soft_notch_cutoff - min: 1 - max: 500 - name: pidsum_limit field: pidSumLimit min: PID_SUM_LIMIT_MIN @@ -1283,6 +1281,10 @@ groups: - name: pid_type field: pidControllerType table: pidTypeTable + - name: mc_cd_lpf_hz + field: controlDerivativeLpfHz + min: 0 + max: 200 - name: PG_PID_AUTOTUNE_CONFIG type: pidAutotuneConfig_t diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 599ca7d438a..fc00244a85f 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -63,6 +63,7 @@ typedef struct { float kI; // Integral gain float kD; // Derivative gain float kFF; // Feed-forward gain + float kCD; // Control Derivative float kT; // Back-calculation tracking gain float gyroRate; @@ -85,22 +86,23 @@ typedef struct { pt1Filter_t ptermLpfState; filter_t dtermLpfState; filter_t dtermLpf2State; - // Dterm notch filtering - biquadFilter_t deltaNotchFilter; + float stickPosition; -#ifdef USE_D_BOOST float previousRateTarget; float previousRateGyro; + +#ifdef USE_D_BOOST pt1Filter_t dBoostLpf; biquadFilter_t dBoostGyroLpf; #endif uint16_t pidSumLimit; filterApply4FnPtr ptermFilterApplyFn; bool itermLimitActive; + + biquadFilter_t rateTargetFilter; } pidState_t; -STATIC_FASTRAM filterApplyFnPtr notchFilterApplyFn; STATIC_FASTRAM bool pidFiltersConfigured = false; static EXTENDED_FASTRAM float headingHoldCosZLimit; static EXTENDED_FASTRAM int16_t headingHoldTarget; @@ -115,8 +117,7 @@ FASTRAM int16_t axisPID[FLIGHT_DYNAMICS_INDEX_COUNT]; int32_t axisPID_P[FLIGHT_DYNAMICS_INDEX_COUNT], axisPID_I[FLIGHT_DYNAMICS_INDEX_COUNT], axisPID_D[FLIGHT_DYNAMICS_INDEX_COUNT], axisPID_Setpoint[FLIGHT_DYNAMICS_INDEX_COUNT]; #endif -STATIC_FASTRAM pidState_t pidState[FLIGHT_DYNAMICS_INDEX_COUNT]; - +static EXTENDED_FASTRAM pidState_t pidState[FLIGHT_DYNAMICS_INDEX_COUNT]; static EXTENDED_FASTRAM pt1Filter_t windupLpf[XYZ_AXIS_COUNT]; static EXTENDED_FASTRAM uint8_t itermRelax; static EXTENDED_FASTRAM uint8_t itermRelaxType; @@ -148,15 +149,16 @@ typedef void (*pidControllerFnPtr)(pidState_t *pidState, flight_dynamics_index_t static EXTENDED_FASTRAM pidControllerFnPtr pidControllerApplyFn; static EXTENDED_FASTRAM filterApplyFnPtr dTermLpfFilterApplyFn; static EXTENDED_FASTRAM filterApplyFnPtr dTermLpf2FilterApplyFn; +static EXTENDED_FASTRAM bool levelingEnabled = false; -PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 12); +PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 13); PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .bank_mc = { .pid = { - [PID_ROLL] = { 40, 30, 23, 0 }, - [PID_PITCH] = { 40, 30, 23, 0 }, - [PID_YAW] = { 85, 45, 0, 0 }, + [PID_ROLL] = { 40, 30, 23, 60 }, + [PID_PITCH] = { 40, 30, 23, 60 }, + [PID_YAW] = { 85, 45, 0, 60 }, [PID_LEVEL] = { .P = 20, // Self-level strength .I = 15, // Self-leveing low-pass frequency (0 - disabled) @@ -230,15 +232,11 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, } }, - .dterm_soft_notch_hz = 0, - .dterm_soft_notch_cutoff = 1, .dterm_lpf_type = 1, //Default to BIQUAD .dterm_lpf_hz = 40, .dterm_lpf2_type = 1, //Default to BIQUAD .dterm_lpf2_hz = 0, // Off by default .yaw_lpf_hz = 0, - .dterm_setpoint_weight = 1.0f, - .use_dterm_fir_filter = 1, .itermWindupPointPercent = 50, // Percent @@ -270,6 +268,7 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .antigravityCutoff = ANTI_GRAVITY_THROTTLE_FILTER_CUTOFF, .pidControllerType = PID_TYPE_AUTO, .navFwPosHdgPidsumLimit = PID_SUM_LIMIT_YAW_DEFAULT, + .controlDerivativeLpfHz = 30, ); bool pidInitFilters(void) @@ -280,38 +279,6 @@ bool pidInitFilters(void) return false; } - static float dtermCoeffs[PID_GYRO_RATE_BUF_LENGTH]; - - if (pidProfile()->use_dterm_fir_filter) { - // Calculate derivative using 5-point noise-robust differentiators without time delay (one-sided or forward filters) - // by Pavel Holoborodko, see http://www.holoborodko.com/pavel/numerical-methods/numerical-derivative/smooth-low-noise-differentiators/ - // h[0] = 5/8, h[-1] = 1/4, h[-2] = -1, h[-3] = -1/4, h[-4] = 3/8 - dtermCoeffs[0] = 5.0f/8; - dtermCoeffs[1] = 2.0f/8; - dtermCoeffs[2] = -8.0f/8; - dtermCoeffs[3] = -2.0f/8; - dtermCoeffs[4] = 3.0f/8; - } else { - //simple d(t) - d(t-1) differentiator - dtermCoeffs[0] = 1.0f; - dtermCoeffs[1] = -1.0f; - dtermCoeffs[2] = 0.0f; - dtermCoeffs[3] = 0.0f; - dtermCoeffs[4] = 0.0f; - } - - for (int axis = 0; axis < 3; ++ axis) { - firFilterInit(&pidState[axis].gyroRateFilter, pidState[axis].gyroRateBuf, PID_GYRO_RATE_BUF_LENGTH, dtermCoeffs); - } - - notchFilterApplyFn = nullFilterApply; - if (pidProfile()->dterm_soft_notch_hz != 0) { - notchFilterApplyFn = (filterApplyFnPtr)biquadFilterApply; - for (int axis = 0; axis < 3; ++ axis) { - biquadFilterInitNotch(&pidState[axis].deltaNotchFilter, refreshRate, pidProfile()->dterm_soft_notch_hz, pidProfile()->dterm_soft_notch_cutoff); - } - } - // Init other filters if (pidProfile()->dterm_lpf_hz) { for (int axis = 0; axis < 3; ++ axis) { @@ -348,6 +315,12 @@ bool pidInitFilters(void) } #endif + if (pidProfile()->controlDerivativeLpfHz) { + for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { + biquadFilterInitLPF(&pidState[axis].rateTargetFilter, pidProfile()->controlDerivativeLpfHz, getLooptime()); + } + } + pidFiltersConfigured = true; return true; @@ -496,6 +469,7 @@ void FAST_CODE NOINLINE updatePIDCoefficients(float dT) pidState[axis].kI = pidBank()->pid[axis].I / FP_PID_RATE_I_MULTIPLIER * tpaFactor; pidState[axis].kD = 0.0f; pidState[axis].kFF = pidBank()->pid[axis].FF / FP_PID_RATE_FF_MULTIPLIER * tpaFactor; + pidState[axis].kCD = 0.0f; pidState[axis].kT = 0.0f; } else { @@ -503,6 +477,7 @@ void FAST_CODE NOINLINE updatePIDCoefficients(float dT) pidState[axis].kP = pidBank()->pid[axis].P / FP_PID_RATE_P_MULTIPLIER * axisTPA; pidState[axis].kI = pidBank()->pid[axis].I / FP_PID_RATE_I_MULTIPLIER; pidState[axis].kD = pidBank()->pid[axis].D / FP_PID_RATE_D_MULTIPLIER * axisTPA; + pidState[axis].kCD = pidBank()->pid[axis].FF / FP_PID_RATE_D_FF_MULTIPLIER * axisTPA; pidState[axis].kFF = 0.0f; // Tracking anti-windup requires P/I/D to be all defined which is only true for MC @@ -591,7 +566,7 @@ bool isFixedWingItermLimitActive(float stickPosition) * Iterm anti windup whould be active only when pilot controls the rotation * velocity directly, not when ANGLE or HORIZON are used */ - if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) { + if (levelingEnabled) { return false; } @@ -689,9 +664,6 @@ static float FAST_CODE applyDBoost(pidState_t *pidState, float dT) { dBoost = scaleRangef(acceleration, 0.0f, dBoostMaxAtAlleceleration, 1.0f, dBoostFactor); dBoost = pt1FilterApply4(&pidState->dBoostLpf, dBoost, D_BOOST_LPF_HZ, dT); dBoost = constrainf(dBoost, 1.0f, dBoostFactor); - - pidState->previousRateTarget = pidState->rateTarget; - pidState->previousRateGyro = pidState->gyroRate; } return dBoost; @@ -709,34 +681,38 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid const float rateError = pidState->rateTarget - pidState->gyroRate; const float newPTerm = pTermProcess(pidState, rateError, dT); + const float rateTargetDelta = pidState->rateTarget - pidState->previousRateTarget; + const float rateTargetDeltaFiltered = biquadFilterApply(&pidState->rateTargetFilter, rateTargetDelta); + + /* + * Compute Control Derivative + * CD is enabled only when ANGLE and HORIZON modes are not enabled! + */ + float newCDTerm; + if (levelingEnabled) { + newCDTerm = 0.0F; + } else { + newCDTerm = rateTargetDeltaFiltered * (pidState->kCD / dT); + } + DEBUG_SET(DEBUG_CD, axis, newCDTerm); + // Calculate new D-term float newDTerm; if (pidState->kD == 0) { // optimisation for when D8 is zero, often used by YAW axis newDTerm = 0; } else { - // Calculate delta for Dterm calculation. Apply filters before derivative to minimize effects of dterm kick - const float deltaFiltered = pidProfile()->dterm_setpoint_weight * pidState->rateTarget - pidState->gyroRate; - - firFilterUpdate(&pidState->gyroRateFilter, deltaFiltered); - newDTerm = firFilterApply(&pidState->gyroRateFilter); - - // Apply D-term notch - newDTerm = notchFilterApplyFn(&pidState->deltaNotchFilter, newDTerm); + float delta = pidState->previousRateGyro - pidState->gyroRate; - // Apply additional lowpass - newDTerm = dTermLpfFilterApplyFn((filter_t *) &pidState->dtermLpfState, newDTerm); - newDTerm = dTermLpf2FilterApplyFn((filter_t *) &pidState->dtermLpf2State, newDTerm); + delta = dTermLpfFilterApplyFn((filter_t *) &pidState->dtermLpfState, delta); + delta = dTermLpf2FilterApplyFn((filter_t *) &pidState->dtermLpf2State, delta); // Calculate derivative - newDTerm = newDTerm * (pidState->kD / dT) * applyDBoost(pidState, dT); - - // Additionally constrain D - newDTerm = constrainf(newDTerm, -300.0f, 300.0f); + newDTerm = delta * (pidState->kD / dT) * applyDBoost(pidState, dT); } // TODO: Get feedback from mixer on available correction range for each axis - const float newOutput = newPTerm + newDTerm + pidState->errorGyroIf; + const float newOutput = newPTerm + newDTerm + pidState->errorGyroIf + newCDTerm; const float newOutputLimited = constrainf(newOutput, -pidState->pidSumLimit, +pidState->pidSumLimit); float itermErrorRate = rateError; @@ -760,6 +736,9 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid axisPID_D[axis] = newDTerm; axisPID_Setpoint[axis] = pidState->rateTarget; #endif + + pidState->previousRateTarget = pidState->rateTarget; + pidState->previousRateGyro = pidState->gyroRate; } void updateHeadingHoldTarget(int16_t heading) @@ -995,6 +974,9 @@ void FAST_CODE pidController(float dT) pidLevel(&pidState[FD_ROLL], FD_ROLL, horizonRateMagnitude, dT); pidLevel(&pidState[FD_PITCH], FD_PITCH, horizonRateMagnitude, dT); canUseFpvCameraMix = false; // FPVANGLEMIX is incompatible with ANGLE/HORIZON + levelingEnabled = true; + } else { + levelingEnabled = false; } if (FLIGHT_MODE(TURN_ASSISTANT) || navigationRequiresTurnAssistance()) { diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 9290bfff914..f25c3cb33f1 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -45,6 +45,7 @@ FP-PID has been rescaled to match LuxFloat (and MWRewrite) from Cleanflight 1.13 #define FP_PID_RATE_P_MULTIPLIER 31.0f #define FP_PID_RATE_I_MULTIPLIER 4.0f #define FP_PID_RATE_D_MULTIPLIER 1905.0f +#define FP_PID_RATE_D_FF_MULTIPLIER 7270.0f #define FP_PID_LEVEL_P_MULTIPLIER 6.56f // Level P gain units is [1/sec] and angle error is [deg] => [deg/s] #define FP_PID_YAWHOLD_P_MULTIPLIER 80.0f @@ -104,17 +105,12 @@ typedef struct pidProfile_s { pidBank_t bank_fw; pidBank_t bank_mc; - uint16_t dterm_soft_notch_hz; // Dterm Notch frequency - uint16_t dterm_soft_notch_cutoff; // Dterm Notch Cutoff frequency - uint8_t dterm_lpf_type; // Dterm LPF type: PT1, BIQUAD uint16_t dterm_lpf_hz; uint8_t dterm_lpf2_type; // Dterm LPF type: PT1, BIQUAD uint16_t dterm_lpf2_hz; - uint8_t use_dterm_fir_filter; // Use classical INAV FIR differentiator. Very noise robust, can be quite slowish - uint8_t yaw_lpf_hz; uint8_t heading_hold_rate_limit; // Maximum rotation rate HEADING_HOLD mode can feed to yaw rate PID controller @@ -126,7 +122,6 @@ typedef struct pidProfile_s { int16_t max_angle_inclination[ANGLE_INDEX_COUNT]; // Max possible inclination (roll and pitch axis separately - float dterm_setpoint_weight; uint16_t pidSumLimit; uint16_t pidSumLimitYaw; @@ -151,6 +146,7 @@ typedef struct pidProfile_s { uint8_t antigravityCutoff; uint16_t navFwPosHdgPidsumLimit; + uint8_t controlDerivativeLpfHz; } pidProfile_t; typedef struct pidAutotuneConfig_s { diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index 6d0167202b5..29b3abf0743 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -568,8 +568,8 @@ static mspResult_e djiProcessMspCommand(mspPacket_t *cmd, mspPacket_t *reply, ms sbufWriteU16(dst, pidProfile()->yaw_lpf_hz); // BF: currentPidProfile->yaw_lowpass_hz sbufWriteU16(dst, gyroConfig()->gyro_notch_hz); // BF: gyroConfig()->gyro_soft_notch_hz_1 sbufWriteU16(dst, gyroConfig()->gyro_notch_cutoff); // BF: gyroConfig()->gyro_soft_notch_cutoff_1 - sbufWriteU16(dst, pidProfile()->dterm_soft_notch_hz); // BF: currentPidProfile->dterm_notch_hz - sbufWriteU16(dst, pidProfile()->dterm_soft_notch_cutoff); // BF: currentPidProfile->dterm_notch_cutoff + sbufWriteU16(dst, 0); // BF: currentPidProfile->dterm_notch_hz + sbufWriteU16(dst, 1); // BF: currentPidProfile->dterm_notch_cutoff sbufWriteU16(dst, 0); // BF: gyroConfig()->gyro_soft_notch_hz_2 sbufWriteU16(dst, 1); // BF: gyroConfig()->gyro_soft_notch_cutoff_2 sbufWriteU8(dst, 0); // BF: currentPidProfile->dterm_filter_type diff --git a/src/main/target/FALCORE/config.c b/src/main/target/FALCORE/config.c index a6acf83bfab..d862359d49e 100755 --- a/src/main/target/FALCORE/config.c +++ b/src/main/target/FALCORE/config.c @@ -167,9 +167,6 @@ void targetConfiguration(void) pidProfileMutable()->max_angle_inclination[FD_PITCH] = 300; pidProfileMutable()->dterm_lpf_hz = 70; pidProfileMutable()->yaw_lpf_hz = 35; - pidProfileMutable()->dterm_setpoint_weight = 0; - pidProfileMutable()->dterm_soft_notch_hz = 0; - pidProfileMutable()->dterm_soft_notch_cutoff = 1; pidProfileMutable()->pidSumLimit = 500; pidProfileMutable()->axisAccelerationLimitRollPitch = 0; pidProfileMutable()->axisAccelerationLimitYaw = 10000; diff --git a/src/main/target/OMNIBUS/target.mk b/src/main/target/OMNIBUS/target.mk_ similarity index 100% rename from src/main/target/OMNIBUS/target.mk rename to src/main/target/OMNIBUS/target.mk_ From 57d37905ce957ce902fee889ab4a20d64e2b546b Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Wed, 10 Jun 2020 19:44:47 +0200 Subject: [PATCH 021/248] Swap IMU definitions on FIREWORKSV2 target; Fixes gyro on OMNIBUS F4 Nano V6 --- src/main/target/FIREWORKSV2/target.h | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/src/main/target/FIREWORKSV2/target.h b/src/main/target/FIREWORKSV2/target.h index b8dd5c6ef6b..c3818458fd5 100644 --- a/src/main/target/FIREWORKSV2/target.h +++ b/src/main/target/FIREWORKSV2/target.h @@ -75,13 +75,14 @@ # define IMU_2_SPI_BUS BUS_SPI1 # define IMU_2_ALIGN CW0_DEG #else - // FIREWORKS V2 -# define IMU_1_CS_PIN PD2 -# define IMU_1_SPI_BUS BUS_SPI3 -# define IMU_1_ALIGN CW180_DEG -# define IMU_2_CS_PIN PA4 -# define IMU_2_SPI_BUS BUS_SPI1 -# define IMU_2_ALIGN CW0_DEG_FLIP + // IMU_1 is verified to work on OBF4V6 and Omnibus Fireworks board +# define IMU_1_CS_PIN PA4 +# define IMU_1_SPI_BUS BUS_SPI1 +# define IMU_1_ALIGN CW0_DEG_FLIP + // IMU_2 is sketchy and was not verified on actual hardware +# define IMU_2_CS_PIN PD2 +# define IMU_2_SPI_BUS BUS_SPI3 +# define IMU_2_ALIGN CW180_DEG #endif #define USE_MAG From f238d57f585495c8db11e7bac427984f253acbfe Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Thu, 11 Jun 2020 12:06:40 +0200 Subject: [PATCH 022/248] [VTX] Allow override of max power capability for buggy VTXes --- docs/Cli.md | 1 + src/main/fc/settings.yaml | 4 ++++ src/main/io/vtx.c | 3 ++- src/main/io/vtx.h | 11 ++++++----- src/main/io/vtx_tramp.c | 10 +++++++++- 5 files changed, 22 insertions(+), 7 deletions(-) diff --git a/docs/Cli.md b/docs/Cli.md index f580fdc288b..aaddd99a606 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -488,6 +488,7 @@ A shorter form is also supported to enable and disable functions using `serial < | vtx_low_power_disarm | OFF | When the craft is disarmed, set the VTX to its lowest power. `ON` will set the power to its minimum value on startup, increase it to `vtx_power` when arming and change it back to its lowest setting after disarming. `UNTIL_FIRST_ARM` will start with minimum power, but once the craft is armed it will increase to `vtx_power` and it will never decrease until the craft is power cycled. | | vtx_pit_mode_freq | Frequency to use (in MHz) when the VTX is in pit mode. | | vtx_power | 1 | VTX RF power level to use. The exact number of mw depends on the VTX hardware. | +| vtx_max_power_override | 0 | Some VTXes may report max power incorrectly (i.e. 200mW for a 600mW VTX). Use this to override max supported power. 0 to disable and use whatever VTX reports as it's capabilities | | motor_accel_time | 0 | Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000] | | motor_decel_time | 0 | Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000] | | thr_comp_weight | 0.692 | Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage) | diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 9f5880120b4..62e6275f938 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2119,6 +2119,10 @@ groups: field: pitModeChan min: VTX_SETTINGS_MIN_CHANNEL max: VTX_SETTINGS_MAX_CHANNEL + - name: vtx_max_power_override + field: maxPowerOverride + min: 0 + max: 10000 - name: PG_PINIOBOX_CONFIG type: pinioBoxConfig_t diff --git a/src/main/io/vtx.c b/src/main/io/vtx.c index 6a2fffa66ca..f4b999a5342 100644 --- a/src/main/io/vtx.c +++ b/src/main/io/vtx.c @@ -43,7 +43,7 @@ #include "io/vtx_string.h" #include "io/vtx_control.h" -PG_REGISTER_WITH_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig, PG_VTX_SETTINGS_CONFIG, 1); +PG_REGISTER_WITH_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig, PG_VTX_SETTINGS_CONFIG, 2); PG_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig, .band = VTX_SETTINGS_DEFAULT_BAND, @@ -51,6 +51,7 @@ PG_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig, .power = VTX_SETTINGS_DEFAULT_POWER, .pitModeChan = VTX_SETTINGS_DEFAULT_PITMODE_CHANNEL, .lowPowerDisarm = VTX_LOW_POWER_DISARM_OFF, + .maxPowerOverride = 0, ); typedef enum { diff --git a/src/main/io/vtx.h b/src/main/io/vtx.h index e3bb6018a62..4bff70af54a 100644 --- a/src/main/io/vtx.h +++ b/src/main/io/vtx.h @@ -35,11 +35,12 @@ typedef enum { } vtxLowerPowerDisarm_e; typedef struct vtxSettingsConfig_s { - uint8_t band; // 1=A, 2=B, 3=E, 4=F(Airwaves/Fatshark), 5=Racebande - uint8_t channel; // 1-8 - uint8_t power; // 0 = lowest - uint16_t pitModeChan; // sets out-of-range pitmode frequency - uint8_t lowPowerDisarm; // min power while disarmed, from vtxLowerPowerDisarm_e + uint8_t band; // 1=A, 2=B, 3=E, 4=F(Airwaves/Fatshark), 5=Racebande + uint8_t channel; // 1-8 + uint8_t power; // 0 = lowest + uint16_t pitModeChan; // sets out-of-range pitmode frequency + uint8_t lowPowerDisarm; // min power while disarmed, from vtxLowerPowerDisarm_e + uint16_t maxPowerOverride; // for VTX drivers that are polling VTX capabilities - override what VTX is reporting } vtxSettingsConfig_t; PG_DECLARE(vtxSettingsConfig_t, vtxSettingsConfig); diff --git a/src/main/io/vtx_tramp.c b/src/main/io/vtx_tramp.c index 3e95ac1ae8f..4e22d35f2ff 100644 --- a/src/main/io/vtx_tramp.c +++ b/src/main/io/vtx_tramp.c @@ -228,9 +228,17 @@ static vtxProtoResponseType_e vtxProtoProcessResponse(void) vtxState.capabilities.freqMin = vtxState.recvPkt[2] | (vtxState.recvPkt[3] << 8); vtxState.capabilities.freqMax = vtxState.recvPkt[4] | (vtxState.recvPkt[5] << 8); vtxState.capabilities.powerMax = vtxState.recvPkt[6] | (vtxState.recvPkt[7] << 8); + if (vtxState.capabilities.freqMin != 0 && vtxState.capabilities.freqMin < vtxState.capabilities.freqMax) { - // Update max power metadata so OSD settings would match VTX capabiolities + // Some TRAMP VTXes may report max power incorrectly (i.e. 200mW for a 600mW VTX) + // Make use of vtxSettingsConfig()->maxPowerOverride to override + if (vtxSettingsConfig()->maxPowerOverride != 0) { + vtxState.capabilities.powerMax = vtxSettingsConfig()->maxPowerOverride; + } + + // Update max power metadata so OSD settings would match VTX capabilities vtxProtoUpdatePowerMetadata(vtxState.capabilities.powerMax); + return VTX_RESPONSE_TYPE_CAPABILITIES; } break; From 706da4aef22a1ce4fc5df4d97308a12ddda48cfc Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Pawe=C5=82=20Spychalski?= Date: Thu, 11 Jun 2020 13:46:04 +0200 Subject: [PATCH 023/248] Gyro Kalman filter from EmuFlight (#5519) * Direct copy from EmuFlight, compiles, does not wrk * Fix Kalman computation * Catchup on Emu implementation * Make Q, W and Sharpness configurable * Settings for Kalman Q, W and Sharpness * Make it possible to enable/disable Kalman filter * Change scaling to make initial values simpler * Change Kalman constrains * Compute real variance * Drop unused function parameter * Improve EKF processing for gyro --- make/source.mk | 1 + src/main/build/debug.h | 1 + src/main/fc/settings.yaml | 21 ++++++- src/main/flight/kalman.c | 126 ++++++++++++++++++++++++++++++++++++++ src/main/flight/kalman.h | 54 ++++++++++++++++ src/main/flight/pid.c | 4 ++ src/main/sensors/gyro.c | 20 +++++- src/main/sensors/gyro.h | 4 ++ src/main/target/common.h | 1 + 9 files changed, 230 insertions(+), 2 deletions(-) create mode 100755 src/main/flight/kalman.c create mode 100755 src/main/flight/kalman.h diff --git a/make/source.mk b/make/source.mk index cb16ae755ec..6c4800aa35a 100644 --- a/make/source.mk +++ b/make/source.mk @@ -104,6 +104,7 @@ COMMON_SRC = \ flight/gyroanalyse.c \ flight/rpm_filter.c \ flight/dynamic_gyro_notch.c \ + flight/kalman.c \ io/beeper.c \ io/esc_serialshot.c \ io/servo_sbus.c \ diff --git a/src/main/build/debug.h b/src/main/build/debug.h index f3360e8e045..a5a5e90ea65 100644 --- a/src/main/build/debug.h +++ b/src/main/build/debug.h @@ -72,5 +72,6 @@ typedef enum { DEBUG_DYNAMIC_FILTER_FREQUENCY, DEBUG_IRLOCK, DEBUG_CD, + DEBUG_KALMAN, DEBUG_COUNT } debugType_e; diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index e5b3d3471d5..91511be8284 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -84,7 +84,7 @@ tables: "FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE", "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "ITERM_RELAX", "ERPM", "RPM_FILTER", "RPM_FREQ", "NAV_YAW", "DYNAMIC_FILTER", "DYNAMIC_FILTER_FREQUENCY", - "IRLOCK", "CD"] + "IRLOCK", "CD", "KALMAN"] - name: async_mode values: ["NONE", "GYRO", "ALL"] - name: aux_operator @@ -203,6 +203,25 @@ groups: condition: USE_DYNAMIC_FILTERS min: 30 max: 1000 + - name: gyro_kalman_enabled + condition: USE_GYRO_KALMAN + field: kalmanEnabled + type: bool + - name: gyro_kalman_q + field: kalman_q + condition: USE_GYRO_KALMAN + min: 1 + max: 16000 + - name: gyro_kalman_w + field: kalman_w + condition: USE_GYRO_KALMAN + min: 1 + max: 40 + - name: gyro_kalman_sharpness + field: kalman_sharpness + condition: USE_GYRO_KALMAN + min: 1 + max: 16000 - name: gyro_to_use condition: USE_DUAL_GYRO min: 0 diff --git a/src/main/flight/kalman.c b/src/main/flight/kalman.c new file mode 100755 index 00000000000..9e672a4a6ac --- /dev/null +++ b/src/main/flight/kalman.c @@ -0,0 +1,126 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ +#include "platform.h" +#ifdef USE_GYRO_KALMAN + +FILE_COMPILE_FOR_SPEED + +#include +#include "arm_math.h" + +#include "kalman.h" +#include "build/debug.h" + +kalman_t kalmanFilterStateRate[XYZ_AXIS_COUNT]; +float setPoint[XYZ_AXIS_COUNT]; + +static void gyroKalmanInitAxis(kalman_t *filter) +{ + memset(filter, 0, sizeof(kalman_t)); + filter->q = gyroConfig()->kalman_q * 0.03f; //add multiplier to make tuning easier + filter->r = 88.0f; //seeding R at 88.0f + filter->p = 30.0f; //seeding P at 30.0f + filter->e = 1.0f; + filter->s = gyroConfig()->kalman_sharpness / 10.0f; + filter->w = gyroConfig()->kalman_w * 8; + filter->inverseN = 1.0f / (float)(filter->w); +} + +void gyroKalmanSetSetpoint(uint8_t axis, float rate) +{ + setPoint[axis] = rate; +} + +void gyroKalmanInitialize(void) +{ + gyroKalmanInitAxis(&kalmanFilterStateRate[X]); + gyroKalmanInitAxis(&kalmanFilterStateRate[Y]); + gyroKalmanInitAxis(&kalmanFilterStateRate[Z]); +} + +float kalman_process(kalman_t *kalmanState, float input, float target) +{ + float targetAbs = fabsf(target); + //project the state ahead using acceleration + kalmanState->x += (kalmanState->x - kalmanState->lastX); + + //figure out how much to boost or reduce our error in the estimate based on setpoint target. + //this should be close to 0 as we approach the sepoint and really high the futher away we are from the setpoint. + //update last state + kalmanState->lastX = kalmanState->x; + + if (kalmanState->lastX != 0.0f) + { + // calculate the error and add multiply sharpness boost + float errorMultiplier = fabsf(target - kalmanState->x) * kalmanState->s; + + // give a boost to the setpoint, used to caluclate the kalman q, based on the error and setpoint/gyrodata + errorMultiplier = constrainf(errorMultiplier * fabsf(1.0f - (target / kalmanState->lastX)) + 1.0f, 1.0f, 50.0f); + + kalmanState->e = fabsf(1.0f - (((targetAbs + 1.0f) * errorMultiplier) / fabsf(kalmanState->lastX))); + } + + //prediction update + kalmanState->p = kalmanState->p + (kalmanState->q * kalmanState->e); + + //measurement update + kalmanState->k = kalmanState->p / (kalmanState->p + kalmanState->r); + kalmanState->x += kalmanState->k * (input - kalmanState->x); + kalmanState->p = (1.0f - kalmanState->k) * kalmanState->p; + return kalmanState->x; +} + +static void updateAxisVariance(kalman_t *kalmanState, float rate) +{ + kalmanState->axisWindow[kalmanState->windex] = rate; + + kalmanState->axisSumMean += kalmanState->axisWindow[kalmanState->windex]; + float varianceElement = kalmanState->axisWindow[kalmanState->windex] - kalmanState->axisMean; + varianceElement = varianceElement * varianceElement; + kalmanState->axisSumVar += varianceElement; + kalmanState->varianceWindow[kalmanState->windex] = varianceElement; + + kalmanState->windex++; + if (kalmanState->windex >= kalmanState->w) { + kalmanState->windex = 0; + } + + kalmanState->axisSumMean -= kalmanState->axisWindow[kalmanState->windex]; + kalmanState->axisSumVar -= kalmanState->varianceWindow[kalmanState->windex]; + + //New mean + kalmanState->axisMean = kalmanState->axisSumMean * kalmanState->inverseN; + kalmanState->axisVar = kalmanState->axisSumVar * kalmanState->inverseN; + + float squirt; + arm_sqrt_f32(kalmanState->axisVar, &squirt); + kalmanState->r = squirt * VARIANCE_SCALE; +} + +float gyroKalmanUpdate(uint8_t axis, float input) +{ + updateAxisVariance(&kalmanFilterStateRate[axis], input); + + DEBUG_SET(DEBUG_KALMAN, axis, kalmanFilterStateRate[axis].k * 1000.0f); //Kalman gain + + return kalman_process(&kalmanFilterStateRate[axis], input, setPoint[axis]); +} + +#endif \ No newline at end of file diff --git a/src/main/flight/kalman.h b/src/main/flight/kalman.h new file mode 100755 index 00000000000..f493c1f628d --- /dev/null +++ b/src/main/flight/kalman.h @@ -0,0 +1,54 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +#include "sensors/gyro.h" +#include "common/filter.h" + +#define MAX_KALMAN_WINDOW_SIZE 512 + +#define VARIANCE_SCALE 0.67f + +typedef struct kalman +{ + float q; //process noise covariance + float r; //measurement noise covariance + float p; //estimation error covariance matrix + float k; //kalman gain + float x; //state + float lastX; //previous state + float e; + float s; + + float axisVar; + uint16_t windex; + float axisWindow[MAX_KALMAN_WINDOW_SIZE]; + float varianceWindow[MAX_KALMAN_WINDOW_SIZE]; + float axisSumMean; + float axisMean; + float axisSumVar; + float inverseN; + uint16_t w; +} kalman_t; + +void gyroKalmanInitialize(void); +float gyroKalmanUpdate(uint8_t axis, float input); +void gyroKalmanSetSetpoint(uint8_t axis, float rate); diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index fc00244a85f..a9e621285ed 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -44,6 +44,7 @@ FILE_COMPILE_FOR_SPEED #include "flight/imu.h" #include "flight/mixer.h" #include "flight/rpm_filter.h" +#include "flight/kalman.h" #include "io/gps.h" @@ -966,6 +967,9 @@ void FAST_CODE pidController(float dT) // Limit desired rate to something gyro can measure reliably pidState[axis].rateTarget = constrainf(rateTarget, -GYRO_SATURATION_LIMIT, +GYRO_SATURATION_LIMIT); +#ifdef USE_GYRO_KALMAN + gyroKalmanSetSetpoint(axis, pidState[axis].rateTarget); +#endif } // Step 3: Run control for ANGLE_MODE, HORIZON_MODE, and HEADING_LOCK diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index bd6b43db1c6..e11b2f5d003 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -72,6 +72,7 @@ FILE_COMPILE_FOR_SPEED #include "flight/gyroanalyse.h" #include "flight/rpm_filter.h" #include "flight/dynamic_gyro_notch.h" +#include "flight/kalman.h" #ifdef USE_HARDWARE_REVISION_DETECTION #include "hardware_revision.h" @@ -119,7 +120,11 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .dynamicGyroNotchRange = DYN_NOTCH_RANGE_MEDIUM, .dynamicGyroNotchQ = 120, .dynamicGyroNotchMinHz = 150, - .dynamicGyroNotchEnabled = 0 + .dynamicGyroNotchEnabled = 0, + .kalman_q = 100, + .kalman_w = 4, + .kalman_sharpness = 100, + .kalmanEnabled = 0, ); STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev, gyroSensor_e gyroHardware) @@ -307,6 +312,11 @@ bool gyroInit(void) } gyroInitFilters(); +#ifdef USE_GYRO_KALMAN + if (gyroConfig()->kalmanEnabled) { + gyroKalmanInitialize(); + } +#endif #ifdef USE_DYNAMIC_FILTERS dynamicGyroNotchFiltersInit(&dynamicGyroNotchState); gyroDataAnalyseStateInit( @@ -450,6 +460,14 @@ void FAST_CODE NOINLINE gyroUpdate() gyro.gyroADCf[axis] = gyroADCf; } +#ifdef USE_GYRO_KALMAN + if (gyroConfig()->kalmanEnabled) { + gyro.gyroADCf[X] = gyroKalmanUpdate(X, gyro.gyroADCf[X]); + gyro.gyroADCf[Y] = gyroKalmanUpdate(Y, gyro.gyroADCf[Y]); + gyro.gyroADCf[Z] = gyroKalmanUpdate(Z, gyro.gyroADCf[Z]); + } +#endif + #ifdef USE_DYNAMIC_FILTERS if (dynamicGyroNotchState.enabled) { gyroDataAnalyse(&gyroAnalyseState); diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index b709294b553..39e04c84800 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -74,6 +74,10 @@ typedef struct gyroConfig_s { uint16_t dynamicGyroNotchQ; uint16_t dynamicGyroNotchMinHz; uint8_t dynamicGyroNotchEnabled; + uint16_t kalman_q; + uint16_t kalman_w; + uint16_t kalman_sharpness; + uint8_t kalmanEnabled; } gyroConfig_t; PG_DECLARE(gyroConfig_t, gyroConfig); diff --git a/src/main/target/common.h b/src/main/target/common.h index 52eb6eb819a..d79dad8a621 100755 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -72,6 +72,7 @@ #define USE_PITOT_VIRTUAL #define USE_DYNAMIC_FILTERS +#define USE_GYRO_KALMAN #define USE_EXTENDED_CMS_MENUS #define USE_UAV_INTERCONNECT #define USE_RX_UIB From e030235c64f6bd1d0f25c21d697edfcc1e40b202 Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Thu, 18 Jun 2020 11:46:49 +0200 Subject: [PATCH 024/248] [BARO] Add DPS310 barometer driver; Enable on some Matek targets --- src/main/drivers/barometer/barometer_dps310.c | 318 ++++++++++++++++++ src/main/drivers/barometer/barometer_dps310.h | 29 ++ src/main/drivers/bus.h | 1 + src/main/fc/settings.yaml | 2 +- src/main/sensors/barometer.c | 30 +- src/main/sensors/barometer.h | 5 +- src/main/target/MATEKF405/target.h | 1 + src/main/target/MATEKF405/target.mk | 1 + src/main/target/MATEKF405SE/target.h | 1 + src/main/target/MATEKF405SE/target.mk | 1 + src/main/target/MATEKF411/target.h | 1 + src/main/target/MATEKF411/target.mk | 1 + src/main/target/MATEKF411SE/target.h | 1 + src/main/target/MATEKF411SE/target.mk | 1 + src/main/target/MATEKF722/target.h | 1 + src/main/target/MATEKF722/target.mk | 1 + src/main/target/MATEKF722PX/target.h | 1 + src/main/target/MATEKF722PX/target.mk | 1 + src/main/target/MATEKF722SE/target.h | 1 + src/main/target/MATEKF722SE/target.mk | 1 + src/main/target/MATEKF765/target.h | 1 + src/main/target/MATEKF765/target.mk | 1 + src/main/target/common_hardware.c | 12 + 23 files changed, 406 insertions(+), 7 deletions(-) create mode 100644 src/main/drivers/barometer/barometer_dps310.c create mode 100644 src/main/drivers/barometer/barometer_dps310.h diff --git a/src/main/drivers/barometer/barometer_dps310.c b/src/main/drivers/barometer/barometer_dps310.c new file mode 100644 index 00000000000..6cc7110ae55 --- /dev/null +++ b/src/main/drivers/barometer/barometer_dps310.c @@ -0,0 +1,318 @@ +/* + * This file is part of INAV. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + * + * Copyright: INAVFLIGHT OU + */ + +#include +#include +#include + +#include + +#include "build/build_config.h" +#include "build/debug.h" +#include "common/utils.h" + +#include "drivers/io.h" +#include "drivers/bus.h" +#include "drivers/time.h" +#include "drivers/barometer/barometer.h" +#include "drivers/barometer/barometer_dps310.h" + +#if defined(USE_BARO) && defined(USE_BARO_DPS310) + +#define DPS310_REG_PSR_B2 0x00 +#define DPS310_REG_PSR_B1 0x01 +#define DPS310_REG_PSR_B0 0x02 +#define DPS310_REG_TMP_B2 0x03 +#define DPS310_REG_TMP_B1 0x04 +#define DPS310_REG_TMP_B0 0x05 +#define DPS310_REG_PRS_CFG 0x06 +#define DPS310_REG_TMP_CFG 0x07 +#define DPS310_REG_MEAS_CFG 0x08 +#define DPS310_REG_CFG_REG 0x09 + +#define DPS310_REG_RESET 0x0C +#define DPS310_REG_ID 0x0D + +#define DPS310_REG_COEF 0x10 +#define DPS310_REG_COEF_SRCE 0x28 + + +#define DPS310_ID_REV_AND_PROD_ID (0x10) + +#define DPS310_RESET_BIT_SOFT_RST (0x09) // 0b1001 + +#define DPS310_MEAS_CFG_COEF_RDY (1 << 7) +#define DPS310_MEAS_CFG_SENSOR_RDY (1 << 6) +#define DPS310_MEAS_CFG_TMP_RDY (1 << 5) +#define DPS310_MEAS_CFG_PRS_RDY (1 << 4) +#define DPS310_MEAS_CFG_MEAS_CTRL_CONT (0x7) + +#define DPS310_PRS_CFG_BIT_PM_RATE_32HZ (0x50) // 101 - 32 measurements pr. sec. +#define DPS310_PRS_CFG_BIT_PM_PRC_16 (0x04) // 0100 - 16 times (Standard). + +#define DPS310_TMP_CFG_BIT_TMP_EXT (0x80) // +#define DPS310_TMP_CFG_BIT_TMP_RATE_32HZ (0x50) // 101 - 32 measurements pr. sec. +#define DPS310_TMP_CFG_BIT_TMP_PRC_16 (0x04) // 0100 - 16 times (Standard). + +#define DPS310_CFG_REG_BIT_P_SHIFT (0x04) +#define DPS310_CFG_REG_BIT_T_SHIFT (0x08) + +#define DPS310_COEF_SRCE_BIT_TMP_COEF_SRCE (0x80) + +typedef struct { + int16_t c0; // 12bit + int16_t c1; // 12bit + int32_t c00; // 20bit + int32_t c10; // 20bit + int16_t c01; // 16bit + int16_t c11; // 16bit + int16_t c20; // 16bit + int16_t c21; // 16bit + int16_t c30; // 16bit +} calibrationCoefficients_t; + +typedef struct { + calibrationCoefficients_t calib; + float pressure; // Pa + float temperature; // DegC +} baroState_t; + +static baroState_t baroState; + + +// Helper functions +static uint8_t registerRead(busDevice_t * busDev, uint8_t reg) +{ + uint8_t buf; + busRead(busDev, reg, &buf); + return buf; +} + +static void registerWrite(busDevice_t * busDev, uint8_t reg, uint8_t value) +{ + busWrite(busDev, reg, value); +} + +static void registerSetBits(busDevice_t * busDev, uint8_t reg, uint8_t setbits) +{ + uint8_t val = registerRead(busDev, reg); + + if ((val & setbits) != setbits) { + val |= setbits; + registerWrite(busDev, reg, val); + } +} + +static int32_t getTwosComplement(int32_t raw, uint8_t length) +{ + if (raw & ((int)1 << (length - 1))) { + raw -= (int)1 << length; + } + + return raw; +} + +static bool deviceConfigure(busDevice_t * busDev) +{ + // Trigger a chip reset + registerSetBits(busDev, DPS310_REG_RESET, DPS310_RESET_BIT_SOFT_RST); + + // Sleep 40ms + delay(40); + + uint8_t status = registerRead(busDev, DPS310_REG_MEAS_CFG); + + // Check if coefficients are available + if ((status & DPS310_MEAS_CFG_COEF_RDY) == 0) { + return false; + } + + // Check if sensor initialization is complete + if ((status & DPS310_MEAS_CFG_SENSOR_RDY) == 0) { + return false; + } + + // 1. Read the pressure calibration coefficients (c00, c10, c20, c30, c01, c11, and c21) from the Calibration Coefficient register. + // Note: The coefficients read from the coefficient register are 2's complement numbers. + uint8_t coef[18]; + if (!busReadBuf(busDev, DPS310_REG_COEF, coef, sizeof(coef))) { + return false; + } + + // 0x11 c0 [3:0] + 0x10 c0 [11:4] + baroState.calib.c0 = getTwosComplement(((uint32_t)coef[0] << 4) | (((uint32_t)coef[1] >> 4) & 0x0F), 12); + + // 0x11 c1 [11:8] + 0x12 c1 [7:0] + baroState.calib.c1 = getTwosComplement((((uint32_t)coef[1] & 0x0F) << 8) | (uint32_t)coef[2], 12); + + // 0x13 c00 [19:12] + 0x14 c00 [11:4] + 0x15 c00 [3:0] + baroState.calib.c00 = getTwosComplement(((uint32_t)coef[3] << 12) | ((uint32_t)coef[4] << 4) | (((uint32_t)coef[5] >> 4) & 0x0F), 20); + + // 0x15 c10 [19:16] + 0x16 c10 [15:8] + 0x17 c10 [7:0] + baroState.calib.c10 = getTwosComplement((((uint32_t)coef[5] & 0x0F) << 16) | ((uint32_t)coef[6] << 8) | (uint32_t)coef[7], 20); + + // 0x18 c01 [15:8] + 0x19 c01 [7:0] + baroState.calib.c01 = getTwosComplement(((uint32_t)coef[8] << 8) | (uint32_t)coef[9], 16); + + // 0x1A c11 [15:8] + 0x1B c11 [7:0] + baroState.calib.c11 = getTwosComplement(((uint32_t)coef[8] << 8) | (uint32_t)coef[9], 16); + + // 0x1C c20 [15:8] + 0x1D c20 [7:0] + baroState.calib.c20 = getTwosComplement(((uint32_t)coef[12] << 8) | (uint32_t)coef[13], 16); + + // 0x1E c21 [15:8] + 0x1F c21 [7:0] + baroState.calib.c21 = getTwosComplement(((uint32_t)coef[14] << 8) | (uint32_t)coef[15], 16); + + // 0x20 c30 [15:8] + 0x21 c30 [7:0] + baroState.calib.c30 = getTwosComplement(((uint32_t)coef[16] << 8) | (uint32_t)coef[17], 16); + + // PRS_CFG: pressure measurement rate (32 Hz) and oversampling (16 time standard) + registerSetBits(busDev, DPS310_REG_PRS_CFG, DPS310_PRS_CFG_BIT_PM_RATE_32HZ | DPS310_PRS_CFG_BIT_PM_PRC_16); + + // TMP_CFG: temperature measurement rate (32 Hz) and oversampling (16 times) + const uint8_t TMP_COEF_SRCE = registerRead(busDev, DPS310_REG_COEF_SRCE) & DPS310_COEF_SRCE_BIT_TMP_COEF_SRCE; + registerSetBits(busDev, DPS310_REG_TMP_CFG, DPS310_TMP_CFG_BIT_TMP_RATE_32HZ | DPS310_TMP_CFG_BIT_TMP_PRC_16 | TMP_COEF_SRCE); + + // CFG_REG: set pressure and temperature result bit-shift (required when the oversampling rate is >8 times) + registerSetBits(busDev, DPS310_REG_CFG_REG, DPS310_CFG_REG_BIT_T_SHIFT | DPS310_CFG_REG_BIT_P_SHIFT); + + // MEAS_CFG: Continuous pressure and temperature measurement + registerSetBits(busDev, DPS310_REG_MEAS_CFG, DPS310_MEAS_CFG_MEAS_CTRL_CONT); + + return true; +} + +static bool deviceReadMeasurement(baroDev_t *baro) +{ + // 1. Check if pressure is ready + bool pressure_ready = registerRead(baro->busDev, DPS310_REG_MEAS_CFG) & DPS310_MEAS_CFG_PRS_RDY; + if (!pressure_ready) { + return false; + } + + // 2. Choose scaling factors kT (for temperature) and kP (for pressure) based on the chosen precision rate. + // The scaling factors are listed in Table 9. + static float kT = 253952; // 16 times (Standard) + static float kP = 253952; // 16 times (Standard) + + // 3. Read the pressure and temperature result from the registers + // Read PSR_B2, PSR_B1, PSR_B0, TMP_B2, TMP_B1, TMP_B0 + uint8_t buf[6]; + if (busReadBuf(baro->busDev, DPS310_REG_PSR_B2, buf, 6)) { + return false; + } + + const int32_t Praw = getTwosComplement((buf[0] << 16) + (buf[1] << 8) + buf[2], 24); + const int32_t Traw = getTwosComplement((buf[3] << 16) + (buf[4] << 8) + buf[5], 24); + + // 4. Calculate scaled measurement results. + const float Praw_sc = Praw / kP; + const float Traw_sc = Traw / kT; + + // 5. Calculate compensated measurement results. + const float c00 = baroState.calib.c00; + const float c01 = baroState.calib.c01; + const float c10 = baroState.calib.c10; + const float c11 = baroState.calib.c11; + const float c20 = baroState.calib.c20; + const float c21 = baroState.calib.c21; + const float c30 = baroState.calib.c30; + + const float c0 = baroState.calib.c0; + const float c1 = baroState.calib.c1; + + baroState.pressure = c00 + Praw_sc * (c10 + Praw_sc * (c20 + Praw_sc * c30)) + Traw_sc * c01 + Traw_sc * Praw_sc * (c11 + Praw_sc * c21); + baroState.temperature = c0 * 0.5f + c1 * Traw_sc; + + return true; +} + +static bool deviceCalculate(baroDev_t *baro, int32_t *pressure, int32_t *temperature) +{ + UNUSED(baro); + + if (pressure) { + *pressure = baroState.pressure; + } + + if (temperature) { + *temperature = (baroState.temperature * 100); // to centidegrees + } + + return true; +} + + + +#define DETECTION_MAX_RETRY_COUNT 5 +static bool deviceDetect(busDevice_t * busDev) +{ + for (int retry = 0; retry < DETECTION_MAX_RETRY_COUNT; retry++) { + uint8_t chipId[1]; + + delay(100); + + bool ack = busReadBuf(busDev, DPS310_REG_ID, chipId, 1); + + if (ack && chipId[1] == DPS310_ID_REV_AND_PROD_ID) { + return true; + } + }; + + return false; +} + +bool baroDPS310Detect(baroDev_t *baro) +{ + baro->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_DPS310, 0, OWNER_BARO); + if (baro->busDev == NULL) { + return false; + } + + if (!deviceDetect(baro->busDev)) { + busDeviceDeInit(baro->busDev); + return false; + } + + if (!deviceConfigure(baro->busDev)) { + busDeviceDeInit(baro->busDev); + return false; + } + + baro->ut_delay = 0; + baro->start_ut = NULL; + baro->get_ut = NULL; + + baro->up_delay = 1000000 / 32 / 2; // twice the sample rate to capture all new data + baro->start_up = NULL; + baro->get_up = deviceReadMeasurement; + + baro->calculate = deviceCalculate; + + return true; +} + +#endif diff --git a/src/main/drivers/barometer/barometer_dps310.h b/src/main/drivers/barometer/barometer_dps310.h new file mode 100644 index 00000000000..314c282c5cd --- /dev/null +++ b/src/main/drivers/barometer/barometer_dps310.h @@ -0,0 +1,29 @@ +/* + * This file is part of INAV. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + * + * Copyright: INAVFLIGHT OU + */ + +#pragma once + +bool baroDPS310Detect(baroDev_t *baro); diff --git a/src/main/drivers/bus.h b/src/main/drivers/bus.h index 7f7d06d092f..d5a877f7d6b 100755 --- a/src/main/drivers/bus.h +++ b/src/main/drivers/bus.h @@ -104,6 +104,7 @@ typedef enum { DEVHW_LPS25H, DEVHW_SPL06, DEVHW_BMP388, + DEVHW_DPS310, /* Compass chips */ DEVHW_HMC5883, diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 5a760bde8fc..29da670777b 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -16,7 +16,7 @@ tables: values: ["NONE", "PMW3901", "CXOF", "MSP", "FAKE"] enum: opticalFlowSensor_e - name: baro_hardware - values: ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "FAKE"] + values: ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "DPS310", "FAKE"] enum: baroSensor_e - name: pitot_hardware values: ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE"] diff --git a/src/main/sensors/barometer.c b/src/main/sensors/barometer.c index f9e72f15a8a..567264f783c 100644 --- a/src/main/sensors/barometer.c +++ b/src/main/sensors/barometer.c @@ -38,6 +38,7 @@ #include "drivers/barometer/barometer_fake.h" #include "drivers/barometer/barometer_ms56xx.h" #include "drivers/barometer/barometer_spl06.h" +#include "drivers/barometer/barometer_dps310.h" #include "drivers/time.h" #include "fc/runtime_config.h" @@ -172,6 +173,19 @@ bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse) } FALLTHROUGH; + case BARO_DPS310: +#if defined(USE_BARO_DPS310) + if (baroDPS310Detect(dev)) { + baroHardware = BARO_DPS310; + break; + } +#endif + /* If we are asked for a specific sensor - break out, otherwise - fall through and continue */ + if (baroHardwareToUse != BARO_AUTODETECT) { + break; + } + FALLTHROUGH; + case BARO_FAKE: #ifdef USE_FAKE_BARO if (fakeBaroDetect(dev)) { @@ -265,15 +279,23 @@ uint32_t baroUpdate(void) switch (state) { default: case BAROMETER_NEEDS_SAMPLES: - baro.dev.get_ut(&baro.dev); - baro.dev.start_up(&baro.dev); + if (baro.dev.get_ut) { + baro.dev.get_ut(&baro.dev); + } + if (baro.dev.start_up) { + baro.dev.start_up(&baro.dev); + } state = BAROMETER_NEEDS_CALCULATION; return baro.dev.up_delay; break; case BAROMETER_NEEDS_CALCULATION: - baro.dev.get_up(&baro.dev); - baro.dev.start_ut(&baro.dev); + if (baro.dev.get_up) { + baro.dev.get_up(&baro.dev); + } + if (baro.dev.start_ut) { + baro.dev.start_ut(&baro.dev); + } baro.dev.calculate(&baro.dev, &baro.baroPressure, &baro.baroTemperature); if (barometerConfig()->use_median_filtering) { baro.baroPressure = applyBarometerMedianFilter(baro.baroPressure); diff --git a/src/main/sensors/barometer.h b/src/main/sensors/barometer.h index 3e10700f0c7..6301c79b0b6 100644 --- a/src/main/sensors/barometer.h +++ b/src/main/sensors/barometer.h @@ -29,9 +29,10 @@ typedef enum { BARO_BMP280 = 4, BARO_MS5607 = 5, BARO_LPS25H = 6, - BARO_SPL06 = 7, + BARO_SPL06 = 7, BARO_BMP388 = 8, - BARO_FAKE = 9, + BARO_DPS310 = 9, + BARO_FAKE = 10, BARO_MAX = BARO_FAKE } baroSensor_e; diff --git a/src/main/target/MATEKF405/target.h b/src/main/target/MATEKF405/target.h index 077155b1ff3..37e7f78096c 100644 --- a/src/main/target/MATEKF405/target.h +++ b/src/main/target/MATEKF405/target.h @@ -147,6 +147,7 @@ #define USE_BARO_BMP280 #define USE_BARO_MS5611 #define USE_BARO_BMP085 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS diff --git a/src/main/target/MATEKF405/target.mk b/src/main/target/MATEKF405/target.mk index dd5ce7864a0..62dd163f0c4 100755 --- a/src/main/target/MATEKF405/target.mk +++ b/src/main/target/MATEKF405/target.mk @@ -7,6 +7,7 @@ TARGET_SRC = \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms56xx.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_ak8963.c \ drivers/compass/compass_ak8975.c \ drivers/compass/compass_hmc5883l.c \ diff --git a/src/main/target/MATEKF405SE/target.h b/src/main/target/MATEKF405SE/target.h index 513b14a8b25..81681b94f55 100644 --- a/src/main/target/MATEKF405SE/target.h +++ b/src/main/target/MATEKF405SE/target.h @@ -58,6 +58,7 @@ #define USE_BARO_BMP280 #define USE_BARO_MS5611 #define USE_BARO_BMP085 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 diff --git a/src/main/target/MATEKF405SE/target.mk b/src/main/target/MATEKF405SE/target.mk index 8a0cc40ea76..13886f855eb 100644 --- a/src/main/target/MATEKF405SE/target.mk +++ b/src/main/target/MATEKF405SE/target.mk @@ -6,6 +6,7 @@ TARGET_SRC = \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms56xx.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_ak8963.c \ drivers/compass/compass_ak8975.c \ drivers/compass/compass_hmc5883l.c \ diff --git a/src/main/target/MATEKF411/target.h b/src/main/target/MATEKF411/target.h index 7063d18c381..967e3c0ef8e 100755 --- a/src/main/target/MATEKF411/target.h +++ b/src/main/target/MATEKF411/target.h @@ -118,6 +118,7 @@ #define USE_BARO_BMP280 #define USE_BARO_MS5611 #define USE_BARO_BMP085 +#define USE_BARO_DPS310 #define TEMPERATURE_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF411/target.mk b/src/main/target/MATEKF411/target.mk index f383248f318..1ea03d20db7 100755 --- a/src/main/target/MATEKF411/target.mk +++ b/src/main/target/MATEKF411/target.mk @@ -7,6 +7,7 @@ TARGET_SRC = \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms56xx.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_mag3110.c \ drivers/compass/compass_qmc5883l.c \ diff --git a/src/main/target/MATEKF411SE/target.h b/src/main/target/MATEKF411SE/target.h index cbffcd1a2c1..790be95bac3 100755 --- a/src/main/target/MATEKF411SE/target.h +++ b/src/main/target/MATEKF411SE/target.h @@ -95,6 +95,7 @@ #define USE_BARO_BMP280 #define USE_BARO_MS5611 #define USE_BARO_BMP085 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF411SE/target.mk b/src/main/target/MATEKF411SE/target.mk index ee090ce48f7..94819998682 100755 --- a/src/main/target/MATEKF411SE/target.mk +++ b/src/main/target/MATEKF411SE/target.mk @@ -6,6 +6,7 @@ TARGET_SRC = \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms56xx.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_mag3110.c \ drivers/compass/compass_qmc5883l.c \ diff --git a/src/main/target/MATEKF722/target.h b/src/main/target/MATEKF722/target.h index 62227998e8d..a99a60afc14 100755 --- a/src/main/target/MATEKF722/target.h +++ b/src/main/target/MATEKF722/target.h @@ -56,6 +56,7 @@ #define USE_BARO_BMP280 #define USE_BARO_MS5611 #define USE_BARO_BMP085 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF722/target.mk b/src/main/target/MATEKF722/target.mk index f221bb51ca9..a62d66f5322 100755 --- a/src/main/target/MATEKF722/target.mk +++ b/src/main/target/MATEKF722/target.mk @@ -5,6 +5,7 @@ TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_dps310.c \ drivers/barometer/barometer_ms56xx.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ diff --git a/src/main/target/MATEKF722PX/target.h b/src/main/target/MATEKF722PX/target.h index 38e9a8f3803..f2f1bca2420 100755 --- a/src/main/target/MATEKF722PX/target.h +++ b/src/main/target/MATEKF722PX/target.h @@ -53,6 +53,7 @@ #define BARO_I2C_BUS BUS_I2C1 #define USE_BARO_BMP280 #define USE_BARO_MS5611 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF722PX/target.mk b/src/main/target/MATEKF722PX/target.mk index 0db5e55e787..3b7c3615dd1 100755 --- a/src/main/target/MATEKF722PX/target.mk +++ b/src/main/target/MATEKF722PX/target.mk @@ -5,6 +5,7 @@ TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms56xx.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_ak8975.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ diff --git a/src/main/target/MATEKF722SE/target.h b/src/main/target/MATEKF722SE/target.h index 56dcdcc886f..7942a30e218 100644 --- a/src/main/target/MATEKF722SE/target.h +++ b/src/main/target/MATEKF722SE/target.h @@ -70,6 +70,7 @@ #define BARO_I2C_BUS BUS_I2C1 #define USE_BARO_BMP280 #define USE_BARO_MS5611 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF722SE/target.mk b/src/main/target/MATEKF722SE/target.mk index 63b91d30001..19ae98915c2 100644 --- a/src/main/target/MATEKF722SE/target.mk +++ b/src/main/target/MATEKF722SE/target.mk @@ -7,6 +7,7 @@ TARGET_SRC = \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms56xx.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_ak8975.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ diff --git a/src/main/target/MATEKF765/target.h b/src/main/target/MATEKF765/target.h index fcddab26937..8fefd8d077e 100644 --- a/src/main/target/MATEKF765/target.h +++ b/src/main/target/MATEKF765/target.h @@ -74,6 +74,7 @@ #define BARO_I2C_BUS BUS_I2C2 #define USE_BARO_BMP280 #define USE_BARO_MS5611 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 diff --git a/src/main/target/MATEKF765/target.mk b/src/main/target/MATEKF765/target.mk index 11d75e59b31..9e34a0864e2 100644 --- a/src/main/target/MATEKF765/target.mk +++ b/src/main/target/MATEKF765/target.mk @@ -7,6 +7,7 @@ TARGET_SRC = \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms56xx.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ drivers/compass/compass_ist8310.c \ diff --git a/src/main/target/common_hardware.c b/src/main/target/common_hardware.c index 1e35d2baef5..418d01a9fcc 100755 --- a/src/main/target/common_hardware.c +++ b/src/main/target/common_hardware.c @@ -149,6 +149,18 @@ #endif #endif +#if defined(USE_BARO_DPS310) + #if defined(DPS310_SPI_BUS) + BUSDEV_REGISTER_SPI(busdev_dps310, DEVHW_DPS310, DPS310_SPI_BUS, DPS310_CS_PIN, NONE, DEVFLAGS_NONE, 0); + #elif defined(DPS310_I2C_BUS) || defined(BARO_I2C_BUS) + #if !defined(DPS310_I2C_BUS) + #define DPS310_I2C_BUS BARO_I2C_BUS + #endif + BUSDEV_REGISTER_I2C(busdev_dps310, DEVHW_DPS310, DPS310_I2C_BUS, 0x77, NONE, DEVFLAGS_NONE, 0); + #endif +#endif + + /** COMPASS SENSORS **/ #if !defined(USE_TARGET_MAG_HARDWARE_DESCRIPTORS) #if defined(USE_MAG_HMC5883) From 676596c2eb201d1d6f7154adbcac8ae5a2f46da6 Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Thu, 18 Jun 2020 15:50:30 +0200 Subject: [PATCH 025/248] [BARO] Fix DPS310 I2C address --- src/main/target/common_hardware.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/common_hardware.c b/src/main/target/common_hardware.c index 418d01a9fcc..b372e9c8f74 100755 --- a/src/main/target/common_hardware.c +++ b/src/main/target/common_hardware.c @@ -156,7 +156,7 @@ #if !defined(DPS310_I2C_BUS) #define DPS310_I2C_BUS BARO_I2C_BUS #endif - BUSDEV_REGISTER_I2C(busdev_dps310, DEVHW_DPS310, DPS310_I2C_BUS, 0x77, NONE, DEVFLAGS_NONE, 0); + BUSDEV_REGISTER_I2C(busdev_dps310, DEVHW_DPS310, DPS310_I2C_BUS, 0x76, NONE, DEVFLAGS_NONE, 0); #endif #endif From ac43b52599da138149a738686c4d57a6b7034a03 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Niccol=C3=B2=20Maggioni?= Date: Mon, 15 Jun 2020 16:40:39 +0200 Subject: [PATCH 026/248] Autogenerate CLI docs from settings.yaml --- docs/Cli.md | 635 +++++++++++++++------------- src/main/fc/settings.yaml | 772 +++++++++++++++++++++++++++++++++++ src/utils/update_cli_docs.py | 131 ++++++ 3 files changed, 1245 insertions(+), 293 deletions(-) create mode 100755 src/utils/update_cli_docs.py diff --git a/docs/Cli.md b/docs/Cli.md index 851f623f89d..391182da546 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -125,276 +125,161 @@ A shorter form is also supported to enable and disable functions using `serial < ## CLI Variable Reference -| Variable Name | Default Value | Description | -| ------ | ------ | ------ | -| looptime | 1000 | This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible. | -| i2c_speed | 400KHZ | This setting controls the clock speed of I2C bus. 400KHZ is the default that most setups are able to use. Some noise-free setups may be overclocked to 800KHZ. Some sensor chips or setups with long wires may work unreliably at 400KHZ - user can try lowering the clock speed to 200KHZ or even 100KHZ. User need to bear in mind that lower clock speeds might require higher looptimes (lower looptime rate) | -| cpu_underclock | OFF | This option is only available on certain architectures (F3 CPUs at the moment). It makes CPU clock lower to reduce interference to long-range RC systems working at 433MHz | -| gyro_sync | OFF | This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf | -| min_check | 1100 | These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value. | -| max_check | 1900 | These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value. | -| rssi_channel | 0 | RX channel containing the RSSI signal | -| rssi_min | 0 | The minimum RSSI value sent by the receiver, in %. For example, if your receiver's minimum RSSI value shows as 42% in the configurator/OSD set this parameter to 42. See also rssi_max. Note that rssi_min can be set to a value bigger than rssi_max to invert the RSSI calculation (i.e. bigger values mean lower RSSI). | -| rssi_max | 100 | The maximum RSSI value sent by the receiver, in %. For example, if your receiver's maximum RSSI value shows as 83% in the configurator/OSD set this parameter to 83. See also rssi_min. | -| rc_filter_frequency | 50 | RC data biquad filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay. Practical values are 20-50. Set to zero to disable entirely and use unsmoothed RC stick values | -| input_filtering_mode | OFF | Filter out noise from OpenLRS Telemetry RX | -| throttle_idle | 15 | The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle. | -| max_throttle | 1850 | This is the maximum value (in us) sent to esc when armed. Default of 1850 are OK for everyone (legacy). For modern ESCs, higher values (c. 2000) may be more appropriate. If you have brushed motors, the value should be set to 2000. | -| min_command | 1000 | This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly when powered up, try decreasing this value. It can also be used for calibrating all ESCs at once. | -| 3d_deadband_low | 1406 | Low value of throttle deadband for 3D mode (when stick is in the 3d_deadband_throttle range, the fixed values of 3d_deadband_low / _high are used instead) | -| 3d_deadband_high | 1514 | High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead) | -| 3d_neutral | 1460 | Neutral (stop) throttle value for 3D mode | -| 3d_deadband_throttle | 50 | Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter. | -| motor_pwm_rate | 400 | Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000. | -| motor_pwm_protocol | STANDARD | Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED | -| fixed_wing_auto_arm | OFF | Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured. | -| disarm_kill_switch | ON | Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel. | -| switch_disarm_delay | 250 | Delay before disarming when requested by switch (ms) [0-1000] | -| small_angle | 25 | If the aircraft tilt angle exceed this value the copter will refuse to arm. | -| reboot_character | 82 | Special character used to trigger reboot | -| gps_provider | UBLOX | Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N). | -| gps_sbas_mode | NONE | Which SBAS mode to be used | -| gps_dyn_model | AIR_1G | GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying. | -| gps_auto_config | ON | Enable automatic configuration of UBlox GPS receivers. | -| gps_auto_baud | ON | Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS. When used with NAZA/DJI it will automatic detect GPS baudrate and change to it, ignoring the selected baudrate set in ports | -| gps_min_sats | 6 | Minimum number of GPS satellites in view to acquire GPS_FIX and consider GPS position valid. Some GPS receivers appeared to be very inaccurate with low satellite count. | -| gps_ublox_use_galileo | OFF | Enable use of Galileo satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires M8N and Ublox firmware 3.x (or later) [OFF/ON]. -| inav_auto_mag_decl | ON | Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored. | -| inav_gravity_cal_tolerance | 5 | Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value. | -| inav_use_gps_velned | ON | Defined if iNav should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF iNav will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance. | -| inav_reset_altitude | FIRST_ARM | Defines when relative estimated altitude is reset to zero. Variants - `NEVER` (once reference is acquired it's used regardless); `FIRST_ARM` (keep altitude at zero until firstly armed), `EACH_ARM` (altitude is reset to zero on each arming) | -| inav_reset_home | FIRST_ARM | Allows to chose when the home position is reset. Can help prevent resetting home position after accidental mid-air disarm. Possible values are: NEVER, FIRST_ARM and EACH_ARM | -| inav_max_surface_altitude | 200 | Max allowed altitude for surface following mode. [cm] | -| inav_w_z_baro_p | 0.350 | Weight of barometer measurements in estimated altitude and climb rate | -| inav_w_z_gps_p | 0.200 | Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes | -| inav_w_z_gps_v | 0.500 | Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero | -| inav_w_xy_gps_p | 1.000 | Weight of GPS coordinates in estimated UAV position and speed. | -| inav_w_xy_gps_v | 2.000 | Weight of GPS velocity data in estimated UAV speed | -| inav_w_z_res_v | 0.500 | Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost | -| inav_w_xy_res_v | 0.500 | Decay coefficient for estimated velocity when GPS reference for position is lost | -| inav_w_acc_bias | 0.010 | Weight for accelerometer drift estimation | -| inav_max_eph_epv | 1000.000 | Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm] | -| inav_baro_epv | 100.000 | Uncertainty value for barometric sensor [cm] | -| name | Empty string | Craft name | -| nav_disarm_on_landing | OFF | If set to ON, iNav disarms the FC after landing | -| nav_use_midthr_for_althold | OFF | If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude | -| nav_extra_arming_safety | ON | If set to ON drone won't arm if no GPS fix and any navigation mode like RTH or POSHOLD is configured. ALLOW_BYPASS allows the user to momentarily disable this check by holding yaw high (left stick held at the bottom right in mode 2) when switch arming is used | -| nav_user_control_mode | ATTI | Defines how Pitch/Roll input from RC receiver affects flight in POSHOLD mode: ATTI - pitch/roll controls attitude like in ANGLE mode; CRUISE - pitch/roll controls velocity in forward and right direction. | -| nav_position_timeout | 5 | If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable) | -| nav_wp_radius | 100 | Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius | -| nav_wp_safe_distance | 10000 | First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check. | -| nav_auto_speed | 300 | Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only] | -| nav_auto_climb_rate | 500 | Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s] | -| nav_manual_speed | 500 | Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only] | -| nav_manual_climb_rate | 200 | Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] | -| nav_landing_speed | 200 | Vertical descent velocity during the RTH landing phase. [cm/s] | -| nav_land_slowdown_minalt | 500 | Defines at what altitude the descent velocity should start to be 25% of nav_landing_speed [cm] | -| nav_land_slowdown_maxalt | 2000 | Defines at what altitude the descent velocity should start to ramp down from 100% nav_landing_speed to 25% nav_landing_speed. [cm] | -| nav_emerg_landing_speed | 500 | Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s] | -| nav_min_rth_distance | 500 | Minimum distance from homepoint when RTH full procedure will be activated [cm]. Below this distance, the mode will activate at the current location and the final phase is executed (loiter / land). Above this distance, the full procedure is activated, which may include initial climb and flying directly to the homepoint before entering the loiter / land phase. | -| nav_overrides_motor_stop | ON | Setting to OFF combined with MOTOR_STOP feature will allow user to stop motor when in autonomous modes. On most places this setting is likely to cause a stall. | -| nav_rth_climb_first | ON | If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way. | -| nav_rth_tail_first | OFF | If set to ON drone will return tail-first. Obviously meaningless for airplanes. | -| nav_rth_allow_landing | ALWAYS | If set to ON drone will land as a last phase of RTH. | -| nav_rth_climb_ignore_emerg | OFF | If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status. | -| nav_rth_alt_mode | AT_LEAST | Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details | -| nav_rth_altitude | 1000 | Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters) | -| nav_rth_home_altitude | 0 | Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm] | -| nav_rth_abort_threshold | 50000 | RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. [cm] | -| nav_rth_home_offset_distance | 0 | Distance offset from GPS established home to "safe" position used for RTH (cm, 0 disables) | -| nav_rth_home_offset_direction | 0 | Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) | -| nav_mc_bank_angle | 30 | Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude | -| nav_mc_hover_thr | 1500 | Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering. | -| nav_mc_auto_disarm_delay | 2000 | | -| nav_fw_cruise_thr | 1400 | Cruise throttle in GPS assisted modes, this includes RTH. Should be set high enough to avoid stalling. This values gives INAV a base for throttle when flying straight, and it will increase or decrease throttle based on pitch of airplane and the parameters below. In addition it will increase throttle if GPS speed gets below 7m/s ( hardcoded ) | -| nav_fw_cruise_speed | 0 | Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s | -| nav_fw_allow_manual_thr_increase | OFF | Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing | -| nav_fw_min_thr | 1200 | Minimum throttle for flying wing in GPS assisted modes | -| nav_fw_max_thr | 1700 | Maximum throttle for flying wing in GPS assisted modes | -| nav_fw_bank_angle | 20 | Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll | -| nav_fw_climb_angle | 20 | Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit | -| nav_fw_dive_angle | 15 | Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit | -| nav_fw_pitch2thr | 10 | Amount of throttle applied related to pitch attitude in GPS assisted modes. Throttle = nav_fw_cruise_throttle - (nav_fw_pitch2thr * pitch_angle). (notice that pitch_angle is in degrees and is negative when climbing and positive when diving, and throttle value is constrained between nav_fw_min_thr and nav_fw_max_thr) | -| nav_fw_control_smoothness | 0 | How smoothly the autopilot controls the airplane to correct the navigation error | -| nav_fw_loiter_radius | 5000 | PosHold radius. 3000 to 7500 is a good value (30-75m) [cm] | -| nav_fw_launch_velocity | 300 | Forward velocity threshold for swing-launch detection [cm/s] | -| nav_fw_launch_accel | 1863 | Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s | -| nav_fw_launch_max_angle | 45 | Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg] | -| nav_fw_launch_detect_time | 40 | Time for which thresholds have to breached to consider launch happened [ms] | -| nav_fw_launch_thr | 1700 | Launch throttle - throttle to be set during launch sequence (pwm units) | -| nav_fw_launch_idle_thr | 1000 | Launch idle throttle - throttle to be set before launch sequence is initiated. If set below minimum throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above minimum throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position) | -| nav_fw_launch_motor_delay | 500 | Delay between detected launch and launch sequence start and throttling up (ms) | -| nav_fw_launch_spinup_time | 100 | Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller | -| nav_fw_launch_timeout | 5000 | Maximum time for launch sequence to be executed. After this time LAUNCH mode will be turned off and regular flight mode will take over (ms) | -| nav_fw_launch_max_altitude | 0 | Altitude at which LAUNCH mode will be turned off and regular flight mode will take over. [cm] | -| nav_fw_launch_climb_angle | 18 | Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit | -| nav_fw_launch_min_time | 0 | Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]. | -| nav_fw_launch_max_altitude | 0 | Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]. | -| nav_fw_land_dive_angle | 2 | Dive angle that airplane will use during final landing phase. During dive phase, motor is stopped or IDLE and roll control is locked to 0 degrees | -| nav_fw_cruise_yaw_rate | 20 | Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps]| -| nav_use_fw_yaw_control | OFF | Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats | -| serialrx_provider | SPEK1024 | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. | -| serialrx_halfduplex | OFF | Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire | -| serialrx_inverted | OFF | Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY). | -| spektrum_sat_bind | 0 | 0 = disabled. Used to bind the spektrum satellite to RX | -| telemetry_switch | OFF | Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed. | -| telemetry_inverted | OFF | Determines if the telemetry protocol default signal inversion is reversed. This should be OFF in most cases unless a custom or hacked RX is used. | -| frsky_unit | METRIC | Not used? [METRIC/IMPERIAL] | -| frsky_default_latitude | 0.000 | D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. | -| frsky_default_longitude | 0.000 | D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. | -| frsky_coordinates_format | 0 | D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA | -| frsky_vfas_precision | 0 | D-Series telemetry only: Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method | -| frsky_pitch_roll | OFF | S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data | -| smartport_fuel_unit | MAH | S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends precent). [PERCENT/MAH/MWH] | -| telemetry_halfduplex | OFF | S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details | -| report_cell_voltage | OFF | S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON | -| hott_alarm_sound_interval | 5 | Battery alarm delay in seconds for Hott telemetry | -| smartport_fuel_unit | MAH | S.Port and D-Series telemetry: Unit of the value sent with the `FUEL` ID. [PERCENT/MAH/MWH] | -| ibus_telemetry_type | 0 | Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details. | -| ltm_update_rate | NORMAL | Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details. | -| battery_capacity | 0 | Battery capacity in mAH. This value is used in conjunction with the current meter to determine remaining battery capacity. | -| vbat_scale | 1100 | Battery voltage calibration value. 1100 = 11:1 voltage divider (10k:1k) x 100. Adjust this slightly if reported pack voltage is different from multimeter reading. You can get current voltage by typing "status" in cli. | -| bat_voltage_src | RAW | Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP` | -| bat_cells | 0 | Number of cells of the battery (0 = autodetect), see battery documentation | -| vbat_cell_detect_voltage | 430 | Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units, default is 4.30V | -| vbat_max_cell_voltage | 420 | Maximum voltage per cell in 0.01V units, default is 4.20V | -| vbat_min_cell_voltage | 330 | Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V) | -| vbat_warning_cell_voltage | 350 | Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V) | -| current_meter_scale | 400 | This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt. | -| current_meter_offset | 0 | This sets the output offset voltage of the current sensor in millivolts. | -| battery_capacity | 0 | Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity. | -| battery_capacity_warning | 0 | If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink. | -| battery_capacity_critical | 0 | If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps. | -| battery_capacity_unit | MAH | Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour). | -| cruise_power | 0 | Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit | -| idle_power | 0 | Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit | -| rth_energy_margin | 5 | Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation | -| multiwii_current_meter_output | OFF | Default current output via MSP is in 0.01A steps. Setting this to 1 causes output in default multiwii scaling (1mA steps) | -| current_meter_type | ADC | ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position. | -| align_gyro | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. | -| align_acc | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. | -| align_mag | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. | -| align_board_roll | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | -| align_board_pitch | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | -| align_board_yaw | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | -| align_mag_roll | 0 | Set the external mag alignment on the roll axis (in 0.1 degree steps). If this value is non-zero, the compass is assumed to be externally mounted and both the board and on-board compass alignent (align_mag) are ignored. See also align_mag_pitch and align_mag_yaw. | -| align_mag_pitch | 0 | Same as align_mag_roll, but for the pitch axis. | -| align_mag_yaw | 0 | Same as align_mag_roll, but for the yaw axis. | -| align_opflow | 5 | Optical flow module alignment (default CW0_DEG_FLIP) | -| gyro_hardware_lpf | 42HZ | Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first. | -| moron_threshold | 32 | When powering up, gyro bias is calculated. If the model is shaking/moving during this initial calibration, offsets are calculated incorrectly, and could lead to poor flying performance. This threshold means how much average gyro reading could differ before re-calibration is triggered. | -| imu_dcm_kp | 2500 | Inertial Measurement Unit KP Gain for accelerometer measurements | -| imu_dcm_ki | 50 | Inertial Measurement Unit KI Gain for accelerometer measurements | -| imu_dcm_kp_mag | 10000 | Inertial Measurement Unit KP Gain for compass measurements | -| imu_dcm_ki_mag | 0 | Inertial Measurement Unit KI Gain for compass measurements | -| imu_acc_ignore_rate | 0 | Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes | -| imu_acc_ignore_slope | 0 | Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight) | -| pos_hold_deadband | 20 | Stick deadband in [r/c points], applied after r/c deadband and expo | -| alt_hold_deadband | 50 | Defines the deadband of throttle during alt_hold [r/c points] | -| motor_direction_inverted | OFF | Use if you need to inverse yaw motor direction. | -| tri_unarmed_servo | ON | On tricopter mix only, if this is set to ON, servo will always be correcting regardless of armed state. to disable this, set it to OFF. | -| servo_protocol | PWM | An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SERVO_DRIVER` (I2C PCA9685 peripheral), `SBUS` (S.Bus protocol output via a configured serial port) | -| servo_lpf_hz | 20 | Selects the servo PWM output cutoff frequency. Value is in [Hz] | -| servo_center_pulse | 1500 | Servo midpoint | -| servo_pwm_rate | 50 | Output frequency (in Hz) servo pins. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz. | -| failsafe_delay | 5 | Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). | -| failsafe_recovery_delay | 5 | Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay). | -| failsafe_off_delay | 200 | Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay). | -| failsafe_throttle | 1000 | Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | -| failsafe_throttle_low_delay | 100 | If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout | -| failsafe_procedure | SET-THR | What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | -| failsafe_stick_threshold | 50 | Threshold for stick motion to consider failsafe condition resolved. If non-zero failsafe won't clear even if RC link is restored - you have to move sticks to exit failsafe. | -| failsafe_fw_roll_angle | -200 | Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll | -| failsafe_fw_pitch_angle | 100 | Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb | -| failsafe_fw_yaw_rate | -45 | Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn | -| failsafe_min_distance | 0 | If failsafe happens when craft is closer than this distance in centimeters from home, failsafe will not execute regular failsafe_procedure, but will execute procedure specified in failsafe_min_distance_procedure instead. 0 = Normal failsafe_procedure always taken. | -| failsafe_min_distance_procedure | DROP | What failsafe procedure to initiate in Stage 2 when craft is closer to home than failsafe_min_distance. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | -| failsafe_lights | ON | Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]. | -| failsafe_lights_flash_period | 1000 | Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]. | -| failsafe_lights_flash_on_time | 100 | Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]. | -| failsafe_mission | ON | If set to `OFF` the failsafe procedure won't be triggered and the mission will continue if the FC is in WP (automatic mission) mode | -| rx_min_usec | 885 | Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc. | -| rx_max_usec | 2115 | Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of mid_rc. | -| rx_nosignal_throttle | HOLD | Defines behavior of throttle channel after signal loss is detected and until `failsafe_procedure` kicks in. Possible values - `HOLD` and `DROP`. | -| acc_hardware | AUTO | Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info | -| baro_median_filter | ON | 3-point median filtering for barometer readouts. No reason to change this setting | -| baro_hardware | AUTO | Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info | -| mag_hardware | AUTO | Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info | -| mag_to_use | | Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target | -| rangefinder_median_filter | OFF | 3-point median filtering for rangefinder readouts | -| blackbox_rate_num | 1 | Blackbox logging rate numerator. Use num/denom settings to decide if a frame should be logged, allowing control of the portion of logged loop iterations | -| blackbox_rate_denom | 1 | Blackbox logging rate denominator. See blackbox_rate_num. | -| blackbox_device | SPIFLASH | Selection of where to write blackbox data | -| sdcard_detect_inverted | `TARGET dependent` | This setting drives the way SD card is detected in card slot. On some targets (AnyFC F7 clone) different card slot was used and depending of hardware revision ON or OFF setting might be required. If card is not detected, change this value. | -| ledstrip_visual_beeper | OFF | | -| osd_video_system | AUTO | Video system used. Possible values are `AUTO`, `PAL` and `NTSC` | -| osd_row_shiftdown | 0 | Number of rows to shift the OSD display (increase if top rows are cut off) | -| osd_units | METRIC| IMPERIAL, METRIC, UK | -| osd_stats_energy_unit | MAH | Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour) | -| osd_main_voltage_decimals | 1 | Number of decimals for the battery voltages displayed in the OSD [1-2]. | -| osd_rssi_alarm | 20 | Value bellow which to make the OSD RSSI indicator blink | -| osd_time_alarm | 10 | Value above which to make the OSD flight time indicator blink (minutes) | -| osd_dist_alarm | 1000 | Value above which to make the OSD distance from home indicator blink (meters) | -| osd_alt_alarm | 100 | Value above which to make the OSD relative altitude indicator blink (meters) | -| osd_neg_alt_alarm | 5 | Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters) | -| osd_gforce_alarm | 5 | Value above which the OSD g force indicator will blink (g) | -| osd_gforce_axis_alarm_min | -5 | Value under which the OSD axis g force indicators will blink (g) | -| osd_gforce_axis_alarm_max | 5 | Value above which the OSD axis g force indicators will blink (g) | -| osd_imu_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | -| osd_imu_temp_alarm_max | 600 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | -| osd_esc_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | -| osd_esc_temp_alarm_max | 900 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | -| osd_baro_temp_alarm_min | -200 | Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade) | -| osd_baro_temp_alarm_max | 600 | Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade) | -| osd_current_alarm | 0 | Value above which the OSD current consumption element will start blinking. Measured in full Amperes. | -| osd_estimations_wind_compensation | ON | Use wind estimation for remaining flight time/distance estimation | -| osd_failsafe_switch_layout | OFF | If enabled the OSD automatically switches to the first layout during failsafe | -| osd_temp_label_align | LEFT | Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT` | -| osd_hud_wp_disp | OFF | Controls display of the next waypoints in the HUD.| -| osd_ahi_style | DEFAULT | Sets OSD Artificial Horizon style "DEFAULT" or "LINE" for the FrSky Graphical OSD. | -| display_force_sw_blink | OFF | OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON | -| magzero_x | 0 | Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed. | -| magzero_y | 0 | Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed. | -| magzero_z | 0 | Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed. | -| acczero_x | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | -| acczero_y | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | -| acczero_z | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | -| accgain_x | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | -| accgain_y | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | -| accgain_z | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | -| nav_mc_pos_z_p | 50 | P gain of altitude PID controller (Multirotor) | -| nav_fw_pos_z_p | 50 | P gain of altitude PID controller (Fixedwing) | -| nav_fw_pos_z_i | 0 | I gain of altitude PID controller (Fixedwing) | -| nav_fw_pos_z_d | 0 | D gain of altitude PID controller (Fixedwing) | -| nav_mc_vel_z_p | 100 | P gain of velocity PID controller | -| nav_mc_vel_z_i | 50 | I gain of velocity PID controller | -| nav_mc_vel_z_d | 10 | D gain of velocity PID controller | -| nav_mc_pos_xy_p | 65 | Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity | -| nav_mc_vel_xy_p | 40 | P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause "nervous" behavior and oscillations | -| nav_mc_vel_xy_i | 15 | I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot | -| nav_mc_vel_xy_d | 100 | D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target. | -| nav_fw_pos_xy_p | 75 | P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH | -| nav_fw_pos_xy_i | 5 | I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero | -| nav_fw_pos_xy_d | 8 | D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero | -| nav_fw_pos_hdg_p | 60 | P gain of heading PID controller. (Fixedwing, rovers, boats) | -| nav_fw_pos_hdg_i | 0 | I gain of heading trajectory PID controller. (Fixedwing, rovers, boats) | -| nav_fw_pos_hdg_d | 0 | D gain of heading trajectory PID controller. (Fixedwing, rovers, boats) | -| nav_fw_pos_hdg_pidsum_limit | 350 | Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats) | -| nav_fw_yaw_deadband | 0 | Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course | -| nav_mc_heading_p | 60 | P gain of Heading Hold controller (Multirotor) | -| nav_fw_heading_p | 60 | P gain of Heading Hold controller (Fixedwing) | -| deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. | -| yaw_deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. | -| throttle_tilt_comp_str | 0 | Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled. | -| flaperon_throw_offset | 200 | Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated. | -| fw_iterm_throw_limit | 165 | Limits max/min I-term value in stabilization PID controller in case of Fixed Wing. It solves the problem of servo saturation before take-off/throwing the airplane into the air. By default, error accumulated in I-term can not exceed 1/3 of servo throw (around 165us). Set 0 to disable completely. | -| fw_reference_airspeed | 1000 | Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present. | -| fw_turn_assist_yaw_gain | 1 | Gain required to keep the yaw rate consistent with the turn rate for a coordinated turn (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter | -| fw_loiter_direction | RIGHT | Direction of loitering: center point on right wing (clockwise - default), or center point on left wing (counterclockwise). If equal YAW then can be changed in flight using a yaw stick. | -| mode_range_logic_operator | OR | Control how Mode selection works in flight modes. If you example have Angle mode configured on two different Aux channels, this controls if you need both activated ( AND ) or if you only need one activated ( OR ) to active angle mode. | -| default_rate_profile | 0 | Default = profile number | -| mag_declination | 0 | Current location magnetic declination in format. For example, -6deg 37min = -637 for Japan. Leading zero in ddd not required. Get your local magnetic declination here: http://magnetic-declination.com/ . Not in use if inav_auto_mag_decl is turned on and you acquire valid GPS fix. | -| heading_hold_rate_limit | 90 | This setting limits yaw rotation rate that HEADING_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when HEADING_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes. | +| Variable Name | Default Value | Description | +| ------------- | ------------- | ----------- | +| 3d_deadband_high | 1514 | High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead) | +| 3d_deadband_low | 1406 | Low value of throttle deadband for 3D mode (when stick is in the 3d_deadband_throttle range, the fixed values of 3d_deadband_low / _high are used instead) | +| 3d_deadband_throttle | 50 | Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter. | +| 3d_neutral | 1460 | Neutral (stop) throttle value for 3D mode | +| acc_event_threshold_high | 0 | Acceleration threshold [cm/s/s] for impact / high g event text messages sent by SIM module. Acceleration values greater than 4 g can occur in fixed wing flight without an impact, so a setting of 4000 or greater is suggested. 0 = detection off. | +| acc_event_threshold_low | 0 | Acceleration threshold [cm/s/s] for low-g / freefall detection text messages sent by SIM module. A setting of less than 100 is suggested. Valid values: [0-900], 0 = detection off. | +| acc_event_threshold_neg_x | 0 | Acceleration threshold [cm/s/s] for backwards acceleration / fixed wing landing detection text messages sent by SIM module. Suggested value for fixed wing: 1100. 0 = detection off. | +| acc_hardware | AUTO | Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info | +| acc_lpf_hz | 15 | Software-based filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. | +| acc_lpf_type | BIQUAD | Specifies the type of the software LPF of the acc signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. | +| accgain_x | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | +| accgain_y | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | +| accgain_z | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | +| acczero_x | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | +| acczero_y | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | +| acczero_z | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | +| airspeed_adc_channel | 0 | ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0 | +| align_acc | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. | +| align_board_pitch | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | +| align_board_roll | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | +| align_board_yaw | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | +| align_gyro | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. | +| align_mag | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. | +| align_mag_pitch | 0 | Same as align_mag_roll, but for the pitch axis. | +| align_mag_roll | 0 | Set the external mag alignment on the roll axis (in 0.1 degree steps). If this value is non-zero, the compass is assumed to be externally mounted and both the board and on-board compass alignent (align_mag) are ignored. See also align_mag_pitch and align_mag_yaw. | +| align_mag_yaw | 0 | Same as align_mag_roll, but for the yaw axis. | +| align_opflow | 5 | Optical flow module alignment (default CW0_DEG_FLIP) | +| alt_hold_deadband | 50 | Defines the deadband of throttle during alt_hold [r/c points] | +| antigravity_accelerator | 1 | | +| antigravity_cutoff_lpf_hz | 15 | Antigravity cutoff frequenct for Throtte filter. Antigravity is based on the difference between actual and filtered throttle input. The bigger is the difference, the bigger Antigravity gain | +| antigravity_gain | 1 | Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements | +| baro_cal_tolerance | 150 | Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]. | +| baro_hardware | AUTO | Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info | +| baro_median_filter | ON | 3-point median filtering for barometer readouts. No reason to change this setting | +| bat_cells | 0 | Number of cells of the battery (0 = autodetect), see battery documentation | +| bat_voltage_src | RAW | Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP` | +| battery_capacity | 0 | Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity. | +| battery_capacity_critical | 0 | If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps. | +| battery_capacity_unit | MAH | Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour). | +| battery_capacity_warning | 0 | If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink. | +| blackbox_device | SPIFLASH | Selection of where to write blackbox data | +| blackbox_rate_denom | 1 | Blackbox logging rate denominator. See blackbox_rate_num. | +| blackbox_rate_num | 1 | Blackbox logging rate numerator. Use num/denom settings to decide if a frame should be logged, allowing control of the portion of logged loop iterations | +| cpu_underclock | OFF | This option is only available on certain architectures (F3 CPUs at the moment). It makes CPU clock lower to reduce interference to long-range RC systems working at 433MHz | +| cruise_power | 0 | Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit | +| current_adc_channel | - | ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled | +| current_meter_offset | 0 | This sets the output offset voltage of the current sensor in millivolts. | +| current_meter_scale | 400 | This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt. | +| current_meter_type | ADC | ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position. | +| deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. | +| disarm_kill_switch | ON | Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel. | +| display_force_sw_blink | OFF | OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON | +| dterm_lpf2_hz | 0 | Cutoff frequency for stage 2 D-term low pass filter | +| dterm_lpf2_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | +| dterm_lpf_hz | 40 | Dterm low pass filter cutoff frequency. Default setting is very conservative and small multirotors should use higher value between 80 and 100Hz. 80 seems like a gold spot for 7-inch builds while 100 should work best with 5-inch machines. If motors are getting too hot, lower the value | +| dterm_lpf_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | +| dynamic_gyro_notch_enabled | `OFF` | Enable/disable dynamic gyro notch also known as Matrix Filter | +| dynamic_gyro_notch_min_hz | 150 | Minimum frequency for dynamic notches. Default value of `150` works best with 5" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7" drones. 10" can go down to `60` - `70` | +| dynamic_gyro_notch_q | 120 | Q factor for dynamic notches | +| dynamic_gyro_notch_range | `MEDIUM` | Range for dynamic gyro notches. `MEDIUM` for 5", `HIGH` for 3" and `MEDIUM`/`LOW` for 7" and bigger propellers | +| failsafe_delay | 5 | Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). | +| failsafe_fw_pitch_angle | 100 | Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb | +| failsafe_fw_roll_angle | -200 | Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll | +| failsafe_fw_yaw_rate | -45 | Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn | +| failsafe_lights | ON | Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]. | +| failsafe_lights_flash_on_time | 100 | Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]. | +| failsafe_lights_flash_period | 1000 | Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]. | +| failsafe_min_distance | 0 | If failsafe happens when craft is closer than this distance in centimeters from home, failsafe will not execute regular failsafe_procedure, but will execute procedure specified in failsafe_min_distance_procedure instead. 0 = Normal failsafe_procedure always taken. | +| failsafe_min_distance_procedure | DROP | What failsafe procedure to initiate in Stage 2 when craft is closer to home than failsafe_min_distance. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | +| failsafe_mission | ON | If set to `OFF` the failsafe procedure won't be triggered and the mission will continue if the FC is in WP (automatic mission) mode | +| failsafe_off_delay | 200 | Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay). | +| failsafe_procedure | SET-THR | What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | +| failsafe_recovery_delay | 5 | Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay). | +| failsafe_stick_threshold | 50 | Threshold for stick motion to consider failsafe condition resolved. If non-zero failsafe won't clear even if RC link is restored - you have to move sticks to exit failsafe. | +| failsafe_throttle | 1000 | Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | +| failsafe_throttle_low_delay | 100 | If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout | +| fixed_wing_auto_arm | OFF | Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured. | +| flaperon_throw_offset | 200 | Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated. | +| frsky_coordinates_format | 0 | D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA | +| frsky_default_latitude | 0.000 | D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. | +| frsky_default_longitude | 0.000 | D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. | +| frsky_pitch_roll | OFF | S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data | +| frsky_unit | METRIC | Not used? [METRIC/IMPERIAL] | +| frsky_vfas_precision | 0 | D-Series telemetry only: Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method | +| fw_autotune_ff_to_i_tc | 600 | FF to I time (defines time for I to reach the same level of response as FF) [ms] | +| fw_autotune_ff_to_p_gain | 10 | FF to P gain (strength relationship) [%] | +| fw_autotune_overshoot_time | 100 | Time [ms] to detect sustained overshoot | +| fw_autotune_threshold | 50 | Threshold [%] of max rate to consider overshoot/undershoot detection | +| fw_autotune_undershoot_time | 200 | Time [ms] to detect sustained undershoot | +| fw_d_level | 75 | Fixed-wing attitude stabilisation HORIZON transition point | +| fw_ff_pitch | 50 | Fixed-wing rate stabilisation FF-gain for PITCH | +| fw_ff_roll | 50 | Fixed-wing rate stabilisation FF-gain for ROLL | +| fw_ff_yaw | 60 | Fixed-wing rate stabilisation FF-gain for YAW | +| fw_i_level | 5 | Fixed-wing attitude stabilisation low-pass filter cutoff | +| fw_i_pitch | 7 | Fixed-wing rate stabilisation I-gain for PITCH | +| fw_i_roll | 7 | Fixed-wing rate stabilisation I-gain for ROLL | +| fw_i_yaw | 10 | Fixed-wing rate stabilisation I-gain for YAW | +| fw_iterm_limit_stick_position | 0.5 | Iterm is not allowed to grow when stick position is above threshold. This solves the problem of bounceback or followthrough when full stick deflection is applied on poorely tuned fixed wings. In other words, stabilization is partialy disabled when pilot is actively controlling the aircraft and active when sticks are not touched. `0` mean stick is in center position, `1` means it is fully deflected to either side | +| fw_iterm_throw_limit | 165 | Limits max/min I-term value in stabilization PID controller in case of Fixed Wing. It solves the problem of servo saturation before take-off/throwing the airplane into the air. By default, error accumulated in I-term can not exceed 1/3 of servo throw (around 165us). Set 0 to disable completely. | +| fw_loiter_direction | RIGHT | Direction of loitering: center point on right wing (clockwise - default), or center point on left wing (counterclockwise). If equal YAW then can be changed in flight using a yaw stick. | +| fw_min_throttle_down_pitch | 0 | Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees) | +| fw_p_level | 20 | Fixed-wing attitude stabilisation P-gain | +| fw_p_pitch | 5 | Fixed-wing rate stabilisation P-gain for PITCH | +| fw_p_roll | 5 | Fixed-wing rate stabilisation P-gain for ROLL | +| fw_p_yaw | 6 | Fixed-wing rate stabilisation P-gain for YAW | +| fw_reference_airspeed | 1000 | Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present. | +| fw_tpa_time_constant | 0 | TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. Planes with low thrust/weight ratio generally need higher time constant. Default is zero for compatibility with old setups | +| fw_turn_assist_yaw_gain | 1 | Gain required to keep the yaw rate consistent with the turn rate for a coordinated turn (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter | +| gps_auto_baud | ON | Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS. When used with NAZA/DJI it will automatic detect GPS baudrate and change to it, ignoring the selected baudrate set in ports | +| gps_auto_config | ON | Enable automatic configuration of UBlox GPS receivers. | +| gps_dyn_model | AIR_1G | GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying. | +| gps_min_sats | 6 | Minimum number of GPS satellites in view to acquire GPS_FIX and consider GPS position valid. Some GPS receivers appeared to be very inaccurate with low satellite count. | +| gps_provider | UBLOX | Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N). | +| gps_sbas_mode | NONE | Which SBAS mode to be used | +| gps_ublox_use_galileo | OFF | Enable use of Galileo satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires M8N and Ublox firmware 3.x (or later) [OFF/ON]. | +| gyro_hardware_lpf | 42HZ | Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first. | +| gyro_lpf_hz | 60 | Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. | +| gyro_lpf_type | BIQUAD | Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. | +| gyro_stage2_lowpass_hz | 0 | Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz) | +| gyro_stage2_lowpass_type | `BIQUAD` | Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | +| gyro_sync | OFF | This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf | +| has_flaps | OFF | Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot | +| heading_hold_rate_limit | 90 | This setting limits yaw rotation rate that HEADING_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when HEADING_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes. | +| hott_alarm_sound_interval | 5 | Battery alarm delay in seconds for Hott telemetry | +| i2c_speed | 400KHZ | This setting controls the clock speed of I2C bus. 400KHZ is the default that most setups are able to use. Some noise-free setups may be overclocked to 800KHZ. Some sensor chips or setups with long wires may work unreliably at 400KHZ - user can try lowering the clock speed to 200KHZ or even 100KHZ. User need to bear in mind that lower clock speeds might require higher looptimes (lower looptime rate) | +| ibus_telemetry_type | 0 | Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details. | +| idle_power | 0 | Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit | +| imu_acc_ignore_rate | 0 | Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes | +| imu_acc_ignore_slope | 0 | Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight) | +| imu_dcm_ki | 50 | Inertial Measurement Unit KI Gain for accelerometer measurements | +| imu_dcm_ki_mag | 0 | Inertial Measurement Unit KI Gain for compass measurements | +| imu_dcm_kp | 2500 | Inertial Measurement Unit KP Gain for accelerometer measurements | +| imu_dcm_kp_mag | 10000 | Inertial Measurement Unit KP Gain for compass measurements | +| inav_auto_mag_decl | ON | Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored. | +| inav_baro_epv | 100.000 | Uncertainty value for barometric sensor [cm] | +| inav_gravity_cal_tolerance | 5 | Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value. | +| inav_max_eph_epv | 1000.000 | Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm] | +| inav_max_surface_altitude | 200 | Max allowed altitude for surface following mode. [cm] | +| inav_reset_altitude | FIRST_ARM | Defines when relative estimated altitude is reset to zero. Variants - `NEVER` (once reference is acquired it's used regardless); `FIRST_ARM` (keep altitude at zero until firstly armed), `EACH_ARM` (altitude is reset to zero on each arming) | +| inav_reset_home | FIRST_ARM | Allows to chose when the home position is reset. Can help prevent resetting home position after accidental mid-air disarm. Possible values are: NEVER, FIRST_ARM and EACH_ARM | +| inav_use_gps_velned | ON | Defined if iNav should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF iNav will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance. | +| inav_w_acc_bias | 0.010 | Weight for accelerometer drift estimation | +| inav_w_xy_gps_p | 1.000 | Weight of GPS coordinates in estimated UAV position and speed. | +| inav_w_xy_gps_v | 2.000 | Weight of GPS velocity data in estimated UAV speed | +| inav_w_xy_res_v | 0.500 | Decay coefficient for estimated velocity when GPS reference for position is lost | +| inav_w_z_baro_p | 0.350 | Weight of barometer measurements in estimated altitude and climb rate | +| inav_w_z_gps_p | 0.200 | Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes | +| inav_w_z_gps_v | 0.500 | Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero | +| inav_w_z_res_v | 0.500 | Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost | +| iterm_windup | 50 | Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter) | +| ledstrip_visual_beeper | OFF | | +| looptime | 1000 | This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible. | +| ltm_update_rate | NORMAL | Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details. | | mag_calibration_time | 30 | Adjust how long time the Calibration of mag will last. | | mc_p_pitch | 40 | Multicopter rate stabilisation P-gain for PITCH | | mc_i_pitch | 30 | Multicopter rate stabilisation I-gain for PITCH | @@ -494,34 +379,198 @@ A shorter form is also supported to enable and disable functions using `serial < | vtx_max_power_override | 0 | Some VTXes may report max power incorrectly (i.e. 200mW for a 600mW VTX). Use this to override max supported power. 0 to disable and use whatever VTX reports as it's capabilities | | motor_accel_time | 0 | Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000] | | motor_decel_time | 0 | Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000] | -| thr_comp_weight | 0.692 | Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage) | -| nav_mc_braking_speed_threshold | 100 | min speed in cm/s above which braking can happen | -| nav_mc_braking_disengage_speed | 75 | braking is disabled when speed goes below this value | -| nav_mc_braking_timeout | 2000 | timeout in ms for braking | +| motor_direction_inverted | OFF | Use if you need to inverse yaw motor direction. | +| motor_pwm_protocol | STANDARD | Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED | +| motor_pwm_rate | 400 | Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000. | +| name | Empty string | Craft name | +| nav_auto_climb_rate | 500 | Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s] | +| nav_auto_speed | 300 | Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only] | +| nav_disarm_on_landing | OFF | If set to ON, iNav disarms the FC after landing | +| nav_emerg_landing_speed | 500 | Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s] | +| nav_extra_arming_safety | ON | If set to ON drone won't arm if no GPS fix and any navigation mode like RTH or POSHOLD is configured. ALLOW_BYPASS allows the user to momentarily disable this check by holding yaw high (left stick held at the bottom right in mode 2) when switch arming is used | +| nav_fw_allow_manual_thr_increase | OFF | Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing | +| nav_fw_bank_angle | 20 | Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll | +| nav_fw_climb_angle | 20 | Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit | +| nav_fw_control_smoothness | 0 | How smoothly the autopilot controls the airplane to correct the navigation error | +| nav_fw_cruise_speed | 0 | Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s | +| nav_fw_cruise_thr | 1400 | Cruise throttle in GPS assisted modes, this includes RTH. Should be set high enough to avoid stalling. This values gives INAV a base for throttle when flying straight, and it will increase or decrease throttle based on pitch of airplane and the parameters below. In addition it will increase throttle if GPS speed gets below 7m/s ( hardcoded ) | +| nav_fw_cruise_yaw_rate | 20 | Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps] | +| nav_fw_dive_angle | 15 | Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit | +| nav_fw_heading_p | 60 | P gain of Heading Hold controller (Fixedwing) | +| nav_fw_land_dive_angle | 2 | Dive angle that airplane will use during final landing phase. During dive phase, motor is stopped or IDLE and roll control is locked to 0 degrees | +| nav_fw_launch_accel | 1863 | Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s | +| nav_fw_launch_climb_angle | 18 | Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit | +| nav_fw_launch_detect_time | 40 | Time for which thresholds have to breached to consider launch happened [ms] | +| nav_fw_launch_idle_thr | 1000 | Launch idle throttle - throttle to be set before launch sequence is initiated. If set below minimum throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above minimum throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position) | +| nav_fw_launch_max_altitude | 0 | Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]. | +| nav_fw_launch_max_angle | 45 | Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg] | +| nav_fw_launch_min_time | 0 | Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]. | +| nav_fw_launch_motor_delay | 500 | Delay between detected launch and launch sequence start and throttling up (ms) | +| nav_fw_launch_spinup_time | 100 | Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller | +| nav_fw_launch_thr | 1700 | Launch throttle - throttle to be set during launch sequence (pwm units) | +| nav_fw_launch_timeout | 5000 | Maximum time for launch sequence to be executed. After this time LAUNCH mode will be turned off and regular flight mode will take over (ms) | +| nav_fw_launch_velocity | 300 | Forward velocity threshold for swing-launch detection [cm/s] | +| nav_fw_loiter_radius | 5000 | PosHold radius. 3000 to 7500 is a good value (30-75m) [cm] | +| nav_fw_max_thr | 1700 | Maximum throttle for flying wing in GPS assisted modes | +| nav_fw_min_thr | 1200 | Minimum throttle for flying wing in GPS assisted modes | +| nav_fw_pitch2thr | 10 | Amount of throttle applied related to pitch attitude in GPS assisted modes. Throttle = nav_fw_cruise_throttle - (nav_fw_pitch2thr * pitch_angle). (notice that pitch_angle is in degrees and is negative when climbing and positive when diving, and throttle value is constrained between nav_fw_min_thr and nav_fw_max_thr) | +| nav_fw_pos_hdg_d | 0 | D gain of heading trajectory PID controller. (Fixedwing, rovers, boats) | +| nav_fw_pos_hdg_i | 0 | I gain of heading trajectory PID controller. (Fixedwing, rovers, boats) | +| nav_fw_pos_hdg_p | 60 | P gain of heading PID controller. (Fixedwing, rovers, boats) | +| nav_fw_pos_hdg_pidsum_limit | 350 | Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats) | +| nav_fw_pos_xy_d | 8 | D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero | +| nav_fw_pos_xy_i | 5 | I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero | +| nav_fw_pos_xy_p | 75 | P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH | +| nav_fw_pos_z_d | 0 | D gain of altitude PID controller (Fixedwing) | +| nav_fw_pos_z_i | 0 | I gain of altitude PID controller (Fixedwing) | +| nav_fw_pos_z_p | 50 | P gain of altitude PID controller (Fixedwing) | +| nav_fw_yaw_deadband | 0 | Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course | +| nav_land_slowdown_maxalt | 2000 | Defines at what altitude the descent velocity should start to ramp down from 100% nav_landing_speed to 25% nav_landing_speed. [cm] | +| nav_land_slowdown_minalt | 500 | Defines at what altitude the descent velocity should start to be 25% of nav_landing_speed [cm] | +| nav_landing_speed | 200 | Vertical descent velocity during the RTH landing phase. [cm/s] | +| nav_manual_climb_rate | 200 | Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] | +| nav_manual_speed | 500 | Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only] | +| nav_mc_auto_disarm_delay | 2000 | | +| nav_mc_bank_angle | 30 | Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude | +| nav_mc_braking_bank_angle | 40 | max angle that MR is allowed to bank in BOOST mode | +| nav_mc_braking_boost_disengage_speed | 100 | BOOST will be disabled when speed goes below this value | | nav_mc_braking_boost_factor | 100 | acceleration factor for BOOST phase | -| nav_mc_braking_boost_timeout | 750 | how long in ms BOOST phase can happen | | nav_mc_braking_boost_speed_threshold | 150 | BOOST can be enabled when speed is above this value | -| nav_mc_braking_boost_disengage_speed | 100 | BOOST will be disabled when speed goes below this value | -| nav_mc_braking_bank_angle | 40 | max angle that MR is allowed to bank in BOOST mode | +| nav_mc_braking_boost_timeout | 750 | how long in ms BOOST phase can happen | +| nav_mc_braking_disengage_speed | 75 | braking is disabled when speed goes below this value | +| nav_mc_braking_speed_threshold | 100 | min speed in cm/s above which braking can happen | +| nav_mc_braking_timeout | 2000 | timeout in ms for braking | +| nav_mc_heading_p | 60 | P gain of Heading Hold controller (Multirotor) | +| nav_mc_hover_thr | 1500 | Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering. | | nav_mc_pos_deceleration_time | 120 | Used for stoping distance calculation. Stop position is computed as _speed_ * _nav_mc_pos_deceleration_time_ from the place where sticks are released. Braking mode overrides this setting | | nav_mc_pos_expo | 10 | Expo for PosHold control | +| nav_mc_pos_xy_p | 65 | Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity | +| nav_mc_pos_z_p | 50 | P gain of altitude PID controller (Multirotor) | +| nav_mc_vel_xy_d | 100 | D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target. | +| nav_mc_vel_xy_i | 15 | I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot | +| nav_mc_vel_xy_p | 40 | P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause "nervous" behavior and oscillations | +| nav_mc_vel_z_d | 10 | D gain of velocity PID controller | +| nav_mc_vel_z_i | 50 | I gain of velocity PID controller | +| nav_mc_vel_z_p | 100 | P gain of velocity PID controller | +| nav_min_rth_distance | 500 | Minimum distance from homepoint when RTH full procedure will be activated [cm]. Below this distance, the mode will activate at the current location and the final phase is executed (loiter / land). Above this distance, the full procedure is activated, which may include initial climb and flying directly to the homepoint before entering the loiter / land phase. | +| nav_overrides_motor_stop | ON | Setting to OFF combined with MOTOR_STOP feature will allow user to stop motor when in autonomous modes. On most places this setting is likely to cause a stall. | +| nav_position_timeout | 5 | If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable) | +| nav_rth_abort_threshold | 50000 | RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. [cm] | +| nav_rth_allow_landing | ALWAYS | If set to ON drone will land as a last phase of RTH. | +| nav_rth_alt_mode | AT_LEAST | Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details | +| nav_rth_altitude | 1000 | Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters) | +| nav_rth_climb_first | ON | If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way. | +| nav_rth_climb_ignore_emerg | OFF | If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status. | +| nav_rth_home_altitude | 0 | Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm] | +| nav_rth_home_offset_direction | 0 | Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) | +| nav_rth_home_offset_distance | 0 | Distance offset from GPS established home to "safe" position used for RTH (cm, 0 disables) | +| nav_rth_tail_first | OFF | If set to ON drone will return tail-first. Obviously meaningless for airplanes. | +| nav_use_fw_yaw_control | OFF | Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats | +| nav_use_midthr_for_althold | OFF | If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude | +| nav_user_control_mode | ATTI | Defines how Pitch/Roll input from RC receiver affects flight in POSHOLD mode: ATTI - pitch/roll controls attitude like in ANGLE mode; CRUISE - pitch/roll controls velocity in forward and right direction. | +| nav_wp_radius | 100 | Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius | +| nav_wp_safe_distance | 10000 | First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check. | +| osd_ahi_style | DEFAULT | Sets OSD Artificial Horizon style "DEFAULT" or "LINE" for the FrSky Graphical OSD. | +| osd_alt_alarm | 100 | Value above which to make the OSD relative altitude indicator blink (meters) | | osd_artificial_horizon_max_pitch | 20 | Max pitch, in degrees, for OSD artificial horizon | -| baro_cal_tolerance | 150 | Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]. | -| mc_airmode_type | STICK_CENTER | Defines the Airmode state handling type for Multirotors. Default **STICK_CENTER** is the classical approach in which Airmode is always active if enabled, but when the throttle is low and ROLL/PITCH/YAW sticks are centered, Iterms is not allowed to grow (ANTI_WINDUP). **THROTTLE_THRESHOLD** is the Airmode behavior known from Betaflight. In this mode, Airmode is active as soon THROTTLE position is above `mc_airmode_threshold` and stays active until disarm. ANTI_WINDUP is never triggered. For small Multirotors (up to 7-inch propellers) it is suggested to switch to **THROTTLE_THRESHOLD** since it keeps full stabilization no matter what pilot does with the sticks. Fixed Wings always use **STICK_CENTER** mode. | -| mc_airmode_threshold | 1300 | Defines airmode THROTTLE activation threshold when `mc_airmode_type` **THROTTLE_THRESHOLD** is used | +| osd_baro_temp_alarm_max | 600 | Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade) | +| osd_baro_temp_alarm_min | -200 | Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade) | +| osd_current_alarm | 0 | Value above which the OSD current consumption element will start blinking. Measured in full Amperes. | +| osd_dist_alarm | 1000 | Value above which to make the OSD distance from home indicator blink (meters) | +| osd_esc_temp_alarm_max | 900 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | +| osd_esc_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | +| osd_estimations_wind_compensation | ON | Use wind estimation for remaining flight time/distance estimation | +| osd_failsafe_switch_layout | OFF | If enabled the OSD automatically switches to the first layout during failsafe | +| osd_gforce_alarm | 5 | Value above which the OSD g force indicator will blink (g) | +| osd_gforce_axis_alarm_max | 5 | Value above which the OSD axis g force indicators will blink (g) | +| osd_gforce_axis_alarm_min | -5 | Value under which the OSD axis g force indicators will blink (g) | +| osd_hud_wp_disp | OFF | Controls display of the next waypoints in the HUD. | +| osd_imu_temp_alarm_max | 600 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | +| osd_imu_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | +| osd_main_voltage_decimals | 1 | Number of decimals for the battery voltages displayed in the OSD [1-2]. | +| osd_neg_alt_alarm | 5 | Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters) | +| osd_row_shiftdown | 0 | Number of rows to shift the OSD display (increase if top rows are cut off) | +| osd_rssi_alarm | 20 | Value bellow which to make the OSD RSSI indicator blink | +| osd_stats_energy_unit | MAH | Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour) | +| osd_temp_label_align | LEFT | Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT` | +| osd_time_alarm | 10 | Value above which to make the OSD flight time indicator blink (minutes) | +| osd_units | METRIC | IMPERIAL, METRIC, UK | +| osd_video_system | AUTO | Video system used. Possible values are `AUTO`, `PAL` and `NTSC` | +| pid_type | | Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID` | +| pidsum_limit | 500 | A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | +| pidsum_limit_yaw | 400 | A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | +| pitch_rate | 20 | Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. | +| platform_type | "MULTIROTOR" | Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented | +| pos_hold_deadband | 20 | Stick deadband in [r/c points], applied after r/c deadband and expo | +| rangefinder_median_filter | OFF | 3-point median filtering for rangefinder readouts | +| rate_accel_limit_roll_pitch | 0 | Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting. | +| rate_accel_limit_yaw | 10000 | Limits acceleration of YAW rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 180 dps^2). When set correctly, it greatly improves stopping performance and general stability during yaw turns. Value of 0 disables limiting. | +| rc_expo | 70 | Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`) | +| rc_filter_frequency | 50 | RC data biquad filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay. Practical values are 20-50. Set to zero to disable entirely and use unsmoothed RC stick values | +| rc_yaw_expo | 20 | Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`) | +| reboot_character | 82 | Special character used to trigger reboot | +| report_cell_voltage | OFF | S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON | +| roll_rate | 20 | Defines rotation rate on ROLL axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. | +| rpm_gyro_filter_enabled | `OFF` | Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV | +| rpm_gyro_harmonics | 1 | Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine | +| rpm_gyro_min_hz | 150 | The lowest frequency for gyro RPM filtere. Default `150` is fine for 5" mini-quads. On 7-inch drones you can lower even down to `60`-`70` | +| rpm_gyro_q | 500 | Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting | +| rssi_adc_channel | - | ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled | +| rssi_channel | 0 | RX channel containing the RSSI signal | +| rssi_max | 100 | The maximum RSSI value sent by the receiver, in %. For example, if your receiver's maximum RSSI value shows as 83% in the configurator/OSD set this parameter to 83. See also rssi_min. | +| rssi_min | 0 | The minimum RSSI value sent by the receiver, in %. For example, if your receiver's minimum RSSI value shows as 42% in the configurator/OSD set this parameter to 42. See also rssi_max. Note that rssi_min can be set to a value bigger than rssi_max to invert the RSSI calculation (i.e. bigger values mean lower RSSI). | +| rssi_source | `AUTO` | Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP` | +| rth_energy_margin | 5 | Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation | +| rx_max_usec | 2115 | Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of mid_rc. | +| rx_min_usec | 885 | Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc. | +| sdcard_detect_inverted | `TARGET dependent` | This setting drives the way SD card is detected in card slot. On some targets (AnyFC F7 clone) different card slot was used and depending of hardware revision ON or OFF setting might be required. If card is not detected, change this value. | +| serialrx_halfduplex | OFF | Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire | +| serialrx_inverted | OFF | Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY). | +| serialrx_provider | SPEK1024 | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. | +| servo_center_pulse | 1500 | Servo midpoint | +| servo_lpf_hz | 20 | Selects the servo PWM output cutoff frequency. Value is in [Hz] | +| servo_protocol | PWM | An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SERVO_DRIVER` (I2C PCA9685 peripheral), `SBUS` (S.Bus protocol output via a configured serial port) | +| servo_pwm_rate | 50 | Output frequency (in Hz) servo pins. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz. | | sim_ground_station_number | Empty string | Number of phone that is used to communicate with SIM module. Messages / calls from other numbers are ignored. If undefined, can be set by calling or sending a message to the module. | +| sim_low_altitude | 0 | Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`. | | sim_pin | Empty string | PIN code for the SIM module | -| sim_transmit_interval | 60 | Text message transmission interval in seconds for SIM module. Minimum value: 10 | | sim_transmit_flags | F | String specifying text message transmit condition flags for the SIM module. Flags can be given in any order. Empty string means the module only sends response messages. `A`: acceleration events, `T`: continuous transmission, `F`: continuous transmission in failsafe mode, `L`: continuous transmission when altitude is below `sim_low_altitude`, `G`: continuous transmission when GPS signal quality is low | -| acc_event_threshold_high | 0 | Acceleration threshold [cm/s/s] for impact / high g event text messages sent by SIM module. Acceleration values greater than 4 g can occur in fixed wing flight without an impact, so a setting of 4000 or greater is suggested. 0 = detection off. | -| acc_event_threshold_low | 0 | Acceleration threshold [cm/s/s] for low-g / freefall detection text messages sent by SIM module. A setting of less than 100 is suggested. Valid values: [0-900], 0 = detection off. | -| acc_event_threshold_neg_x | 0 | Acceleration threshold [cm/s/s] for backwards acceleration / fixed wing landing detection text messages sent by SIM module. Suggested value for fixed wing: 1100. 0 = detection off. | -| sim_low_altitude | 0 | Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`.| -| rssi_source | `AUTO` | Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP` | -| throttle_scale | 1.000 | Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50% | -| vbat_meter_type | `ADC` | Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running | -| antigravity_gain | 1 | Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements | -| antigravity_accelerator | 1 | | -| antigravity_cutoff_lpf_hz | 15 | Antigravity cutoff frequenct for Throtte filter. Antigravity is based on the difference between actual and filtered throttle input. The bigger is the difference, the bigger Antigravity gain | -| sim_pin | | PIN for GSM card module | -| mc_cd_lpf_hz | 30 | Cutoff frequency for Control Derivative. Lower value smoother reaction on fast stick movements. With higher values, response will be more aggressive, jerky | \ No newline at end of file +| sim_transmit_interval | 60 | Text message transmission interval in seconds for SIM module. Minimum value: 10 | +| small_angle | 25 | If the aircraft tilt angle exceed this value the copter will refuse to arm. | +| smartport_fuel_unit | MAH | S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH] | +| spektrum_sat_bind | 0 | 0 = disabled. Used to bind the spektrum satellite to RX | +| stats | OFF | General switch of the statistics recording feature (a.k.a. odometer) | +| stats_total_dist | 0 | Total flight distance [in meters]. The value is updated on every disarm when "stats" are enabled. | +| stats_total_time | 0 | Total flight time [in seconds]. The value is updated on every disarm when "stats" are enabled. | +| switch_disarm_delay | 250 | Delay before disarming when requested by switch (ms) [0-1000] | +| telemetry_halfduplex | OFF | S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details | +| telemetry_inverted | OFF | Determines if the telemetry protocol default signal inversion is reversed. This should be OFF in most cases unless a custom or hacked RX is used. | +| telemetry_switch | OFF | Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed. | +| thr_comp_weight | 0.692 | Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage) | +| thr_expo | 0 | Throttle exposition value | +| thr_mid | 50 | Throttle value when the stick is set to mid-position. Used in the throttle curve calculation. | +| throttle_idle | 15 | The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle. | +| throttle_scale | 1.000 | Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50% | +| throttle_tilt_comp_str | 0 | Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled. | +| tpa_breakpoint | 1500 | See tpa_rate. | +| tpa_rate | 0 | Throttle PID attenuation reduces influence of P on ROLL and PITCH as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate. | +| tri_unarmed_servo | ON | On tricopter mix only, if this is set to ON, servo will always be correcting regardless of armed state. to disable this, set it to OFF. | +| tz_automatic_dst | OFF | Automatically add Daylight Saving Time to the GPS time when needed or simply ignore it. Includes presets for EU and the USA - if you live outside these areas it is suggested to manage DST manually via `tz_offset`. | +| tz_offset | 0 | Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs | +| vbat_adc_channel | - | ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled | +| vbat_cell_detect_voltage | 430 | Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units, default is 4.30V | +| vbat_max_cell_voltage | 420 | Maximum voltage per cell in 0.01V units, default is 4.20V | +| vbat_meter_type | `ADC` | Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running | +| vbat_min_cell_voltage | 330 | Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V) | +| vbat_scale | 1100 | Battery voltage calibration value. 1100 = 11:1 voltage divider (10k:1k) x 100. Adjust this slightly if reported pack voltage is different from multimeter reading. You can get current voltage by typing "status" in cli. | +| vbat_warning_cell_voltage | 350 | Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V) | +| vtx_band | 4 | Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race. | +| vtx_channel | 1 | Channel to use within the configured `vtx_band`. Valid values are [1, 8]. | +| vtx_halfduplex | ON | Use half duplex UART to communicate with the VTX, using only a TX pin in the FC. | +| vtx_low_power_disarm | OFF | When the craft is disarmed, set the VTX to its lowest power. `ON` will set the power to its minimum value on startup, increase it to `vtx_power` when arming and change it back to its lowest setting after disarming. `UNTIL_FIRST_ARM` will start with minimum power, but once the craft is armed it will increase to `vtx_power` and it will never decrease until the craft is power cycled. | +| vtx_power | 1 | VTX RF power level to use. The exact number of mw depends on the VTX hardware. | +| yaw_deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. | +| yaw_lpf_hz | 30 | Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below) | +| yaw_rate | 20 | Defines rotation rate on YAW axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. | + + > Note: this table is autogenerated. Do not edit it manually. diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 5a760bde8fc..be3096bc727 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -151,24 +151,38 @@ groups: headers: ["sensors/gyro.h"] members: - name: looptime + docs_description: "This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible." + docs_default_value: "1000" max: 9000 - name: gyro_sync + docs_description: "This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf" + docs_default_value: "OFF" field: gyroSync type: bool - name: align_gyro + docs_description: "When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP." + docs_default_value: "DEFAULT" field: gyro_align type: uint8_t table: alignment - name: gyro_hardware_lpf + docs_description: "Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first." + docs_default_value: "42HZ" field: gyro_lpf table: gyro_lpf - name: gyro_lpf_hz + docs_description: "Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value." + docs_default_value: "60" field: gyro_soft_lpf_hz max: 200 - name: gyro_lpf_type + docs_description: "Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds." + docs_default_value: "BIQUAD" field: gyro_soft_lpf_type table: filter_type - name: moron_threshold + docs_description: "When powering up, gyro bias is calculated. If the model is shaking/moving during this initial calibration, offsets are calculated incorrectly, and could lead to poor flying performance. This threshold means how much average gyro reading could differ before re-calibration is triggered." + docs_default_value: "32" field: gyroMovementCalibrationThreshold max: 128 - name: gyro_notch_hz @@ -179,26 +193,38 @@ groups: min: 1 max: 500 - name: gyro_stage2_lowpass_hz + docs_description: "Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz)" + docs_default_value: "0" field: gyro_stage2_lowpass_hz min: 0 max: 500 - name: gyro_stage2_lowpass_type + docs_description: "Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation." + docs_default_value: "`BIQUAD`" field: gyro_stage2_lowpass_type table: filter_type - name: dynamic_gyro_notch_enabled + docs_description: "Enable/disable dynamic gyro notch also known as Matrix Filter" + docs_default_value: "`OFF`" field: dynamicGyroNotchEnabled condition: USE_DYNAMIC_FILTERS type: bool - name: dynamic_gyro_notch_range + docs_description: "Range for dynamic gyro notches. `MEDIUM` for 5\", `HIGH` for 3\" and `MEDIUM`/`LOW` for 7\" and bigger propellers" + docs_default_value: "`MEDIUM`" field: dynamicGyroNotchRange condition: USE_DYNAMIC_FILTERS table: dynamicFilterRangeTable - name: dynamic_gyro_notch_q + docs_description: "Q factor for dynamic notches" + docs_default_value: "120" field: dynamicGyroNotchQ condition: USE_DYNAMIC_FILTERS min: 1 max: 1000 - name: dynamic_gyro_notch_min_hz + docs_description: "Minimum frequency for dynamic notches. Default value of `150` works best with 5\" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7\" drones. 10\" can go down to `60` - `70`" + docs_default_value: "150" field: dynamicGyroNotchMinHz condition: USE_DYNAMIC_FILTERS min: 30 @@ -233,18 +259,26 @@ groups: condition: USE_ADC members: - name: vbat_adc_channel + docs_description: "ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled" + docs_default_value: "-" field: adcFunctionChannel[ADC_BATTERY] min: ADC_CHN_NONE max: ADC_CHN_MAX - name: rssi_adc_channel + docs_description: "ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled" + docs_default_value: "-" field: adcFunctionChannel[ADC_RSSI] min: ADC_CHN_NONE max: ADC_CHN_MAX - name: current_adc_channel + docs_description: "ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled" + docs_default_value: "-" field: adcFunctionChannel[ADC_CURRENT] min: ADC_CHN_NONE max: ADC_CHN_MAX - name: airspeed_adc_channel + docs_description: "ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0" + docs_default_value: "0" field: adcFunctionChannel[ADC_AIRSPEED] min: ADC_CHN_NONE max: ADC_CHN_MAX @@ -260,38 +294,58 @@ groups: min: 1 max: 255 - name: align_acc + docs_description: "When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP." + docs_default_value: "DEFAULT" field: acc_align type: uint8_t table: alignment - name: acc_hardware + docs_description: "Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info" + docs_default_value: "AUTO" table: acc_hardware - name: acc_lpf_hz + docs_description: "Software-based filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value." + docs_default_value: "15" min: 0 max: 200 - name: acc_lpf_type + docs_description: "Specifies the type of the software LPF of the acc signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds." + docs_default_value: "BIQUAD" field: acc_soft_lpf_type table: filter_type - name: acczero_x + docs_description: "Calculated value after '6 position avanced calibration'. See Wiki page." + docs_default_value: "0" field: accZero.raw[X] min: INT16_MIN max: INT16_MAX - name: acczero_y + docs_description: "Calculated value after '6 position avanced calibration'. See Wiki page." + docs_default_value: "0" field: accZero.raw[Y] min: INT16_MIN max: INT16_MAX - name: acczero_z + docs_description: "Calculated value after '6 position avanced calibration'. See Wiki page." + docs_default_value: "0" field: accZero.raw[Z] min: INT16_MIN max: INT16_MAX - name: accgain_x + docs_description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page." + docs_default_value: "4096" field: accGain.raw[X] min: 1 max: 8192 - name: accgain_y + docs_description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page." + docs_default_value: "4096" field: accGain.raw[Y] min: 1 max: 8192 - name: accgain_z + docs_description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page." + docs_default_value: "4096" field: accGain.raw[Z] min: 1 max: 8192 @@ -304,6 +358,8 @@ groups: - name: rangefinder_hardware table: rangefinder_hardware - name: rangefinder_median_filter + docs_description: "3-point median filtering for rangefinder readouts" + docs_default_value: "OFF" field: use_median_filtering type: bool @@ -318,6 +374,8 @@ groups: min: 0 max: 10000 - name: align_opflow + docs_description: "Optical flow module alignment (default CW0_DEG_FLIP)" + docs_default_value: "5" field: opflow_align type: uint8_t table: alignment @@ -328,43 +386,64 @@ groups: condition: USE_MAG members: - name: align_mag + docs_description: "When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP." + docs_default_value: "DEFAULT" field: mag_align type: uint8_t table: alignment - name: mag_hardware + docs_description: "Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info" + docs_default_value: "AUTO" table: mag_hardware - name: mag_declination + docs_description: "Current location magnetic declination in format. For example, -6deg 37min = -637 for Japan. Leading zero in ddd not required. Get your local magnetic declination here: http://magnetic-declination.com/ . Not in use if inav_auto_mag_decl is turned on and you acquire valid GPS fix." + docs_default_value: "0" min: -18000 max: 18000 - name: magzero_x + docs_description: "Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed." + docs_default_value: "0" field: magZero.raw[X] min: INT16_MIN max: INT16_MAX - name: magzero_y + docs_description: "Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed." + docs_default_value: "0" field: magZero.raw[Y] min: INT16_MIN max: INT16_MAX - name: magzero_z + docs_description: "Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed." + docs_default_value: "0" field: magZero.raw[Z] min: INT16_MIN max: INT16_MAX - name: mag_calibration_time + docs_description: "Adjust how long time the Calibration of mag will last." + docs_default_value: "30" field: magCalibrationTimeLimit min: 30 max: 120 - name: mag_to_use + docs_description: "Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target" condition: USE_DUAL_MAG min: 0 max: 1 - name: align_mag_roll + docs_description: "Set the external mag alignment on the roll axis (in 0.1 degree steps). If this value is non-zero, the compass is assumed to be externally mounted and both the board and on-board compass alignent (align_mag) are ignored. See also align_mag_pitch and align_mag_yaw." + docs_default_value: "0" field: rollDeciDegrees min: -1800 max: 3600 - name: align_mag_pitch + docs_description: "Same as align_mag_roll, but for the pitch axis." + docs_default_value: "0" field: pitchDeciDegrees min: -1800 max: 3600 - name: align_mag_yaw + docs_description: "Same as align_mag_roll, but for the yaw axis." + docs_default_value: "0" field: yawDeciDegrees min: -1800 max: 3600 @@ -375,11 +454,17 @@ groups: condition: USE_BARO members: - name: baro_hardware + docs_description: "Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info" + docs_default_value: "AUTO" table: baro_hardware - name: baro_median_filter + docs_description: "3-point median filtering for barometer readouts. No reason to change this setting" + docs_default_value: "ON" field: use_median_filtering type: bool - name: baro_cal_tolerance + docs_description: "Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]." + docs_default_value: "150" field: baro_calibration_tolerance min: 0 max: 1000 @@ -406,24 +491,36 @@ groups: field: receiverType table: receiver_type - name: min_check + docs_description: "These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value." + docs_default_value: "1100" field: mincheck min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: max_check + docs_description: "These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value." + docs_default_value: "1900" field: maxcheck min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: rssi_source + docs_description: "Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP`" + docs_default_value: "`AUTO`" field: rssi_source table: rssi_source - name: rssi_channel + docs_description: "RX channel containing the RSSI signal" + docs_default_value: "0" min: 0 max: MAX_SUPPORTED_RC_CHANNEL_COUNT - name: rssi_min + docs_description: "The minimum RSSI value sent by the receiver, in %. For example, if your receiver's minimum RSSI value shows as 42% in the configurator/OSD set this parameter to 42. See also rssi_max. Note that rssi_min can be set to a value bigger than rssi_max to invert the RSSI calculation (i.e. bigger values mean lower RSSI)." + docs_default_value: "0" field: rssiMin min: RSSI_VISIBLE_VALUE_MIN max: RSSI_VISIBLE_VALUE_MAX - name: rssi_max + docs_description: "The maximum RSSI value sent by the receiver, in %. For example, if your receiver's maximum RSSI value shows as 83% in the configurator/OSD set this parameter to 83. See also rssi_min." + docs_default_value: "100" field: rssiMax min: RSSI_VISIBLE_VALUE_MIN max: RSSI_VISIBLE_VALUE_MAX @@ -432,13 +529,19 @@ groups: min: 500 max: 10000 - name: rc_filter_frequency + docs_description: "RC data biquad filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay. Practical values are 20-50. Set to zero to disable entirely and use unsmoothed RC stick values" + docs_default_value: "50" field: rcFilterFrequency min: 0 max: 100 - name: serialrx_provider + docs_description: "When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section." + docs_default_value: "SPEK1024" condition: USE_SERIAL_RX table: serial_rx - name: serialrx_inverted + docs_description: "Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY)." + docs_default_value: "OFF" condition: USE_SERIAL_RX type: bool - name: rx_spi_protocol @@ -452,16 +555,24 @@ groups: min: 0 max: 8 - name: spektrum_sat_bind + docs_description: "0 = disabled. Used to bind the spektrum satellite to RX" + docs_default_value: "0" condition: USE_SPEKTRUM_BIND min: SPEKTRUM_SAT_BIND_DISABLED max: SPEKTRUM_SAT_BIND_MAX - name: rx_min_usec + docs_description: "Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc." + docs_default_value: "885" min: PWM_PULSE_MIN max: PWM_PULSE_MAX - name: rx_max_usec + docs_description: "Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of mid_rc." + docs_default_value: "2115" min: PWM_PULSE_MIN max: PWM_PULSE_MAX - name: serialrx_halfduplex + docs_description: "Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire" + docs_default_value: "OFF" field: halfDuplex type: bool - name: msp_override_channels @@ -476,17 +587,25 @@ groups: condition: USE_BLACKBOX members: - name: blackbox_rate_num + docs_description: "Blackbox logging rate numerator. Use num/denom settings to decide if a frame should be logged, allowing control of the portion of logged loop iterations" + docs_default_value: "1" field: rate_num min: 1 max: 65535 - name: blackbox_rate_denom + docs_description: "Blackbox logging rate denominator. See blackbox_rate_num." + docs_default_value: "1" field: rate_denom min: 1 max: 65535 - name: blackbox_device + docs_description: "Selection of where to write blackbox data" + docs_default_value: "SPIFLASH" field: device table: blackbox_device - name: sdcard_detect_inverted + docs_description: "This setting drives the way SD card is detected in card slot. On some targets (AnyFC F7 clone) different card slot was used and depending of hardware revision ON or OFF setting might be required. If card is not detected, change this value." + docs_default_value: "`TARGET dependent`" field: invertedCardDetection condition: USE_SDCARD type: bool @@ -496,33 +615,49 @@ groups: headers: ["flight/mixer.h"] members: - name: max_throttle + docs_description: "This is the maximum value (in us) sent to esc when armed. Default of 1850 are OK for everyone (legacy). For modern ESCs, higher values (c. 2000) may be more appropriate. If you have brushed motors, the value should be set to 2000." + docs_default_value: "1850" field: maxthrottle min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: min_command + docs_description: "This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly when powered up, try decreasing this value. It can also be used for calibrating all ESCs at once." + docs_default_value: "1000" field: mincommand min: 0 max: PWM_RANGE_MAX - name: motor_pwm_rate + docs_description: "Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000." + docs_default_value: "400" field: motorPwmRate min: 50 max: 32000 - name: motor_accel_time + docs_description: "Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000]" + docs_default_value: "0" field: motorAccelTimeMs min: 0 max: 1000 - name: motor_decel_time + docs_description: "Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000]" + docs_default_value: "0" field: motorDecelTimeMs min: 0 max: 1000 - name: motor_pwm_protocol + docs_description: "Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED" + docs_default_value: "STANDARD" field: motorPwmProtocol table: motor_pwm_protocol - name: throttle_scale + docs_description: "Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50%" + docs_default_value: "1.000" field: throttleScale min: 0 max: 1 - name: throttle_idle + docs_description: "The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle." + docs_default_value: "15" field: throttleIdle min: 4 max: 30 @@ -536,41 +671,67 @@ groups: headers: ["flight/failsafe.h"] members: - name: failsafe_delay + docs_description: "Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay)." + docs_default_value: "5" min: 0 max: 200 - name: failsafe_recovery_delay + docs_description: "Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay)." + docs_default_value: "5" min: 0 max: 200 - name: failsafe_off_delay + docs_description: "Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay)." + docs_default_value: "200" min: 0 max: 200 - name: failsafe_throttle + docs_description: "Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle)." + docs_default_value: "1000" min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: failsafe_throttle_low_delay + docs_description: "If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout" + docs_default_value: "100" min: 0 max: 300 - name: failsafe_procedure + docs_description: "What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle)." + docs_default_value: "SET-THR" table: failsafe_procedure - name: failsafe_stick_threshold + docs_description: "Threshold for stick motion to consider failsafe condition resolved. If non-zero failsafe won't clear even if RC link is restored - you have to move sticks to exit failsafe." + docs_default_value: "50" field: failsafe_stick_motion_threshold min: 0 max: 500 - name: failsafe_fw_roll_angle + docs_description: "Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll" + docs_default_value: "-200" min: -800 max: 800 - name: failsafe_fw_pitch_angle + docs_description: "Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb" + docs_default_value: "100" min: -800 max: 800 - name: failsafe_fw_yaw_rate + docs_description: "Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn" + docs_default_value: "-45" min: -1000 max: 1000 - name: failsafe_min_distance + docs_description: "If failsafe happens when craft is closer than this distance in centimeters from home, failsafe will not execute regular failsafe_procedure, but will execute procedure specified in failsafe_min_distance_procedure instead. 0 = Normal failsafe_procedure always taken." + docs_default_value: "0" min: 0 max: 65000 - name: failsafe_min_distance_procedure + docs_description: "What failsafe procedure to initiate in Stage 2 when craft is closer to home than failsafe_min_distance. See [Failsafe documentation](Failsafe.md#failsafe_throttle)." + docs_default_value: "DROP" table: failsafe_procedure - name: failsafe_mission + docs_description: "If set to `OFF` the failsafe procedure won't be triggered and the mission will continue if the FC is in WP (automatic mission) mode" + docs_default_value: "ON" type: bool - name: PG_LIGHTS_CONFIG @@ -579,13 +740,19 @@ groups: condition: USE_LIGHTS members: - name: failsafe_lights + docs_description: "Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]." + docs_default_value: "ON" field: failsafe.enabled type: bool - name: failsafe_lights_flash_period + docs_description: "Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]." + docs_default_value: "1000" field: failsafe.flash_period min: 40 max: 65535 - name: failsafe_lights_flash_on_time + docs_description: "Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]." + docs_default_value: "100" field: failsafe.flash_on_time min: 20 max: 65535 @@ -595,14 +762,20 @@ groups: headers: ["sensors/boardalignment.h"] members: - name: align_board_roll + docs_description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc" + docs_default_value: "0" field: rollDeciDegrees min: -1800 max: 3600 - name: align_board_pitch + docs_description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc" + docs_default_value: "0" field: pitchDeciDegrees min: -1800 max: 3600 - name: align_board_yaw + docs_description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc" + docs_default_value: "0" field: yawDeciDegrees min: -1800 max: 3600 @@ -612,42 +785,62 @@ groups: headers: ["sensors/battery.h"] members: - name: vbat_meter_type + docs_description: "Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running" + docs_default_value: "`ADC`" field: voltage.type table: voltage_sensor type: uint8_t - name: vbat_scale + docs_description: "Battery voltage calibration value. 1100 = 11:1 voltage divider (10k:1k) x 100. Adjust this slightly if reported pack voltage is different from multimeter reading. You can get current voltage by typing \"status\" in cli." + docs_default_value: "1100" field: voltage.scale condition: USE_ADC min: VBAT_SCALE_MIN max: VBAT_SCALE_MAX - name: current_meter_scale + docs_description: "This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt." + docs_default_value: "400" field: current.scale min: -10000 max: 10000 - name: current_meter_offset + docs_description: "This sets the output offset voltage of the current sensor in millivolts." + docs_default_value: "0" field: current.offset min: -32768 max: 32767 - name: current_meter_type + docs_description: "ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position." + docs_default_value: "ADC" field: current.type table: current_sensor type: uint8_t - name: bat_voltage_src + docs_description: "Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP`" + docs_default_value: "RAW" field: voltageSource table: bat_voltage_source type: uint8_t - name: cruise_power + docs_description: "Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit" + docs_default_value: "0" field: cruise_power min: 0 max: 4294967295 - name: idle_power + docs_description: "Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit" + docs_default_value: "0" field: idle_power min: 0 max: 65535 - name: rth_energy_margin + docs_description: "Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation" + docs_default_value: "5" min: 0 max: 100 - name: thr_comp_weight + docs_description: "Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage)" + docs_default_value: "0.692" field: throttle_compensation_weight min: 0 max: 2 @@ -658,43 +851,61 @@ groups: value_type: BATTERY_CONFIG_VALUE members: - name: bat_cells + docs_description: "Number of cells of the battery (0 = autodetect), see battery documentation" + docs_default_value: "0" field: cells condition: USE_ADC min: 0 max: 8 - name: vbat_cell_detect_voltage + docs_description: "Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units, default is 4.30V" + docs_default_value: "430" field: voltage.cellDetect condition: USE_ADC min: 100 max: 500 - name: vbat_max_cell_voltage + docs_description: "Maximum voltage per cell in 0.01V units, default is 4.20V" + docs_default_value: "420" field: voltage.cellMax condition: USE_ADC min: 100 max: 500 - name: vbat_min_cell_voltage + docs_description: "Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V)" + docs_default_value: "330" field: voltage.cellMin condition: USE_ADC min: 100 max: 500 - name: vbat_warning_cell_voltage + docs_description: "Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V)" + docs_default_value: "350" field: voltage.cellWarning condition: USE_ADC min: 100 max: 500 - name: battery_capacity + docs_description: "Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity." + docs_default_value: "0" field: capacity.value min: 0 max: 4294967295 - name: battery_capacity_warning + docs_description: "If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink." + docs_default_value: "0" field: capacity.warning min: 0 max: 4294967295 - name: battery_capacity_critical + docs_description: "If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps." + docs_default_value: "0" field: capacity.critical min: 0 max: 4294967295 - name: battery_capacity_unit + docs_description: "Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour)." + docs_default_value: "MAH" field: capacity.unit table: bat_capacity_unit type: uint8_t @@ -703,20 +914,30 @@ groups: type: mixerConfig_t members: - name: motor_direction_inverted + docs_description: "Use if you need to inverse yaw motor direction." + docs_default_value: "OFF" field: motorDirectionInverted type: bool - name: platform_type + docs_description: "Defines UAV platform type. Allowed values: \"MULTIROTOR\", \"AIRPLANE\", \"HELICOPTER\", \"TRICOPTER\", \"ROVER\", \"BOAT\". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented" + docs_default_value: "\"MULTIROTOR\"" field: platformType type: uint8_t table: platform_type - name: has_flaps + docs_description: "Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot" + docs_default_value: "OFF" field: hasFlaps type: bool - name: model_preview_type + docs_description: "ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons." + docs_default_value: "-1" field: appliedMixerPreset min: -1 max: INT16_MAX - name: fw_min_throttle_down_pitch + docs_description: "Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)" + docs_default_value: "0" field: fwMinThrottleDownPitchAngle min: 0 max: 450 @@ -725,14 +946,20 @@ groups: type: reversibleMotorsConfig_t members: - name: 3d_deadband_low + docs_description: "Low value of throttle deadband for 3D mode (when stick is in the 3d_deadband_throttle range, the fixed values of 3d_deadband_low / _high are used instead)" + docs_default_value: "1406" field: deadband_low min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: 3d_deadband_high + docs_description: "High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead)" + docs_default_value: "1514" field: deadband_high min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: 3d_neutral + docs_description: "Neutral (stop) throttle value for 3D mode" + docs_default_value: "1460" field: neutral min: PWM_RANGE_MIN max: PWM_RANGE_MAX @@ -742,24 +969,36 @@ groups: headers: ["flight/servos.h"] members: - name: servo_protocol + docs_description: "An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SERVO_DRIVER` (I2C PCA9685 peripheral), `SBUS` (S.Bus protocol output via a configured serial port)" + docs_default_value: "PWM" field: servo_protocol table: servo_protocol - name: servo_center_pulse + docs_description: "Servo midpoint" + docs_default_value: "1500" field: servoCenterPulse min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: servo_pwm_rate + docs_description: "Output frequency (in Hz) servo pins. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz." + docs_default_value: "50" field: servoPwmRate min: 50 max: 498 - name: servo_lpf_hz + docs_description: "Selects the servo PWM output cutoff frequency. Value is in [Hz]" + docs_default_value: "20" field: servo_lowpass_freq min: 0 max: 400 - name: flaperon_throw_offset + docs_description: "Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated." + docs_default_value: "200" min: FLAPERON_THROW_MIN max: FLAPERON_THROW_MAX - name: tri_unarmed_servo + docs_description: "On tricopter mix only, if this is set to ON, servo will always be correcting regardless of armed state. to disable this, set it to OFF." + docs_default_value: "ON" type: bool - name: PG_CONTROL_RATE_PROFILES @@ -768,64 +1007,94 @@ groups: value_type: CONTROL_RATE_VALUE members: - name: thr_mid + docs_description: "Throttle value when the stick is set to mid-position. Used in the throttle curve calculation." + docs_default_value: "50" field: throttle.rcMid8 min: 0 max: 100 - name: thr_expo + docs_description: "Throttle exposition value" + docs_default_value: "0" field: throttle.rcExpo8 min: 0 max: 100 - name: tpa_rate + docs_description: "Throttle PID attenuation reduces influence of P on ROLL and PITCH as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate." + docs_default_value: "0" field: throttle.dynPID min: 0 max: CONTROL_RATE_CONFIG_TPA_MAX - name: tpa_breakpoint + docs_description: "See tpa_rate." + docs_default_value: "1500" field: throttle.pa_breakpoint min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: fw_tpa_time_constant + docs_description: "TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. Planes with low thrust/weight ratio generally need higher time constant. Default is zero for compatibility with old setups" + docs_default_value: "0" field: throttle.fixedWingTauMs min: 0 max: 5000 - name: rc_expo + docs_description: "Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`)" + docs_default_value: "70" field: stabilized.rcExpo8 min: 0 max: 100 - name: rc_yaw_expo + docs_description: "Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`)" + docs_default_value: "20" field: stabilized.rcYawExpo8 min: 0 max: 100 # New rates are in dps/10. That means, Rate of 20 means 200dps of rotation speed on given axis. # Rate 180 (1800dps) is max. value gyro can measure reliably - name: roll_rate + docs_description: "Defines rotation rate on ROLL axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure." + docs_default_value: "20" field: stabilized.rates[FD_ROLL] min: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN max: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX - name: pitch_rate + docs_description: "Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure." + docs_default_value: "20" field: stabilized.rates[FD_PITCH] min: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN max: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX - name: yaw_rate + docs_description: "Defines rotation rate on YAW axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure." + docs_default_value: "20" field: stabilized.rates[FD_YAW] min: CONTROL_RATE_CONFIG_YAW_RATE_MIN max: CONTROL_RATE_CONFIG_YAW_RATE_MAX - name: manual_rc_expo + docs_description: "Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100]" + docs_default_value: "70" field: manual.rcExpo8 min: 0 max: 100 - name: manual_rc_yaw_expo + docs_description: "Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100]" + docs_default_value: "20" field: manual.rcYawExpo8 min: 0 max: 100 - name: manual_roll_rate + docs_description: "Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]%" + docs_default_value: "100" field: manual.rates[FD_ROLL] min: 0 max: 100 - name: manual_pitch_rate + docs_description: "Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]%" + docs_default_value: "100" field: manual.rates[FD_PITCH] min: 0 max: 100 - name: manual_yaw_rate + docs_description: "Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]%" + docs_default_value: "100" field: manual.rates[FD_YAW] min: 0 max: 100 @@ -839,6 +1108,8 @@ groups: headers: ["io/serial.h"] members: - name: reboot_character + docs_description: "Special character used to trigger reboot" + docs_default_value: "82" min: 48 max: 126 @@ -847,25 +1118,39 @@ groups: headers: ["flight/imu.h"] members: - name: imu_dcm_kp + docs_description: "Inertial Measurement Unit KP Gain for accelerometer measurements" + docs_default_value: "2500" field: dcm_kp_acc max: UINT16_MAX - name: imu_dcm_ki + docs_description: "Inertial Measurement Unit KI Gain for accelerometer measurements" + docs_default_value: "50" field: dcm_ki_acc max: UINT16_MAX - name: imu_dcm_kp_mag + docs_description: "Inertial Measurement Unit KP Gain for compass measurements" + docs_default_value: "10000" field: dcm_kp_mag max: UINT16_MAX - name: imu_dcm_ki_mag + docs_description: "Inertial Measurement Unit KI Gain for compass measurements" + docs_default_value: "0" field: dcm_ki_mag max: UINT16_MAX - name: small_angle + docs_description: "If the aircraft tilt angle exceed this value the copter will refuse to arm." + docs_default_value: "25" min: 0 max: 180 - name: imu_acc_ignore_rate + docs_description: "Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes" + docs_default_value: "0" field: acc_ignore_rate min: 0 max: 20 - name: imu_acc_ignore_slope + docs_description: "Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight)" + docs_default_value: "0" field: acc_ignore_slope min: 0 max: 5 @@ -874,10 +1159,16 @@ groups: type: armingConfig_t members: - name: fixed_wing_auto_arm + docs_description: "Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured." + docs_default_value: "OFF" type: bool - name: disarm_kill_switch + docs_description: "Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel." + docs_default_value: "ON" type: bool - name: switch_disarm_delay + docs_description: "Delay before disarming when requested by switch (ms) [0-1000]" + docs_default_value: "250" field: switchDisarmDelayMs min: 0 max: 1000 @@ -896,19 +1187,27 @@ groups: type: rpmFilterConfig_t members: - name: rpm_gyro_filter_enabled + docs_description: "Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV" + docs_default_value: "`OFF`" field: gyro_filter_enabled type: bool - name: rpm_gyro_harmonics + docs_description: "Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine" + docs_default_value: "1" field: gyro_harmonics type: uint8_t min: 1 max: 3 - name: rpm_gyro_min_hz + docs_description: "The lowest frequency for gyro RPM filtere. Default `150` is fine for 5\" mini-quads. On 7-inch drones you can lower even down to `60`-`70`" + docs_default_value: "150" field: gyro_min_hz type: uint8_t min: 30 max: 200 - name: rpm_gyro_q + docs_description: "Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting" + docs_default_value: "500" field: gyro_q type: uint16_t min: 1 @@ -918,27 +1217,41 @@ groups: condition: USE_GPS members: - name: gps_provider + docs_description: "Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N)." + docs_default_value: "UBLOX" field: provider table: gps_provider type: uint8_t - name: gps_sbas_mode + docs_description: "Which SBAS mode to be used" + docs_default_value: "NONE" field: sbasMode table: gps_sbas_mode type: uint8_t - name: gps_dyn_model + docs_description: "GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying." + docs_default_value: "AIR_1G" field: dynModel table: gps_dyn_model type: uint8_t - name: gps_auto_config + docs_description: "Enable automatic configuration of UBlox GPS receivers." + docs_default_value: "ON" field: autoConfig type: bool - name: gps_auto_baud + docs_description: "Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS. When used with NAZA/DJI it will automatic detect GPS baudrate and change to it, ignoring the selected baudrate set in ports" + docs_default_value: "ON" field: autoBaud type: bool - name: gps_ublox_use_galileo + docs_description: "Enable use of Galileo satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires M8N and Ublox firmware 3.x (or later) [OFF/ON]." + docs_default_value: "OFF" field: ubloxUseGalileo type: bool - name: gps_min_sats + docs_description: "Minimum number of GPS satellites in view to acquire GPS_FIX and consider GPS position valid. Some GPS receivers appeared to be very inaccurate with low satellite count." + docs_default_value: "6" field: gpsMinSats min: 5 max: 10 @@ -948,25 +1261,39 @@ groups: headers: ["fc/rc_controls.h"] members: - name: deadband + docs_description: "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle." + docs_default_value: "5" min: 0 max: 32 - name: yaw_deadband + docs_description: "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle." + docs_default_value: "5" min: 0 max: 100 - name: pos_hold_deadband + docs_description: "Stick deadband in [r/c points], applied after r/c deadband and expo" + docs_default_value: "20" min: 2 max: 250 - name: alt_hold_deadband + docs_description: "Defines the deadband of throttle during alt_hold [r/c points]" + docs_default_value: "50" min: 10 max: 250 - name: 3d_deadband_throttle + docs_description: "Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter." + docs_default_value: "50" field: mid_throttle_deadband min: 0 max: 200 - name: mc_airmode_type + docs_description: "Defines the Airmode state handling type for Multirotors. Default **STICK_CENTER** is the classical approach in which Airmode is always active if enabled, but when the throttle is low and ROLL/PITCH/YAW sticks are centered, Iterms is not allowed to grow (ANTI_WINDUP). **THROTTLE_THRESHOLD** is the Airmode behavior known from Betaflight. In this mode, Airmode is active as soon THROTTLE position is above `mc_airmode_threshold` and stays active until disarm. ANTI_WINDUP is never triggered. For small Multirotors (up to 7-inch propellers) it is suggested to switch to **THROTTLE_THRESHOLD** since it keeps full stabilization no matter what pilot does with the sticks. Fixed Wings always use **STICK_CENTER** mode." + docs_default_value: "STICK_CENTER" field: airmodeHandlingType table: airmodeHandlingType - name: mc_airmode_threshold + docs_description: "Defines airmode THROTTLE activation threshold when `mc_airmode_type` **THROTTLE_THRESHOLD** is used" + docs_default_value: "1300" field: airmodeThrottleThreshold min: 1000 max: 2000 @@ -977,214 +1304,320 @@ groups: value_type: PROFILE_VALUE members: - name: mc_p_pitch + docs_description: "Multicopter rate stabilisation P-gain for PITCH" + docs_default_value: "40" field: bank_mc.pid[PID_PITCH].P min: 0 max: 200 - name: mc_i_pitch + docs_description: "Multicopter rate stabilisation I-gain for PITCH" + docs_default_value: "30" field: bank_mc.pid[PID_PITCH].I min: 0 max: 200 - name: mc_d_pitch + docs_description: "Multicopter rate stabilisation D-gain for PITCH" + docs_default_value: "23" field: bank_mc.pid[PID_PITCH].D min: 0 max: 200 - name: mc_cd_pitch + docs_description: "Multicopter Control Derivative gain for PITCH" + docs_default_value: "60" field: bank_mc.pid[PID_PITCH].FF min: 0 max: 200 - name: mc_p_roll + docs_description: "Multicopter rate stabilisation P-gain for ROLL" + docs_default_value: "40" field: bank_mc.pid[PID_ROLL].P min: 0 max: 200 - name: mc_i_roll + docs_description: "Multicopter rate stabilisation I-gain for ROLL" + docs_default_value: "30" field: bank_mc.pid[PID_ROLL].I min: 0 max: 200 - name: mc_d_roll + docs_description: "Multicopter rate stabilisation D-gain for ROLL" + docs_default_value: "23" field: bank_mc.pid[PID_ROLL].D min: 0 max: 200 - name: mc_cd_roll + docs_description: "Multicopter Control Derivative gain for ROLL" + docs_default_value: "60" field: bank_mc.pid[PID_ROLL].FF min: 0 max: 200 - name: mc_p_yaw + docs_description: "Multicopter rate stabilisation P-gain for YAW" + docs_default_value: "85" field: bank_mc.pid[PID_YAW].P min: 0 max: 200 - name: mc_i_yaw + docs_description: "Multicopter rate stabilisation I-gain for YAW" + docs_default_value: "45" field: bank_mc.pid[PID_YAW].I min: 0 max: 200 - name: mc_d_yaw + docs_description: "Multicopter rate stabilisation D-gain for YAW" + docs_default_value: "0" field: bank_mc.pid[PID_YAW].D min: 0 max: 200 - name: mc_cd_yaw + docs_description: "Multicopter Control Derivative gain for YAW" + docs_default_value: "60" field: bank_mc.pid[PID_YAW].FF min: 0 max: 200 - name: mc_p_level + docs_description: "Multicopter attitude stabilisation P-gain" + docs_default_value: "20" field: bank_mc.pid[PID_LEVEL].P min: 0 max: 200 - name: mc_i_level + docs_description: "Multicopter attitude stabilisation low-pass filter cutoff" + docs_default_value: "15" field: bank_mc.pid[PID_LEVEL].I min: 0 max: 200 - name: mc_d_level + docs_description: "Multicopter attitude stabilisation HORIZON transition point" + docs_default_value: "75" field: bank_mc.pid[PID_LEVEL].D min: 0 max: 200 - name: fw_p_pitch + docs_description: "Fixed-wing rate stabilisation P-gain for PITCH" + docs_default_value: "5" field: bank_fw.pid[PID_PITCH].P min: 0 max: 200 - name: fw_i_pitch + docs_description: "Fixed-wing rate stabilisation I-gain for PITCH" + docs_default_value: "7" field: bank_fw.pid[PID_PITCH].I min: 0 max: 200 - name: fw_ff_pitch + docs_description: "Fixed-wing rate stabilisation FF-gain for PITCH" + docs_default_value: "50" field: bank_fw.pid[PID_PITCH].FF min: 0 max: 200 - name: fw_p_roll + docs_description: "Fixed-wing rate stabilisation P-gain for ROLL" + docs_default_value: "5" field: bank_fw.pid[PID_ROLL].P min: 0 max: 200 - name: fw_i_roll + docs_description: "Fixed-wing rate stabilisation I-gain for ROLL" + docs_default_value: "7" field: bank_fw.pid[PID_ROLL].I min: 0 max: 200 - name: fw_ff_roll + docs_description: "Fixed-wing rate stabilisation FF-gain for ROLL" + docs_default_value: "50" field: bank_fw.pid[PID_ROLL].FF min: 0 max: 200 - name: fw_p_yaw + docs_description: "Fixed-wing rate stabilisation P-gain for YAW" + docs_default_value: "6" field: bank_fw.pid[PID_YAW].P min: 0 max: 200 - name: fw_i_yaw + docs_description: "Fixed-wing rate stabilisation I-gain for YAW" + docs_default_value: "10" field: bank_fw.pid[PID_YAW].I min: 0 max: 200 - name: fw_ff_yaw + docs_description: "Fixed-wing rate stabilisation FF-gain for YAW" + docs_default_value: "60" field: bank_fw.pid[PID_YAW].FF min: 0 max: 200 - name: fw_p_level + docs_description: "Fixed-wing attitude stabilisation P-gain" + docs_default_value: "20" field: bank_fw.pid[PID_LEVEL].P min: 0 max: 200 - name: fw_i_level + docs_description: "Fixed-wing attitude stabilisation low-pass filter cutoff" + docs_default_value: "5" field: bank_fw.pid[PID_LEVEL].I min: 0 max: 200 - name: fw_d_level + docs_description: "Fixed-wing attitude stabilisation HORIZON transition point" + docs_default_value: "75" field: bank_fw.pid[PID_LEVEL].D min: 0 max: 200 - name: max_angle_inclination_rll + docs_description: "Maximum inclination in level (angle) mode (ROLL axis). 100=10°" + docs_default_value: "300" field: max_angle_inclination[FD_ROLL] min: 100 max: 900 - name: max_angle_inclination_pit + docs_description: "Maximum inclination in level (angle) mode (PITCH axis). 100=10°" + docs_default_value: "300" field: max_angle_inclination[FD_PITCH] min: 100 max: 900 - name: dterm_lpf_hz + docs_description: "Dterm low pass filter cutoff frequency. Default setting is very conservative and small multirotors should use higher value between 80 and 100Hz. 80 seems like a gold spot for 7-inch builds while 100 should work best with 5-inch machines. If motors are getting too hot, lower the value" + docs_default_value: "40" min: 0 max: 500 - name: dterm_lpf_type + docs_description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation." + docs_default_value: "`BIQUAD`" field: dterm_lpf_type table: filter_type - name: dterm_lpf2_hz + docs_description: "Cutoff frequency for stage 2 D-term low pass filter" + docs_default_value: "0" min: 0 max: 500 - name: dterm_lpf2_type + docs_description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation." + docs_default_value: "`BIQUAD`" field: dterm_lpf2_type table: filter_type - name: yaw_lpf_hz + docs_description: "Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below)" + docs_default_value: "30" min: 0 max: 200 - name: fw_iterm_throw_limit + docs_description: "Limits max/min I-term value in stabilization PID controller in case of Fixed Wing. It solves the problem of servo saturation before take-off/throwing the airplane into the air. By default, error accumulated in I-term can not exceed 1/3 of servo throw (around 165us). Set 0 to disable completely." + docs_default_value: "165" field: fixedWingItermThrowLimit min: FW_ITERM_THROW_LIMIT_MIN max: FW_ITERM_THROW_LIMIT_MAX - name: fw_loiter_direction + docs_description: "Direction of loitering: center point on right wing (clockwise - default), or center point on left wing (counterclockwise). If equal YAW then can be changed in flight using a yaw stick." + docs_default_value: "RIGHT" field: loiter_direction condition: USE_NAV table: direction - name: fw_reference_airspeed + docs_description: "Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present." + docs_default_value: "1000" field: fixedWingReferenceAirspeed min: 1 max: 5000 - name: fw_turn_assist_yaw_gain + docs_description: "Gain required to keep the yaw rate consistent with the turn rate for a coordinated turn (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter" + docs_default_value: "1" field: fixedWingCoordinatedYawGain min: 0 max: 2 - name: fw_iterm_limit_stick_position + docs_description: "Iterm is not allowed to grow when stick position is above threshold. This solves the problem of bounceback or followthrough when full stick deflection is applied on poorely tuned fixed wings. In other words, stabilization is partialy disabled when pilot is actively controlling the aircraft and active when sticks are not touched. `0` mean stick is in center position, `1` means it is fully deflected to either side" + docs_default_value: "0.5" field: fixedWingItermLimitOnStickPosition min: 0 max: 1 - name: pidsum_limit + docs_description: "A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help" + docs_default_value: "500" field: pidSumLimit min: PID_SUM_LIMIT_MIN max: PID_SUM_LIMIT_MAX - name: pidsum_limit_yaw + docs_description: "A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help" + docs_default_value: "400" field: pidSumLimitYaw min: PID_SUM_LIMIT_MIN max: PID_SUM_LIMIT_MAX - name: iterm_windup + docs_description: "Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter)" + docs_default_value: "50" field: itermWindupPointPercent min: 0 max: 90 - name: rate_accel_limit_roll_pitch + docs_description: "Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting." + docs_default_value: "0" field: axisAccelerationLimitRollPitch max: 500000 - name: rate_accel_limit_yaw + docs_description: "Limits acceleration of YAW rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 180 dps^2). When set correctly, it greatly improves stopping performance and general stability during yaw turns. Value of 0 disables limiting." + docs_default_value: "10000" field: axisAccelerationLimitYaw max: 500000 - name: heading_hold_rate_limit + docs_description: "This setting limits yaw rotation rate that HEADING_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when HEADING_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes." + docs_default_value: "90" min: HEADING_HOLD_RATE_LIMIT_MIN max: HEADING_HOLD_RATE_LIMIT_MAX - name: nav_mc_pos_z_p + docs_description: "P gain of altitude PID controller (Multirotor)" + docs_default_value: "50" field: bank_mc.pid[PID_POS_Z].P condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_z_p + docs_description: "P gain of velocity PID controller" + docs_default_value: "100" field: bank_mc.pid[PID_VEL_Z].P condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_z_i + docs_description: "I gain of velocity PID controller" + docs_default_value: "50" field: bank_mc.pid[PID_VEL_Z].I condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_z_d + docs_description: "D gain of velocity PID controller" + docs_default_value: "10" field: bank_mc.pid[PID_VEL_Z].D condition: USE_NAV min: 0 max: 255 - name: nav_mc_pos_xy_p + docs_description: "Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity" + docs_default_value: "65" field: bank_mc.pid[PID_POS_XY].P condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_xy_p + docs_description: "P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause \"nervous\" behavior and oscillations" + docs_default_value: "40" field: bank_mc.pid[PID_VEL_XY].P condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_xy_i + docs_description: "I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot" + docs_default_value: "15" field: bank_mc.pid[PID_VEL_XY].I condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_xy_d + docs_description: "D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target." + docs_default_value: "100" field: bank_mc.pid[PID_VEL_XY].D condition: USE_NAV min: 0 @@ -1195,6 +1628,8 @@ groups: min: 0 max: 255 - name: nav_mc_heading_p + docs_description: "P gain of Heading Hold controller (Multirotor)" + docs_default_value: "60" field: bank_mc.pid[PID_HEADING].P condition: USE_NAV min: 0 @@ -1204,56 +1639,78 @@ groups: min: 0 max: 100 - name: nav_fw_pos_z_p + docs_description: "P gain of altitude PID controller (Fixedwing)" + docs_default_value: "50" field: bank_fw.pid[PID_POS_Z].P condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_z_i + docs_description: "I gain of altitude PID controller (Fixedwing)" + docs_default_value: "0" field: bank_fw.pid[PID_POS_Z].I condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_z_d + docs_description: "D gain of altitude PID controller (Fixedwing)" + docs_default_value: "0" field: bank_fw.pid[PID_POS_Z].D condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_xy_p + docs_description: "P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH" + docs_default_value: "75" field: bank_fw.pid[PID_POS_XY].P condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_xy_i + docs_description: "I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero" + docs_default_value: "5" field: bank_fw.pid[PID_POS_XY].I condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_xy_d + docs_description: "D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero" + docs_default_value: "8" field: bank_fw.pid[PID_POS_XY].D condition: USE_NAV min: 0 max: 255 - name: nav_fw_heading_p + docs_description: "P gain of Heading Hold controller (Fixedwing)" + docs_default_value: "60" field: bank_fw.pid[PID_HEADING].P condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_hdg_p + docs_description: "P gain of heading PID controller. (Fixedwing, rovers, boats)" + docs_default_value: "60" field: bank_fw.pid[PID_POS_HEADING].P condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_hdg_i + docs_description: "I gain of heading trajectory PID controller. (Fixedwing, rovers, boats)" + docs_default_value: "0" field: bank_fw.pid[PID_POS_HEADING].I condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_hdg_d + docs_description: "D gain of heading trajectory PID controller. (Fixedwing, rovers, boats)" + docs_default_value: "0" field: bank_fw.pid[PID_POS_HEADING].D condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_hdg_pidsum_limit + docs_description: "Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats)" + docs_default_value: "350" field: navFwPosHdgPidsumLimit min: PID_SUM_LIMIT_MIN max: PID_SUM_LIMIT_MAX @@ -1283,24 +1740,33 @@ groups: min: 10 max: 250 - name: antigravity_gain + docs_description: "Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements" + docs_default_value: "1" field: antigravityGain condition: USE_ANTIGRAVITY min: 1 max: 20 - name: antigravity_accelerator + docs_description: "" + docs_default_value: "1" field: antigravityAccelerator condition: USE_ANTIGRAVITY min: 1 max: 20 - name: antigravity_cutoff_lpf_hz + docs_description: "Antigravity cutoff frequenct for Throtte filter. Antigravity is based on the difference between actual and filtered throttle input. The bigger is the difference, the bigger Antigravity gain" + docs_default_value: "15" field: antigravityCutoff condition: USE_ANTIGRAVITY min: 1 max: 30 - name: pid_type + docs_description: "Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID`" field: pidControllerType table: pidTypeTable - name: mc_cd_lpf_hz + docs_description: "Cutoff frequency for Control Derivative. Lower value smoother reaction on fast stick movements. With higher values, response will be more aggressive, jerky" + docs_default_value: "30" field: controlDerivativeLpfHz min: 0 max: 200 @@ -1310,22 +1776,32 @@ groups: condition: USE_NAV && USE_AUTOTUNE_FIXED_WING members: - name: fw_autotune_overshoot_time + docs_description: "Time [ms] to detect sustained overshoot" + docs_default_value: "100" field: fw_overshoot_time min: 50 max: 500 - name: fw_autotune_undershoot_time + docs_description: "Time [ms] to detect sustained undershoot" + docs_default_value: "200" field: fw_undershoot_time min: 50 max: 500 - name: fw_autotune_threshold + docs_description: "Threshold [%] of max rate to consider overshoot/undershoot detection" + docs_default_value: "50" field: fw_max_rate_threshold min: 0 max: 100 - name: fw_autotune_ff_to_p_gain + docs_description: "FF to P gain (strength relationship) [%]" + docs_default_value: "10" field: fw_ff_to_p_gain min: 0 max: 100 - name: fw_autotune_ff_to_i_tc + docs_description: "FF to I time (defines time for I to reach the same level of response as FF) [ms]" + docs_default_value: "600" field: fw_ff_to_i_time_constant min: 100 max: 5000 @@ -1335,25 +1811,37 @@ groups: condition: USE_NAV members: - name: inav_auto_mag_decl + docs_description: "Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored." + docs_default_value: "ON" field: automatic_mag_declination type: bool - name: inav_gravity_cal_tolerance + docs_description: "Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value." + docs_default_value: "5" field: gravity_calibration_tolerance min: 0 max: 255 - name: inav_use_gps_velned + docs_description: "Defined if iNav should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF iNav will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance." + docs_default_value: "ON" field: use_gps_velned type: bool - name: inav_allow_dead_reckoning field: allow_dead_reckoning type: bool - name: inav_reset_altitude + docs_description: "Defines when relative estimated altitude is reset to zero. Variants - `NEVER` (once reference is acquired it's used regardless); `FIRST_ARM` (keep altitude at zero until firstly armed), `EACH_ARM` (altitude is reset to zero on each arming)" + docs_default_value: "FIRST_ARM" field: reset_altitude_type table: reset_type - name: inav_reset_home + docs_description: "Allows to chose when the home position is reset. Can help prevent resetting home position after accidental mid-air disarm. Possible values are: NEVER, FIRST_ARM and EACH_ARM" + docs_default_value: "FIRST_ARM" field: reset_home_type table: reset_type - name: inav_max_surface_altitude + docs_description: "Max allowed altitude for surface following mode. [cm]" + docs_default_value: "200" field: max_surface_altitude min: 0 max: 1000 @@ -1374,30 +1862,44 @@ groups: min: 0 max: 100 - name: inav_w_z_baro_p + docs_description: "Weight of barometer measurements in estimated altitude and climb rate" + docs_default_value: "0.350" field: w_z_baro_p min: 0 max: 10 - name: inav_w_z_gps_p + docs_description: "Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes" + docs_default_value: "0.200" field: w_z_gps_p min: 0 max: 10 - name: inav_w_z_gps_v + docs_description: "Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero" + docs_default_value: "0.500" field: w_z_gps_v min: 0 max: 10 - name: inav_w_xy_gps_p + docs_description: "Weight of GPS coordinates in estimated UAV position and speed." + docs_default_value: "1.000" field: w_xy_gps_p min: 0 max: 10 - name: inav_w_xy_gps_v + docs_description: "Weight of GPS velocity data in estimated UAV speed" + docs_default_value: "2.000" field: w_xy_gps_v min: 0 max: 10 - name: inav_w_z_res_v + docs_description: "Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost" + docs_default_value: "0.500" field: w_z_res_v min: 0 max: 10 - name: inav_w_xy_res_v + docs_description: "Decay coefficient for estimated velocity when GPS reference for position is lost" + docs_default_value: "0.500" field: w_xy_res_v min: 0 max: 10 @@ -1406,14 +1908,20 @@ groups: min: 0 max: 1 - name: inav_w_acc_bias + docs_description: "Weight for accelerometer drift estimation" + docs_default_value: "0.010" field: w_acc_bias min: 0 max: 1 - name: inav_max_eph_epv + docs_description: "Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm]" + docs_default_value: "1000.000" field: max_eph_epv min: 0 max: 9999 - name: inav_baro_epv + docs_description: "Uncertainty value for barometric sensor [cm]" + docs_default_value: "100.000" field: baro_epv min: 0 max: 9999 @@ -1424,267 +1932,401 @@ groups: condition: USE_NAV members: - name: nav_disarm_on_landing + docs_description: "If set to ON, iNav disarms the FC after landing" + docs_default_value: "OFF" field: general.flags.disarm_on_landing type: bool - name: nav_use_midthr_for_althold + docs_description: "If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude" + docs_default_value: "OFF" field: general.flags.use_thr_mid_for_althold type: bool - name: nav_extra_arming_safety + docs_description: "If set to ON drone won't arm if no GPS fix and any navigation mode like RTH or POSHOLD is configured. ALLOW_BYPASS allows the user to momentarily disable this check by holding yaw high (left stick held at the bottom right in mode 2) when switch arming is used" + docs_default_value: "ON" field: general.flags.extra_arming_safety table: nav_extra_arming_safety - name: nav_user_control_mode + docs_description: "Defines how Pitch/Roll input from RC receiver affects flight in POSHOLD mode: ATTI - pitch/roll controls attitude like in ANGLE mode; CRUISE - pitch/roll controls velocity in forward and right direction." + docs_default_value: "ATTI" field: general.flags.user_control_mode table: nav_user_control_mode - name: nav_position_timeout + docs_description: "If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable)" + docs_default_value: "5" field: general.pos_failure_timeout min: 0 max: 10 - name: nav_wp_radius + docs_description: "Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius" + docs_default_value: "100" field: general.waypoint_radius min: 10 max: 10000 - name: nav_wp_safe_distance + docs_description: "First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check." + docs_default_value: "10000" field: general.waypoint_safe_distance max: 65000 - name: nav_auto_speed + docs_description: "Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only]" + docs_default_value: "300" field: general.max_auto_speed min: 10 max: 2000 - name: nav_auto_climb_rate + docs_description: "Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]" + docs_default_value: "500" field: general.max_auto_climb_rate min: 10 max: 2000 - name: nav_manual_speed + docs_description: "Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only]" + docs_default_value: "500" field: general.max_manual_speed min: 10 max: 2000 - name: nav_manual_climb_rate + docs_description: "Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]" + docs_default_value: "200" field: general.max_manual_climb_rate min: 10 max: 2000 - name: nav_landing_speed + docs_description: "Vertical descent velocity during the RTH landing phase. [cm/s]" + docs_default_value: "200" field: general.land_descent_rate min: 100 max: 2000 - name: nav_land_slowdown_minalt + docs_description: "Defines at what altitude the descent velocity should start to be 25% of nav_landing_speed [cm]" + docs_default_value: "500" field: general.land_slowdown_minalt min: 50 max: 1000 - name: nav_land_slowdown_maxalt + docs_description: "Defines at what altitude the descent velocity should start to ramp down from 100% nav_landing_speed to 25% nav_landing_speed. [cm]" + docs_default_value: "2000" field: general.land_slowdown_maxalt min: 500 max: 4000 - name: nav_emerg_landing_speed + docs_description: "Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s]" + docs_default_value: "500" field: general.emerg_descent_rate min: 100 max: 2000 - name: nav_min_rth_distance + docs_description: "Minimum distance from homepoint when RTH full procedure will be activated [cm]. Below this distance, the mode will activate at the current location and the final phase is executed (loiter / land). Above this distance, the full procedure is activated, which may include initial climb and flying directly to the homepoint before entering the loiter / land phase." + docs_default_value: "500" field: general.min_rth_distance min: 0 max: 5000 - name: nav_overrides_motor_stop + docs_description: "Setting to OFF combined with MOTOR_STOP feature will allow user to stop motor when in autonomous modes. On most places this setting is likely to cause a stall." + docs_default_value: "ON" field: general.flags.auto_overrides_motor_stop type: bool - name: nav_rth_climb_first + docs_description: "If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way." + docs_default_value: "ON" field: general.flags.rth_climb_first type: bool - name: nav_rth_climb_ignore_emerg + docs_description: "If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status." + docs_default_value: "OFF" field: general.flags.rth_climb_ignore_emerg type: bool - name: nav_rth_tail_first + docs_description: "If set to ON drone will return tail-first. Obviously meaningless for airplanes." + docs_default_value: "OFF" field: general.flags.rth_tail_first type: bool - name: nav_rth_allow_landing + docs_description: "If set to ON drone will land as a last phase of RTH." + docs_default_value: "ALWAYS" field: general.flags.rth_allow_landing table: nav_rth_allow_landing - name: nav_rth_alt_mode + docs_description: "Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details" + docs_default_value: "AT_LEAST" field: general.flags.rth_alt_control_mode table: nav_rth_alt_mode - name: nav_rth_abort_threshold + docs_description: "RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. [cm]" + docs_default_value: "50000" field: general.rth_abort_threshold max: 65000 - name: nav_max_terrain_follow_alt field: general.max_terrain_follow_altitude max: 1000 - name: nav_rth_altitude + docs_description: "Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters)" + docs_default_value: "1000" field: general.rth_altitude max: 65000 - name: nav_rth_home_altitude + docs_description: "Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm]" + docs_default_value: "0" field: general.rth_home_altitude max: 65000 - name: nav_rth_home_offset_distance + docs_description: "Distance offset from GPS established home to \"safe\" position used for RTH (cm, 0 disables)" + docs_default_value: "0" field: general.rth_home_offset_distance max: 65000 - name: nav_rth_home_offset_direction + docs_description: "Direction offset from GPS established home to \"safe\" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance)" + docs_default_value: "0" field: general.rth_home_offset_direction max: 359 - name: nav_mc_bank_angle + docs_description: "Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude" + docs_default_value: "30" field: mc.max_bank_angle min: 15 max: 45 - name: nav_mc_hover_thr + docs_description: "Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering." + docs_default_value: "1500" field: mc.hover_throttle min: 1000 max: 2000 - name: nav_mc_auto_disarm_delay + docs_description: "" + docs_default_value: "2000" field: mc.auto_disarm_delay min: 100 max: 10000 - name: nav_mc_braking_speed_threshold + docs_description: "min speed in cm/s above which braking can happen" + docs_default_value: "100" field: mc.braking_speed_threshold condition: USE_MR_BRAKING_MODE min: 0 max: 1000 - name: nav_mc_braking_disengage_speed + docs_description: "braking is disabled when speed goes below this value" + docs_default_value: "75" field: mc.braking_disengage_speed condition: USE_MR_BRAKING_MODE min: 0 max: 1000 - name: nav_mc_braking_timeout + docs_description: "timeout in ms for braking" + docs_default_value: "2000" field: mc.braking_timeout condition: USE_MR_BRAKING_MODE min: 100 max: 5000 - name: nav_mc_braking_boost_factor + docs_description: "acceleration factor for BOOST phase" + docs_default_value: "100" field: mc.braking_boost_factor condition: USE_MR_BRAKING_MODE min: 0 max: 200 - name: nav_mc_braking_boost_timeout + docs_description: "how long in ms BOOST phase can happen" + docs_default_value: "750" field: mc.braking_boost_timeout condition: USE_MR_BRAKING_MODE min: 0 max: 5000 - name: nav_mc_braking_boost_speed_threshold + docs_description: "BOOST can be enabled when speed is above this value" + docs_default_value: "150" field: mc.braking_boost_speed_threshold condition: USE_MR_BRAKING_MODE min: 100 max: 1000 - name: nav_mc_braking_boost_disengage_speed + docs_description: "BOOST will be disabled when speed goes below this value" + docs_default_value: "100" field: mc.braking_boost_disengage_speed condition: USE_MR_BRAKING_MODE min: 0 max: 1000 - name: nav_mc_braking_bank_angle + docs_description: "max angle that MR is allowed to bank in BOOST mode" + docs_default_value: "40" field: mc.braking_bank_angle condition: USE_MR_BRAKING_MODE min: 15 max: 60 - name: nav_mc_pos_deceleration_time + docs_description: "Used for stoping distance calculation. Stop position is computed as _speed_ * _nav_mc_pos_deceleration_time_ from the place where sticks are released. Braking mode overrides this setting" + docs_default_value: "120" field: mc.posDecelerationTime condition: USE_NAV min: 0 max: 255 - name: nav_mc_pos_expo + docs_description: "Expo for PosHold control" + docs_default_value: "10" field: mc.posResponseExpo condition: USE_NAV min: 0 max: 255 - name: nav_fw_cruise_thr + docs_description: "Cruise throttle in GPS assisted modes, this includes RTH. Should be set high enough to avoid stalling. This values gives INAV a base for throttle when flying straight, and it will increase or decrease throttle based on pitch of airplane and the parameters below. In addition it will increase throttle if GPS speed gets below 7m/s ( hardcoded )" + docs_default_value: "1400" field: fw.cruise_throttle min: 1000 max: 2000 - name: nav_fw_min_thr + docs_description: "Minimum throttle for flying wing in GPS assisted modes" + docs_default_value: "1200" field: fw.min_throttle min: 1000 max: 2000 - name: nav_fw_max_thr + docs_description: "Maximum throttle for flying wing in GPS assisted modes" + docs_default_value: "1700" field: fw.max_throttle min: 1000 max: 2000 - name: nav_fw_bank_angle + docs_description: "Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll" + docs_default_value: "20" field: fw.max_bank_angle min: 5 max: 80 - name: nav_fw_climb_angle + docs_description: "Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit" + docs_default_value: "20" field: fw.max_climb_angle min: 5 max: 80 - name: nav_fw_dive_angle + docs_description: "Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit" + docs_default_value: "15" field: fw.max_dive_angle min: 5 max: 80 - name: nav_fw_pitch2thr + docs_description: "Amount of throttle applied related to pitch attitude in GPS assisted modes. Throttle = nav_fw_cruise_throttle - (nav_fw_pitch2thr * pitch_angle). (notice that pitch_angle is in degrees and is negative when climbing and positive when diving, and throttle value is constrained between nav_fw_min_thr and nav_fw_max_thr)" + docs_default_value: "10" field: fw.pitch_to_throttle min: 0 max: 100 - name: nav_fw_loiter_radius + docs_description: "PosHold radius. 3000 to 7500 is a good value (30-75m) [cm]" + docs_default_value: "5000" field: fw.loiter_radius min: 0 max: 10000 - name: nav_fw_cruise_speed + docs_description: "Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s" + docs_default_value: "0" field: fw.cruise_speed min: 0 max: 65535 - name: nav_fw_control_smoothness + docs_description: "How smoothly the autopilot controls the airplane to correct the navigation error" + docs_default_value: "0" field: fw.control_smoothness min: 0 max: 9 - name: nav_fw_land_dive_angle + docs_description: "Dive angle that airplane will use during final landing phase. During dive phase, motor is stopped or IDLE and roll control is locked to 0 degrees" + docs_default_value: "2" field: fw.land_dive_angle condition: NAV_FIXED_WING_LANDING min: -20 max: 20 - name: nav_fw_launch_velocity + docs_description: "Forward velocity threshold for swing-launch detection [cm/s]" + docs_default_value: "300" field: fw.launch_velocity_thresh min: 100 max: 10000 - name: nav_fw_launch_accel + docs_description: "Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s" + docs_default_value: "1863" field: fw.launch_accel_thresh min: 1000 max: 20000 - name: nav_fw_launch_max_angle + docs_description: "Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg]" + docs_default_value: "45" field: fw.launch_max_angle min: 5 max: 180 - name: nav_fw_launch_detect_time + docs_description: "Time for which thresholds have to breached to consider launch happened [ms]" + docs_default_value: "40" field: fw.launch_time_thresh min: 10 max: 1000 - name: nav_fw_launch_thr + docs_description: "Launch throttle - throttle to be set during launch sequence (pwm units)" + docs_default_value: "1700" field: fw.launch_throttle min: 1000 max: 2000 - name: nav_fw_launch_idle_thr + docs_description: "Launch idle throttle - throttle to be set before launch sequence is initiated. If set below minimum throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above minimum throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position)" + docs_default_value: "1000" field: fw.launch_idle_throttle min: 1000 max: 2000 - name: nav_fw_launch_motor_delay + docs_description: "Delay between detected launch and launch sequence start and throttling up (ms)" + docs_default_value: "500" field: fw.launch_motor_timer min: 0 max: 5000 - name: nav_fw_launch_spinup_time + docs_description: "Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller" + docs_default_value: "100" field: fw.launch_motor_spinup_time min: 0 max: 1000 - name: nav_fw_launch_min_time + docs_description: "Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]." + docs_default_value: "0" field: fw.launch_min_time min: 0 max: 60000 - name: nav_fw_launch_timeout + docs_description: "Maximum time for launch sequence to be executed. After this time LAUNCH mode will be turned off and regular flight mode will take over (ms)" + docs_default_value: "5000" field: fw.launch_timeout max: 60000 - name: nav_fw_launch_max_altitude + docs_description: "Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]." + docs_default_value: "0" field: fw.launch_max_altitude min: 0 max: 60000 - name: nav_fw_launch_climb_angle + docs_description: "Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit" + docs_default_value: "18" field: fw.launch_climb_angle min: 5 max: 45 - name: nav_fw_cruise_yaw_rate + docs_description: "Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps]" + docs_default_value: "20" field: fw.cruise_yaw_rate min: 0 max: 60 - name: nav_fw_allow_manual_thr_increase + docs_description: "Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing" + docs_default_value: "OFF" field: fw.allow_manual_thr_increase type: bool - name: nav_use_fw_yaw_control + docs_description: "Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats" + docs_default_value: "OFF" field: fw.useFwNavYawControl type: bool - name: nav_fw_yaw_deadband + docs_description: "Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course" + docs_default_value: "0" field: fw.yawControlDeadband min: 0 max: 90 @@ -1695,92 +2337,136 @@ groups: condition: USE_TELEMETRY members: - name: telemetry_switch + docs_description: "Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed." + docs_default_value: "OFF" type: bool - name: telemetry_inverted + docs_description: "Determines if the telemetry protocol default signal inversion is reversed. This should be OFF in most cases unless a custom or hacked RX is used." + docs_default_value: "OFF" type: bool - name: frsky_default_latitude + docs_description: "D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired." + docs_default_value: "0.000" field: gpsNoFixLatitude min: -90 max: 90 - name: frsky_default_longitude + docs_description: "D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired." + docs_default_value: "0.000" field: gpsNoFixLongitude min: -180 max: 180 - name: frsky_coordinates_format + docs_description: "D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA" + docs_default_value: "0" field: frsky_coordinate_format min: 0 max: FRSKY_FORMAT_NMEA type: uint8_t # TODO: This seems to use an enum, we should use table: - name: frsky_unit + docs_description: "Not used? [METRIC/IMPERIAL]" + docs_default_value: "METRIC" table: frsky_unit type: uint8_t - name: frsky_vfas_precision + docs_description: "D-Series telemetry only: Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method" + docs_default_value: "0" min: FRSKY_VFAS_PRECISION_LOW max: FRSKY_VFAS_PRECISION_HIGH - name: frsky_pitch_roll + docs_description: "S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data" + docs_default_value: "OFF" type: bool - name: report_cell_voltage + docs_description: "S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON" + docs_default_value: "OFF" type: bool - name: hott_alarm_sound_interval + docs_description: "Battery alarm delay in seconds for Hott telemetry" + docs_default_value: "5" field: hottAlarmSoundInterval min: 0 max: 120 - name: telemetry_halfduplex + docs_description: "S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details" + docs_default_value: "OFF" field: halfDuplex type: bool - name: smartport_fuel_unit + docs_description: "S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH]" + docs_default_value: "MAH" field: smartportFuelUnit condition: USE_TELEMETRY_SMARTPORT type: uint8_t table: smartport_fuel_unit - name: ibus_telemetry_type + docs_description: "Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details." + docs_default_value: "0" field: ibusTelemetryType min: 0 max: 255 - name: ltm_update_rate + docs_description: "Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details." + docs_default_value: "NORMAL" field: ltmUpdateRate condition: USE_TELEMETRY_LTM table: ltm_rates - name: sim_ground_station_number + docs_description: "Number of phone that is used to communicate with SIM module. Messages / calls from other numbers are ignored. If undefined, can be set by calling or sending a message to the module." + docs_default_value: "Empty string" field: simGroundStationNumber condition: USE_TELEMETRY_SIM type: string max: 16 - name: sim_pin + docs_description: "PIN code for the SIM module" + docs_default_value: "Empty string" field: simPin condition: USE_TELEMETRY_SIM type: string max: 8 - name: sim_transmit_interval + docs_description: "Text message transmission interval in seconds for SIM module. Minimum value: 10" + docs_default_value: "60" field: simTransmitInterval condition: USE_TELEMETRY_SIM type: uint16_t min: SIM_MIN_TRANSMIT_INTERVAL max: 65535 - name: sim_transmit_flags + docs_description: "String specifying text message transmit condition flags for the SIM module. Flags can be given in any order. Empty string means the module only sends response messages. `A`: acceleration events, `T`: continuous transmission, `F`: continuous transmission in failsafe mode, `L`: continuous transmission when altitude is below `sim_low_altitude`, `G`: continuous transmission when GPS signal quality is low" + docs_default_value: "F" field: simTransmitFlags condition: USE_TELEMETRY_SIM type: string max: SIM_N_TX_FLAGS - name: acc_event_threshold_high + docs_description: "Acceleration threshold [cm/s/s] for impact / high g event text messages sent by SIM module. Acceleration values greater than 4 g can occur in fixed wing flight without an impact, so a setting of 4000 or greater is suggested. 0 = detection off." + docs_default_value: "0" field: accEventThresholdHigh condition: USE_TELEMETRY_SIM type: uint16_t min: 0 max: 65535 - name: acc_event_threshold_low + docs_description: "Acceleration threshold [cm/s/s] for low-g / freefall detection text messages sent by SIM module. A setting of less than 100 is suggested. Valid values: [0-900], 0 = detection off." + docs_default_value: "0" field: accEventThresholdLow condition: USE_TELEMETRY_SIM type: uint16_t min: 0 max: 900 - name: acc_event_threshold_neg_x + docs_description: "Acceleration threshold [cm/s/s] for backwards acceleration / fixed wing landing detection text messages sent by SIM module. Suggested value for fixed wing: 1100. 0 = detection off." + docs_default_value: "0" field: accEventThresholdNegX condition: USE_TELEMETRY_SIM type: uint16_t min: 0 max: 65535 - name: sim_low_altitude + docs_description: "Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`." + docs_default_value: "0" field: simLowAltitude condition: USE_TELEMETRY_SIM type: int16_t @@ -1848,6 +2534,8 @@ groups: condition: USE_LED_STRIP members: - name: ledstrip_visual_beeper + docs_description: "" + docs_default_value: "OFF" type: bool - name: PG_OSD_CONFIG @@ -1856,85 +2544,125 @@ groups: condition: USE_OSD members: - name: osd_video_system + docs_description: "Video system used. Possible values are `AUTO`, `PAL` and `NTSC`" + docs_default_value: "AUTO" table: osd_video_system field: video_system type: uint8_t - name: osd_row_shiftdown + docs_description: "Number of rows to shift the OSD display (increase if top rows are cut off)" + docs_default_value: "0" field: row_shiftdown min: 0 max: 1 - name: osd_units + docs_description: "IMPERIAL, METRIC, UK" + docs_default_value: "METRIC" field: units table: osd_unit type: uint8_t - name: osd_stats_energy_unit + docs_description: "Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour)" + docs_default_value: "MAH" field: stats_energy_unit table: osd_stats_energy_unit type: uint8_t - name: osd_rssi_alarm + docs_description: "Value bellow which to make the OSD RSSI indicator blink" + docs_default_value: "20" field: rssi_alarm min: 0 max: 100 - name: osd_time_alarm + docs_description: "Value above which to make the OSD flight time indicator blink (minutes)" + docs_default_value: "10" field: time_alarm min: 0 max: 600 - name: osd_alt_alarm + docs_description: "Value above which to make the OSD relative altitude indicator blink (meters)" + docs_default_value: "100" field: alt_alarm min: 0 max: 10000 - name: osd_dist_alarm + docs_description: "Value above which to make the OSD distance from home indicator blink (meters)" + docs_default_value: "1000" field: dist_alarm min: 0 max: 50000 - name: osd_neg_alt_alarm + docs_description: "Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters)" + docs_default_value: "5" field: neg_alt_alarm min: 0 max: 10000 - name: osd_current_alarm + docs_description: "Value above which the OSD current consumption element will start blinking. Measured in full Amperes." + docs_default_value: "0" field: current_alarm min: 0 max: 255 - name: osd_gforce_alarm + docs_description: "Value above which the OSD g force indicator will blink (g)" + docs_default_value: "5" field: gforce_alarm min: 0 max: 20 - name: osd_gforce_axis_alarm_min + docs_description: "Value under which the OSD axis g force indicators will blink (g)" + docs_default_value: "-5" field: gforce_axis_alarm_min min: -20 max: 20 - name: osd_gforce_axis_alarm_max + docs_description: "Value above which the OSD axis g force indicators will blink (g)" + docs_default_value: "5" field: gforce_axis_alarm_max min: -20 max: 20 - name: osd_imu_temp_alarm_min + docs_description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)" + docs_default_value: "-200" field: imu_temp_alarm_min min: -550 max: 1250 - name: osd_imu_temp_alarm_max + docs_description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)" + docs_default_value: "600" field: imu_temp_alarm_max min: -550 max: 1250 - name: osd_esc_temp_alarm_max + docs_description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)" + docs_default_value: "900" field: esc_temp_alarm_max min: -550 max: 1500 - name: osd_esc_temp_alarm_min + docs_description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)" + docs_default_value: "-200" field: esc_temp_alarm_min min: -550 max: 1500 - name: osd_baro_temp_alarm_min + docs_description: "Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade)" + docs_default_value: "-200" field: baro_temp_alarm_min condition: USE_BARO min: -550 max: 1250 - name: osd_baro_temp_alarm_max + docs_description: "Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade)" + docs_default_value: "600" field: baro_temp_alarm_max condition: USE_BARO min: -550 max: 1250 - name: osd_temp_label_align + docs_description: "Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT`" + docs_default_value: "LEFT" field: temp_label_align condition: USE_TEMPERATURE_SENSOR table: osd_alignment @@ -1944,6 +2672,8 @@ groups: field: ahi_reverse_roll type: bool - name: osd_artificial_horizon_max_pitch + docs_description: "Max pitch, in degrees, for OSD artificial horizon" + docs_default_value: "20" field: ahi_max_pitch min: 10 max: 90 @@ -1998,6 +2728,8 @@ groups: min: 0 max: 4000 - name: osd_hud_wp_disp + docs_description: "Controls display of the next waypoints in the HUD." + docs_default_value: "OFF" field: hud_wp_disp min: 0 max: 3 @@ -2013,6 +2745,8 @@ groups: field: sidebar_scroll_arrows type: bool - name: osd_main_voltage_decimals + docs_description: "Number of decimals for the battery voltages displayed in the OSD [1-2]." + docs_default_value: "1" field: main_voltage_decimals min: 1 max: 2 @@ -2022,11 +2756,15 @@ groups: max: 11 - name: osd_estimations_wind_compensation + docs_description: "Use wind estimation for remaining flight time/distance estimation" + docs_default_value: "ON" condition: USE_WIND_ESTIMATOR field: estimations_wind_compensation type: bool - name: osd_failsafe_switch_layout + docs_description: "If enabled the OSD automatically switches to the first layout during failsafe" + docs_default_value: "OFF" type: bool - name: osd_plus_code_digits @@ -2035,6 +2773,8 @@ groups: max: 13 - name: osd_ahi_style + docs_description: "Sets OSD Artificial Horizon style \"DEFAULT\" or \"LINE\" for the FrSky Graphical OSD." + docs_default_value: "DEFAULT" table: osd_ahi_style - name: PG_SYSTEM_CONFIG @@ -2042,25 +2782,35 @@ groups: headers: ["fc/config.h"] members: - name: i2c_speed + docs_description: "This setting controls the clock speed of I2C bus. 400KHZ is the default that most setups are able to use. Some noise-free setups may be overclocked to 800KHZ. Some sensor chips or setups with long wires may work unreliably at 400KHZ - user can try lowering the clock speed to 200KHZ or even 100KHZ. User need to bear in mind that lower clock speeds might require higher looptimes (lower looptime rate)" + docs_default_value: "400KHZ" condition: USE_I2C table: i2c_speed - name: cpu_underclock + docs_description: "This option is only available on certain architectures (F3 CPUs at the moment). It makes CPU clock lower to reduce interference to long-range RC systems working at 433MHz" + docs_default_value: "OFF" field: cpuUnderclock condition: USE_UNDERCLOCK type: bool - name: debug_mode table: debug_modes - name: throttle_tilt_comp_str + docs_description: "Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled." + docs_default_value: "0" field: throttle_tilt_compensation_strength min: 0 max: 100 - name: name + docs_description: "Craft name" + docs_default_value: "Empty string" - name: PG_MODE_ACTIVATION_OPERATOR_CONFIG type: modeActivationOperatorConfig_t headers: ["fc/rc_modes.h"] members: - name: mode_range_logic_operator + docs_description: "Control how Mode selection works in flight modes. If you example have Angle mode configured on two different Aux channels, this controls if you need both activated ( AND ) or if you only need one activated ( OR ) to active angle mode." + docs_default_value: "OR" field: modeActivationOperator table: aux_operator type: uint8_t @@ -2071,11 +2821,17 @@ groups: condition: USE_STATS members: - name: stats + docs_description: "General switch of the statistics recording feature (a.k.a. odometer)" + docs_default_value: "OFF" field: stats_enabled type: bool - name: stats_total_time + docs_description: "Total flight time [in seconds]. The value is updated on every disarm when \"stats\" are enabled." + docs_default_value: "0" max: INT32_MAX - name: stats_total_dist + docs_description: "Total flight distance [in meters]. The value is updated on every disarm when \"stats\" are enabled." + docs_default_value: "0" max: INT32_MAX - name: stats_total_energy max: INT32_MAX @@ -2086,9 +2842,13 @@ groups: headers: ["common/time.h"] members: - name: tz_offset + docs_description: "Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs" + docs_default_value: "0" min: -1440 max: 1440 - name: tz_automatic_dst + docs_description: "Automatically add Daylight Saving Time to the GPS time when needed or simply ignore it. Includes presets for EU and the USA - if you live outside these areas it is suggested to manage DST manually via `tz_offset`." + docs_default_value: "OFF" type: uint8_t table: tz_automatic_dst @@ -2097,6 +2857,8 @@ groups: headers: ["drivers/display.h"] members: - name: display_force_sw_blink + docs_description: "OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON" + docs_default_value: "OFF" field: force_sw_blink type: bool @@ -2106,6 +2868,8 @@ groups: condition: USE_VTX_CONTROL members: - name: vtx_halfduplex + docs_description: "Use half duplex UART to communicate with the VTX, using only a TX pin in the FC." + docs_default_value: "ON" field: halfDuplex type: bool @@ -2114,18 +2878,26 @@ groups: headers: ["drivers/vtx_common.h", "io/vtx.h"] members: - name: vtx_band + docs_description: "Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race." + docs_default_value: "4" field: band min: VTX_SETTINGS_NO_BAND max: VTX_SETTINGS_MAX_BAND - name: vtx_channel + docs_description: "Channel to use within the configured `vtx_band`. Valid values are [1, 8]." + docs_default_value: "1" field: channel min: VTX_SETTINGS_MIN_CHANNEL max: VTX_SETTINGS_MAX_CHANNEL - name: vtx_power + docs_description: "VTX RF power level to use. The exact number of mw depends on the VTX hardware." + docs_default_value: "1" field: power min: VTX_SETTINGS_MIN_POWER max: VTX_SETTINGS_MAX_POWER - name: vtx_low_power_disarm + docs_description: "When the craft is disarmed, set the VTX to its lowest power. `ON` will set the power to its minimum value on startup, increase it to `vtx_power` when arming and change it back to its lowest setting after disarming. `UNTIL_FIRST_ARM` will start with minimum power, but once the craft is armed it will increase to `vtx_power` and it will never decrease until the craft is power cycled." + docs_default_value: "OFF" field: lowPowerDisarm table: vtx_low_power_disarm type: uint8_t diff --git a/src/utils/update_cli_docs.py b/src/utils/update_cli_docs.py new file mode 100755 index 00000000000..35534291f0d --- /dev/null +++ b/src/utils/update_cli_docs.py @@ -0,0 +1,131 @@ +#!/usr/bin/env python3 + +import re +from sys import argv +import yaml + +CLI_MD_PATH = "docs/Cli.md" +SETTINGS_YAML_PATH = "src/main/fc/settings.yaml" + +CLI_MD_SECTION_HEADER = "## CLI Variable Reference" + +def read_cli_md(): + with open(CLI_MD_PATH, "r") as cli_md: + return cli_md.readlines() + +def parse_params_from_md_table(cli_md_lines): + table_offset = cli_md_lines.index("## CLI Variable Reference\n") + 4 + params, i = {}, table_offset + while cli_md_lines[i] != "" and i < len(cli_md_lines) - 1: + param = [ s.strip() for s in cli_md_lines[i].strip("\n").split("|") ][1:-1] + params[param[0]] = { 'default': param[1], 'description': param[2] } + i += 1 + return params + +def read_settings_yaml(): + with open(SETTINGS_YAML_PATH, "r") as settings_yaml: + return settings_yaml.readlines() + +def update_settings_yaml_from_cli_md(cli_md_params, settings_yaml_lines): + new_lines = [] + skip = False + for line in settings_yaml_lines: + if skip: + if line == "\n": + skip = False + elif line.startswith("tables:"): + skip = True + elif "- name:" in line: + for param in cli_md_params: + match = re.match("^\\s+- name: {}\n$".format(param), line) + if match: + match = match.group(0) + prefix = match[:match.index("- name: ") + 8] + line = "{}\n{}\"{}\"\n".format( + match.strip("\n"), + prefix.replace("- name", " docs_description"), + cli_md_params[param]['description'].replace("\"", "\\\""), + ) + if cli_md_params[param]['default']: + line = "{}{}\"{}\"\n".format( + line, + prefix.replace("- name", " docs_default_value"), + cli_md_params[param]['default'].replace("\"", "\\\""), + ) + cli_md_params[param]['documented'] = True + break + new_lines.append(line) + + for param in cli_md_params: + if not "documented" in cli_md_params[param] or not cli_md_params[param]['documented']: + print("\"{}\" is undocumented".format(param)) + + return new_lines + +def write_settings_yaml(lines): + with open(SETTINGS_YAML_PATH, "w") as settings_yaml: + settings_yaml.writelines(lines) + +def parse_settings_yaml(): + with open(SETTINGS_YAML_PATH, "r") as settings_yaml: + return yaml.load(settings_yaml, Loader=yaml.Loader) + +def generate_md_table_from_yaml(settings_yaml): + params = {} + for group in settings_yaml['groups']: + for member in group['members']: + if any(key in member for key in ["docs_description", "docs_default_value"]): + params[member['name']] = { + "description": member["docs_description"], + "default": member["docs_default_value"] if "docs_default_value" in member else "" + } + + md_table_lines = [ + "| Variable Name | Default Value | Description |\n", + "| ------------- | ------------- | ----------- |\n", + ] + for param in sorted(params.items()): + md_table_lines.append("| {} | {} | {} |\n".format(param[0], param[1]['default'], param[1]['description'])) + + return md_table_lines + +def replace_md_table_in_cli_md(cli_md_lines, md_table_lines): + new_lines = [] + lines_to_skip = 0 + skip_until_empty_line = False + for line in cli_md_lines: + if lines_to_skip > 0: + lines_to_skip -= 1 + if lines_to_skip == 0: + skip_until_empty_line = True + continue + elif skip_until_empty_line: + if line != "\n": + continue + else: + skip_until_empty_line = False + new_lines.append("\n") + new_lines += md_table_lines + if line.startswith(CLI_MD_SECTION_HEADER): + lines_to_skip = 2 + new_lines.append(line) + return new_lines + +def write_cli_md(lines): + with open(CLI_MD_PATH, "w") as cli_md: + cli_md.writelines(lines) + +if __name__ == "__main__": + if len(argv) == 2 and argv[1] == "--reverse": + cli_md_lines = read_cli_md() + cli_md_params = parse_params_from_md_table(cli_md_lines) + settings_yaml_lines = read_settings_yaml() + settings_yaml_lines = update_settings_yaml_from_cli_md(cli_md_params, settings_yaml_lines) + write_settings_yaml(settings_yaml_lines) + else: + settings_yaml = parse_settings_yaml() + md_table_lines = generate_md_table_from_yaml(settings_yaml) + cli_md_lines = read_cli_md() + cli_md_lines = replace_md_table_in_cli_md(cli_md_lines, md_table_lines) + write_cli_md(cli_md_lines) + From 551b045b64b4bca5bdb300b8d64035e6e981a8e5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Niccol=C3=B2=20Maggioni?= Date: Mon, 15 Jun 2020 16:55:58 +0200 Subject: [PATCH 027/248] Remove code for markdown->yaml transition --- src/utils/update_cli_docs.py | 97 ++++++++++-------------------------- 1 file changed, 25 insertions(+), 72 deletions(-) diff --git a/src/utils/update_cli_docs.py b/src/utils/update_cli_docs.py index 35534291f0d..4fe2bacd352 100755 --- a/src/utils/update_cli_docs.py +++ b/src/utils/update_cli_docs.py @@ -1,95 +1,54 @@ #!/usr/bin/env python3 -import re -from sys import argv -import yaml +import yaml # pyyaml / python-yaml CLI_MD_PATH = "docs/Cli.md" SETTINGS_YAML_PATH = "src/main/fc/settings.yaml" CLI_MD_SECTION_HEADER = "## CLI Variable Reference" +# Read the contents of the markdown CLI docs def read_cli_md(): with open(CLI_MD_PATH, "r") as cli_md: return cli_md.readlines() -def parse_params_from_md_table(cli_md_lines): - table_offset = cli_md_lines.index("## CLI Variable Reference\n") + 4 - params, i = {}, table_offset - while cli_md_lines[i] != "" and i < len(cli_md_lines) - 1: - param = [ s.strip() for s in cli_md_lines[i].strip("\n").split("|") ][1:-1] - params[param[0]] = { 'default': param[1], 'description': param[2] } - i += 1 - return params - -def read_settings_yaml(): - with open(SETTINGS_YAML_PATH, "r") as settings_yaml: - return settings_yaml.readlines() - -def update_settings_yaml_from_cli_md(cli_md_params, settings_yaml_lines): - new_lines = [] - skip = False - for line in settings_yaml_lines: - if skip: - if line == "\n": - skip = False - elif line.startswith("tables:"): - skip = True - elif "- name:" in line: - for param in cli_md_params: - match = re.match("^\\s+- name: {}\n$".format(param), line) - if match: - match = match.group(0) - prefix = match[:match.index("- name: ") + 8] - line = "{}\n{}\"{}\"\n".format( - match.strip("\n"), - prefix.replace("- name", " docs_description"), - cli_md_params[param]['description'].replace("\"", "\\\""), - ) - if cli_md_params[param]['default']: - line = "{}{}\"{}\"\n".format( - line, - prefix.replace("- name", " docs_default_value"), - cli_md_params[param]['default'].replace("\"", "\\\""), - ) - cli_md_params[param]['documented'] = True - break - new_lines.append(line) - - for param in cli_md_params: - if not "documented" in cli_md_params[param] or not cli_md_params[param]['documented']: - print("\"{}\" is undocumented".format(param)) - - return new_lines - -def write_settings_yaml(lines): - with open(SETTINGS_YAML_PATH, "w") as settings_yaml: - settings_yaml.writelines(lines) - +# Parse the YAML settings specs def parse_settings_yaml(): with open(SETTINGS_YAML_PATH, "r") as settings_yaml: return yaml.load(settings_yaml, Loader=yaml.Loader) def generate_md_table_from_yaml(settings_yaml): + """Generate a sorted markdown table with description & default value for each setting""" params = {} + + # Extract description and default value of each setting from the YAML specs (if present) for group in settings_yaml['groups']: for member in group['members']: if any(key in member for key in ["docs_description", "docs_default_value"]): params[member['name']] = { - "description": member["docs_description"], + "description": member["docs_description"] if "docs_description" in member else "", "default": member["docs_default_value"] if "docs_default_value" in member else "" } - + + # MD table header md_table_lines = [ "| Variable Name | Default Value | Description |\n", "| ------------- | ------------- | ----------- |\n", ] + + # Sort the settings by name and build the rows of the table for param in sorted(params.items()): md_table_lines.append("| {} | {} | {} |\n".format(param[0], param[1]['default'], param[1]['description'])) - + + # Return the assembled table return md_table_lines def replace_md_table_in_cli_md(cli_md_lines, md_table_lines): + """Update the settings table in the CLI docs + + Copy all the original lines up to $CLI_MD_SECTION_HEADER (including the following newline), then insert + the updated table in place of the next block of text (replace everything until an empty line is found). + """ new_lines = [] lines_to_skip = 0 skip_until_empty_line = False @@ -109,23 +68,17 @@ def replace_md_table_in_cli_md(cli_md_lines, md_table_lines): if line.startswith(CLI_MD_SECTION_HEADER): lines_to_skip = 2 new_lines.append(line) + return new_lines +# Write the contents of the markdown CLI docs def write_cli_md(lines): with open(CLI_MD_PATH, "w") as cli_md: cli_md.writelines(lines) if __name__ == "__main__": - if len(argv) == 2 and argv[1] == "--reverse": - cli_md_lines = read_cli_md() - cli_md_params = parse_params_from_md_table(cli_md_lines) - settings_yaml_lines = read_settings_yaml() - settings_yaml_lines = update_settings_yaml_from_cli_md(cli_md_params, settings_yaml_lines) - write_settings_yaml(settings_yaml_lines) - else: - settings_yaml = parse_settings_yaml() - md_table_lines = generate_md_table_from_yaml(settings_yaml) - cli_md_lines = read_cli_md() - cli_md_lines = replace_md_table_in_cli_md(cli_md_lines, md_table_lines) - write_cli_md(cli_md_lines) - + settings_yaml = parse_settings_yaml() + md_table_lines = generate_md_table_from_yaml(settings_yaml) + cli_md_lines = read_cli_md() + cli_md_lines = replace_md_table_in_cli_md(cli_md_lines, md_table_lines) + write_cli_md(cli_md_lines) From 46fc7f8e475696aef1ea15a6aa96dc814b3c19b3 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Niccol=C3=B2=20Maggioni?= Date: Sun, 21 Jun 2020 14:47:09 +0200 Subject: [PATCH 028/248] Move docs to Settings.md and drop "docs_" YAML prefix --- docs/Cli.md | 450 +--------- docs/Settings.md | 393 +++++++++ src/main/fc/settings.yaml | 1544 +++++++++++++++++----------------- src/utils/update_cli_docs.py | 61 +- 4 files changed, 1181 insertions(+), 1267 deletions(-) create mode 100644 docs/Settings.md diff --git a/docs/Cli.md b/docs/Cli.md index 391182da546..a538fb2ccdc 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -125,452 +125,4 @@ A shorter form is also supported to enable and disable functions using `serial < ## CLI Variable Reference -| Variable Name | Default Value | Description | -| ------------- | ------------- | ----------- | -| 3d_deadband_high | 1514 | High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead) | -| 3d_deadband_low | 1406 | Low value of throttle deadband for 3D mode (when stick is in the 3d_deadband_throttle range, the fixed values of 3d_deadband_low / _high are used instead) | -| 3d_deadband_throttle | 50 | Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter. | -| 3d_neutral | 1460 | Neutral (stop) throttle value for 3D mode | -| acc_event_threshold_high | 0 | Acceleration threshold [cm/s/s] for impact / high g event text messages sent by SIM module. Acceleration values greater than 4 g can occur in fixed wing flight without an impact, so a setting of 4000 or greater is suggested. 0 = detection off. | -| acc_event_threshold_low | 0 | Acceleration threshold [cm/s/s] for low-g / freefall detection text messages sent by SIM module. A setting of less than 100 is suggested. Valid values: [0-900], 0 = detection off. | -| acc_event_threshold_neg_x | 0 | Acceleration threshold [cm/s/s] for backwards acceleration / fixed wing landing detection text messages sent by SIM module. Suggested value for fixed wing: 1100. 0 = detection off. | -| acc_hardware | AUTO | Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info | -| acc_lpf_hz | 15 | Software-based filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. | -| acc_lpf_type | BIQUAD | Specifies the type of the software LPF of the acc signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. | -| accgain_x | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | -| accgain_y | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | -| accgain_z | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | -| acczero_x | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | -| acczero_y | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | -| acczero_z | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | -| airspeed_adc_channel | 0 | ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0 | -| align_acc | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. | -| align_board_pitch | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | -| align_board_roll | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | -| align_board_yaw | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | -| align_gyro | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. | -| align_mag | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. | -| align_mag_pitch | 0 | Same as align_mag_roll, but for the pitch axis. | -| align_mag_roll | 0 | Set the external mag alignment on the roll axis (in 0.1 degree steps). If this value is non-zero, the compass is assumed to be externally mounted and both the board and on-board compass alignent (align_mag) are ignored. See also align_mag_pitch and align_mag_yaw. | -| align_mag_yaw | 0 | Same as align_mag_roll, but for the yaw axis. | -| align_opflow | 5 | Optical flow module alignment (default CW0_DEG_FLIP) | -| alt_hold_deadband | 50 | Defines the deadband of throttle during alt_hold [r/c points] | -| antigravity_accelerator | 1 | | -| antigravity_cutoff_lpf_hz | 15 | Antigravity cutoff frequenct for Throtte filter. Antigravity is based on the difference between actual and filtered throttle input. The bigger is the difference, the bigger Antigravity gain | -| antigravity_gain | 1 | Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements | -| baro_cal_tolerance | 150 | Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]. | -| baro_hardware | AUTO | Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info | -| baro_median_filter | ON | 3-point median filtering for barometer readouts. No reason to change this setting | -| bat_cells | 0 | Number of cells of the battery (0 = autodetect), see battery documentation | -| bat_voltage_src | RAW | Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP` | -| battery_capacity | 0 | Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity. | -| battery_capacity_critical | 0 | If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps. | -| battery_capacity_unit | MAH | Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour). | -| battery_capacity_warning | 0 | If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink. | -| blackbox_device | SPIFLASH | Selection of where to write blackbox data | -| blackbox_rate_denom | 1 | Blackbox logging rate denominator. See blackbox_rate_num. | -| blackbox_rate_num | 1 | Blackbox logging rate numerator. Use num/denom settings to decide if a frame should be logged, allowing control of the portion of logged loop iterations | -| cpu_underclock | OFF | This option is only available on certain architectures (F3 CPUs at the moment). It makes CPU clock lower to reduce interference to long-range RC systems working at 433MHz | -| cruise_power | 0 | Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit | -| current_adc_channel | - | ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled | -| current_meter_offset | 0 | This sets the output offset voltage of the current sensor in millivolts. | -| current_meter_scale | 400 | This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt. | -| current_meter_type | ADC | ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position. | -| deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. | -| disarm_kill_switch | ON | Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel. | -| display_force_sw_blink | OFF | OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON | -| dterm_lpf2_hz | 0 | Cutoff frequency for stage 2 D-term low pass filter | -| dterm_lpf2_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | -| dterm_lpf_hz | 40 | Dterm low pass filter cutoff frequency. Default setting is very conservative and small multirotors should use higher value between 80 and 100Hz. 80 seems like a gold spot for 7-inch builds while 100 should work best with 5-inch machines. If motors are getting too hot, lower the value | -| dterm_lpf_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | -| dynamic_gyro_notch_enabled | `OFF` | Enable/disable dynamic gyro notch also known as Matrix Filter | -| dynamic_gyro_notch_min_hz | 150 | Minimum frequency for dynamic notches. Default value of `150` works best with 5" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7" drones. 10" can go down to `60` - `70` | -| dynamic_gyro_notch_q | 120 | Q factor for dynamic notches | -| dynamic_gyro_notch_range | `MEDIUM` | Range for dynamic gyro notches. `MEDIUM` for 5", `HIGH` for 3" and `MEDIUM`/`LOW` for 7" and bigger propellers | -| failsafe_delay | 5 | Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). | -| failsafe_fw_pitch_angle | 100 | Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb | -| failsafe_fw_roll_angle | -200 | Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll | -| failsafe_fw_yaw_rate | -45 | Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn | -| failsafe_lights | ON | Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]. | -| failsafe_lights_flash_on_time | 100 | Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]. | -| failsafe_lights_flash_period | 1000 | Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]. | -| failsafe_min_distance | 0 | If failsafe happens when craft is closer than this distance in centimeters from home, failsafe will not execute regular failsafe_procedure, but will execute procedure specified in failsafe_min_distance_procedure instead. 0 = Normal failsafe_procedure always taken. | -| failsafe_min_distance_procedure | DROP | What failsafe procedure to initiate in Stage 2 when craft is closer to home than failsafe_min_distance. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | -| failsafe_mission | ON | If set to `OFF` the failsafe procedure won't be triggered and the mission will continue if the FC is in WP (automatic mission) mode | -| failsafe_off_delay | 200 | Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay). | -| failsafe_procedure | SET-THR | What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | -| failsafe_recovery_delay | 5 | Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay). | -| failsafe_stick_threshold | 50 | Threshold for stick motion to consider failsafe condition resolved. If non-zero failsafe won't clear even if RC link is restored - you have to move sticks to exit failsafe. | -| failsafe_throttle | 1000 | Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | -| failsafe_throttle_low_delay | 100 | If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout | -| fixed_wing_auto_arm | OFF | Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured. | -| flaperon_throw_offset | 200 | Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated. | -| frsky_coordinates_format | 0 | D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA | -| frsky_default_latitude | 0.000 | D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. | -| frsky_default_longitude | 0.000 | D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. | -| frsky_pitch_roll | OFF | S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data | -| frsky_unit | METRIC | Not used? [METRIC/IMPERIAL] | -| frsky_vfas_precision | 0 | D-Series telemetry only: Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method | -| fw_autotune_ff_to_i_tc | 600 | FF to I time (defines time for I to reach the same level of response as FF) [ms] | -| fw_autotune_ff_to_p_gain | 10 | FF to P gain (strength relationship) [%] | -| fw_autotune_overshoot_time | 100 | Time [ms] to detect sustained overshoot | -| fw_autotune_threshold | 50 | Threshold [%] of max rate to consider overshoot/undershoot detection | -| fw_autotune_undershoot_time | 200 | Time [ms] to detect sustained undershoot | -| fw_d_level | 75 | Fixed-wing attitude stabilisation HORIZON transition point | -| fw_ff_pitch | 50 | Fixed-wing rate stabilisation FF-gain for PITCH | -| fw_ff_roll | 50 | Fixed-wing rate stabilisation FF-gain for ROLL | -| fw_ff_yaw | 60 | Fixed-wing rate stabilisation FF-gain for YAW | -| fw_i_level | 5 | Fixed-wing attitude stabilisation low-pass filter cutoff | -| fw_i_pitch | 7 | Fixed-wing rate stabilisation I-gain for PITCH | -| fw_i_roll | 7 | Fixed-wing rate stabilisation I-gain for ROLL | -| fw_i_yaw | 10 | Fixed-wing rate stabilisation I-gain for YAW | -| fw_iterm_limit_stick_position | 0.5 | Iterm is not allowed to grow when stick position is above threshold. This solves the problem of bounceback or followthrough when full stick deflection is applied on poorely tuned fixed wings. In other words, stabilization is partialy disabled when pilot is actively controlling the aircraft and active when sticks are not touched. `0` mean stick is in center position, `1` means it is fully deflected to either side | -| fw_iterm_throw_limit | 165 | Limits max/min I-term value in stabilization PID controller in case of Fixed Wing. It solves the problem of servo saturation before take-off/throwing the airplane into the air. By default, error accumulated in I-term can not exceed 1/3 of servo throw (around 165us). Set 0 to disable completely. | -| fw_loiter_direction | RIGHT | Direction of loitering: center point on right wing (clockwise - default), or center point on left wing (counterclockwise). If equal YAW then can be changed in flight using a yaw stick. | -| fw_min_throttle_down_pitch | 0 | Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees) | -| fw_p_level | 20 | Fixed-wing attitude stabilisation P-gain | -| fw_p_pitch | 5 | Fixed-wing rate stabilisation P-gain for PITCH | -| fw_p_roll | 5 | Fixed-wing rate stabilisation P-gain for ROLL | -| fw_p_yaw | 6 | Fixed-wing rate stabilisation P-gain for YAW | -| fw_reference_airspeed | 1000 | Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present. | -| fw_tpa_time_constant | 0 | TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. Planes with low thrust/weight ratio generally need higher time constant. Default is zero for compatibility with old setups | -| fw_turn_assist_yaw_gain | 1 | Gain required to keep the yaw rate consistent with the turn rate for a coordinated turn (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter | -| gps_auto_baud | ON | Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS. When used with NAZA/DJI it will automatic detect GPS baudrate and change to it, ignoring the selected baudrate set in ports | -| gps_auto_config | ON | Enable automatic configuration of UBlox GPS receivers. | -| gps_dyn_model | AIR_1G | GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying. | -| gps_min_sats | 6 | Minimum number of GPS satellites in view to acquire GPS_FIX and consider GPS position valid. Some GPS receivers appeared to be very inaccurate with low satellite count. | -| gps_provider | UBLOX | Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N). | -| gps_sbas_mode | NONE | Which SBAS mode to be used | -| gps_ublox_use_galileo | OFF | Enable use of Galileo satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires M8N and Ublox firmware 3.x (or later) [OFF/ON]. | -| gyro_hardware_lpf | 42HZ | Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first. | -| gyro_lpf_hz | 60 | Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. | -| gyro_lpf_type | BIQUAD | Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. | -| gyro_stage2_lowpass_hz | 0 | Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz) | -| gyro_stage2_lowpass_type | `BIQUAD` | Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | -| gyro_sync | OFF | This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf | -| has_flaps | OFF | Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot | -| heading_hold_rate_limit | 90 | This setting limits yaw rotation rate that HEADING_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when HEADING_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes. | -| hott_alarm_sound_interval | 5 | Battery alarm delay in seconds for Hott telemetry | -| i2c_speed | 400KHZ | This setting controls the clock speed of I2C bus. 400KHZ is the default that most setups are able to use. Some noise-free setups may be overclocked to 800KHZ. Some sensor chips or setups with long wires may work unreliably at 400KHZ - user can try lowering the clock speed to 200KHZ or even 100KHZ. User need to bear in mind that lower clock speeds might require higher looptimes (lower looptime rate) | -| ibus_telemetry_type | 0 | Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details. | -| idle_power | 0 | Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit | -| imu_acc_ignore_rate | 0 | Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes | -| imu_acc_ignore_slope | 0 | Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight) | -| imu_dcm_ki | 50 | Inertial Measurement Unit KI Gain for accelerometer measurements | -| imu_dcm_ki_mag | 0 | Inertial Measurement Unit KI Gain for compass measurements | -| imu_dcm_kp | 2500 | Inertial Measurement Unit KP Gain for accelerometer measurements | -| imu_dcm_kp_mag | 10000 | Inertial Measurement Unit KP Gain for compass measurements | -| inav_auto_mag_decl | ON | Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored. | -| inav_baro_epv | 100.000 | Uncertainty value for barometric sensor [cm] | -| inav_gravity_cal_tolerance | 5 | Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value. | -| inav_max_eph_epv | 1000.000 | Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm] | -| inav_max_surface_altitude | 200 | Max allowed altitude for surface following mode. [cm] | -| inav_reset_altitude | FIRST_ARM | Defines when relative estimated altitude is reset to zero. Variants - `NEVER` (once reference is acquired it's used regardless); `FIRST_ARM` (keep altitude at zero until firstly armed), `EACH_ARM` (altitude is reset to zero on each arming) | -| inav_reset_home | FIRST_ARM | Allows to chose when the home position is reset. Can help prevent resetting home position after accidental mid-air disarm. Possible values are: NEVER, FIRST_ARM and EACH_ARM | -| inav_use_gps_velned | ON | Defined if iNav should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF iNav will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance. | -| inav_w_acc_bias | 0.010 | Weight for accelerometer drift estimation | -| inav_w_xy_gps_p | 1.000 | Weight of GPS coordinates in estimated UAV position and speed. | -| inav_w_xy_gps_v | 2.000 | Weight of GPS velocity data in estimated UAV speed | -| inav_w_xy_res_v | 0.500 | Decay coefficient for estimated velocity when GPS reference for position is lost | -| inav_w_z_baro_p | 0.350 | Weight of barometer measurements in estimated altitude and climb rate | -| inav_w_z_gps_p | 0.200 | Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes | -| inav_w_z_gps_v | 0.500 | Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero | -| inav_w_z_res_v | 0.500 | Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost | -| iterm_windup | 50 | Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter) | -| ledstrip_visual_beeper | OFF | | -| looptime | 1000 | This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible. | -| ltm_update_rate | NORMAL | Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details. | -| mag_calibration_time | 30 | Adjust how long time the Calibration of mag will last. | -| mc_p_pitch | 40 | Multicopter rate stabilisation P-gain for PITCH | -| mc_i_pitch | 30 | Multicopter rate stabilisation I-gain for PITCH | -| mc_d_pitch | 23 | Multicopter rate stabilisation D-gain for PITCH | -| mc_cd_pitch | 60 | Multicopter Control Derivative gain for PITCH | -| mc_p_roll | 40 | Multicopter rate stabilisation P-gain for ROLL | -| mc_i_roll | 30 | Multicopter rate stabilisation I-gain for ROLL | -| mc_d_roll | 23 | Multicopter rate stabilisation D-gain for ROLL | -| mc_cd_roll | 60 | Multicopter Control Derivative gain for ROLL | -| mc_p_yaw | 85 | Multicopter rate stabilisation P-gain for YAW | -| mc_i_yaw | 45 | Multicopter rate stabilisation I-gain for YAW | -| mc_d_yaw | 0 | Multicopter rate stabilisation D-gain for YAW | -| mc_cd_yaw | 60 | Multicopter Control Derivative gain for YAW | -| mc_p_level | 20 | Multicopter attitude stabilisation P-gain | -| mc_i_level | 15 | Multicopter attitude stabilisation low-pass filter cutoff | -| mc_d_level | 75 | Multicopter attitude stabilisation HORIZON transition point | -| fw_p_pitch | 5 | Fixed-wing rate stabilisation P-gain for PITCH | -| fw_i_pitch | 7 | Fixed-wing rate stabilisation I-gain for PITCH | -| fw_ff_pitch| 50 | Fixed-wing rate stabilisation FF-gain for PITCH | -| fw_p_roll | 5 | Fixed-wing rate stabilisation P-gain for ROLL | -| fw_i_roll | 7 | Fixed-wing rate stabilisation I-gain for ROLL | -| fw_ff_roll | 50 | Fixed-wing rate stabilisation FF-gain for ROLL | -| fw_p_yaw | 6 | Fixed-wing rate stabilisation P-gain for YAW | -| fw_i_yaw | 10 | Fixed-wing rate stabilisation I-gain for YAW | -| fw_ff_yaw | 60 | Fixed-wing rate stabilisation FF-gain for YAW | -| fw_p_level | 20 | Fixed-wing attitude stabilisation P-gain | -| fw_i_level | 5 | Fixed-wing attitude stabilisation low-pass filter cutoff | -| fw_d_level | 75 | Fixed-wing attitude stabilisation HORIZON transition point | -| max_angle_inclination_rll | 300 | Maximum inclination in level (angle) mode (ROLL axis). 100=10° | -| max_angle_inclination_pit | 300 | Maximum inclination in level (angle) mode (PITCH axis). 100=10° | -| fw_iterm_limit_stick_position | 0.5 | Iterm is not allowed to grow when stick position is above threshold. This solves the problem of bounceback or followthrough when full stick deflection is applied on poorely tuned fixed wings. In other words, stabilization is partialy disabled when pilot is actively controlling the aircraft and active when sticks are not touched. `0` mean stick is in center position, `1` means it is fully deflected to either side | -| fw_min_throttle_down_pitch | 0 | Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees) | -| gyro_lpf_hz | 60 | Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. | -| gyro_lpf_type | BIQUAD | Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. | -| acc_lpf_hz | 15 | Software-based filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. | -| acc_lpf_type | BIQUAD | Specifies the type of the software LPF of the acc signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. | -| dterm_lpf_hz | 40 | Dterm low pass filter cutoff frequency. Default setting is very conservative and small multirotors should use higher value between 80 and 100Hz. 80 seems like a gold spot for 7-inch builds while 100 should work best with 5-inch machines. If motors are getting too hot, lower the value | -| dterm_lpf_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | -| dterm_lpf2_hz | 0 | Cutoff frequency for stage 2 D-term low pass filter | -| dterm_lpf2_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | -| yaw_lpf_hz | 30 | Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below) | -| dynamic_gyro_notch_enabled | `OFF` | Enable/disable dynamic gyro notch also known as Matrix Filter | -| dynamic_gyro_notch_range | `MEDIUM` | Range for dynamic gyro notches. `MEDIUM` for 5", `HIGH` for 3" and `MEDIUM`/`LOW` for 7" and bigger propellers | -| dynamic_gyro_notch_q | 120 | Q factor for dynamic notches | -| dynamic_gyro_notch_min_hz | 150 | Minimum frequency for dynamic notches. Default value of `150` works best with 5" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7" drones. 10" can go down to `60` - `70` | -| gyro_stage2_lowpass_hz | 0 | Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz) | -| gyro_stage2_lowpass_type | `BIQUAD` | Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | -| rpm_gyro_filter_enabled | `OFF` | Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV | -| rpm_gyro_harmonics | 1 | Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine | -| rpm_gyro_min_hz | 150 | The lowest frequency for gyro RPM filtere. Default `150` is fine for 5" mini-quads. On 7-inch drones you can lower even down to `60`-`70` | -| rpm_gyro_q | 500 | Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting | -| pidsum_limit | 500 | A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | -| pidsum_limit_yaw | 400 | A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | -| `pid_type` | Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID` | -| iterm_windup | 50 | Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter) | -| rate_accel_limit_roll_pitch | 0 | Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting. | -| rate_accel_limit_yaw | 10000 | Limits acceleration of YAW rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 180 dps^2). When set correctly, it greatly improves stopping performance and general stability during yaw turns. Value of 0 disables limiting. | -| rc_expo | 70 | Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`) | -| rc_yaw_expo | 20 | Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`) | -| manual_rc_expo | 70 | Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100] | -| manual rc_yaw_expo | 20 | Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100] | -| thr_mid | 50 | Throttle value when the stick is set to mid-position. Used in the throttle curve calculation. | -| thr_expo | 0 | Throttle exposition value | -| roll_rate | 20 | Defines rotation rate on ROLL axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. | -| pitch_rate | 20 | Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. | -| yaw_rate | 20 | Defines rotation rate on YAW axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. | -| manual_pitch_rate | 100 | Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]% | -| manual_roll_rate | 100 | Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]% | -| manual_yaw_rate | 100 | Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]% | -| tpa_rate | 0 | Throttle PID attenuation reduces influence of P on ROLL and PITCH as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate. | -| tpa_breakpoint | 1500 | See tpa_rate. | -| fw_tpa_time_constant | 0 | TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. Planes with low thrust/weight ratio generally need higher time constant. Default is zero for compatibility with old setups | -| fw_autotune_overshoot_time | 100 | Time [ms] to detect sustained overshoot | -| fw_autotune_undershoot_time | 200 | Time [ms] to detect sustained undershoot | -| fw_autotune_threshold | 50 | Threshold [%] of max rate to consider overshoot/undershoot detection | -| fw_autotune_ff_to_p_gain | 10 | FF to P gain (strength relationship) [%] | -| fw_autotune_ff_to_i_tc | 600 | FF to I time (defines time for I to reach the same level of response as FF) [ms] | -| stats | OFF | General switch of the statistics recording feature (a.k.a. odometer) | -| stats_total_time | 0 | Total flight time [in seconds]. The value is updated on every disarm when "stats" are enabled. | -| stats_total_dist | 0 | Total flight distance [in meters]. The value is updated on every disarm when "stats" are enabled. | -| vbat_adc_channel | - | ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled | -| rssi_adc_channel | - | ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled | -| current_adc_channel | - | ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled | -| airspeed_adc_channel | 0 | ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0 | -| platform_type | "MULTIROTOR" | Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented | -| has_flaps | OFF | Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot | -| model_preview_type | -1 | ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons. | -| tz_offset | 0 | Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs | -| tz_automatic_dst | OFF | Automatically add Daylight Saving Time to the GPS time when needed or simply ignore it. Includes presets for EU and the USA - if you live outside these areas it is suggested to manage DST manually via `tz_offset`. | -| vtx_band | 4 | Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race. | -| vtx_channel | 1 | Channel to use within the configured `vtx_band`. Valid values are [1, 8]. | -| vtx_freq | 5740 | Set the VTX frequency using raw MHz. This parameter is ignored unless `vtx_band` is 0. | -| vtx_halfduplex | ON | Use half duplex UART to communicate with the VTX, using only a TX pin in the FC. | -| vtx_low_power_disarm | OFF | When the craft is disarmed, set the VTX to its lowest power. `ON` will set the power to its minimum value on startup, increase it to `vtx_power` when arming and change it back to its lowest setting after disarming. `UNTIL_FIRST_ARM` will start with minimum power, but once the craft is armed it will increase to `vtx_power` and it will never decrease until the craft is power cycled. | -| vtx_pit_mode_freq | Frequency to use (in MHz) when the VTX is in pit mode. | -| vtx_power | 1 | VTX RF power level to use. The exact number of mw depends on the VTX hardware. | -| vtx_max_power_override | 0 | Some VTXes may report max power incorrectly (i.e. 200mW for a 600mW VTX). Use this to override max supported power. 0 to disable and use whatever VTX reports as it's capabilities | -| motor_accel_time | 0 | Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000] | -| motor_decel_time | 0 | Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000] | -| motor_direction_inverted | OFF | Use if you need to inverse yaw motor direction. | -| motor_pwm_protocol | STANDARD | Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED | -| motor_pwm_rate | 400 | Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000. | -| name | Empty string | Craft name | -| nav_auto_climb_rate | 500 | Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s] | -| nav_auto_speed | 300 | Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only] | -| nav_disarm_on_landing | OFF | If set to ON, iNav disarms the FC after landing | -| nav_emerg_landing_speed | 500 | Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s] | -| nav_extra_arming_safety | ON | If set to ON drone won't arm if no GPS fix and any navigation mode like RTH or POSHOLD is configured. ALLOW_BYPASS allows the user to momentarily disable this check by holding yaw high (left stick held at the bottom right in mode 2) when switch arming is used | -| nav_fw_allow_manual_thr_increase | OFF | Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing | -| nav_fw_bank_angle | 20 | Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll | -| nav_fw_climb_angle | 20 | Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit | -| nav_fw_control_smoothness | 0 | How smoothly the autopilot controls the airplane to correct the navigation error | -| nav_fw_cruise_speed | 0 | Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s | -| nav_fw_cruise_thr | 1400 | Cruise throttle in GPS assisted modes, this includes RTH. Should be set high enough to avoid stalling. This values gives INAV a base for throttle when flying straight, and it will increase or decrease throttle based on pitch of airplane and the parameters below. In addition it will increase throttle if GPS speed gets below 7m/s ( hardcoded ) | -| nav_fw_cruise_yaw_rate | 20 | Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps] | -| nav_fw_dive_angle | 15 | Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit | -| nav_fw_heading_p | 60 | P gain of Heading Hold controller (Fixedwing) | -| nav_fw_land_dive_angle | 2 | Dive angle that airplane will use during final landing phase. During dive phase, motor is stopped or IDLE and roll control is locked to 0 degrees | -| nav_fw_launch_accel | 1863 | Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s | -| nav_fw_launch_climb_angle | 18 | Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit | -| nav_fw_launch_detect_time | 40 | Time for which thresholds have to breached to consider launch happened [ms] | -| nav_fw_launch_idle_thr | 1000 | Launch idle throttle - throttle to be set before launch sequence is initiated. If set below minimum throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above minimum throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position) | -| nav_fw_launch_max_altitude | 0 | Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]. | -| nav_fw_launch_max_angle | 45 | Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg] | -| nav_fw_launch_min_time | 0 | Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]. | -| nav_fw_launch_motor_delay | 500 | Delay between detected launch and launch sequence start and throttling up (ms) | -| nav_fw_launch_spinup_time | 100 | Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller | -| nav_fw_launch_thr | 1700 | Launch throttle - throttle to be set during launch sequence (pwm units) | -| nav_fw_launch_timeout | 5000 | Maximum time for launch sequence to be executed. After this time LAUNCH mode will be turned off and regular flight mode will take over (ms) | -| nav_fw_launch_velocity | 300 | Forward velocity threshold for swing-launch detection [cm/s] | -| nav_fw_loiter_radius | 5000 | PosHold radius. 3000 to 7500 is a good value (30-75m) [cm] | -| nav_fw_max_thr | 1700 | Maximum throttle for flying wing in GPS assisted modes | -| nav_fw_min_thr | 1200 | Minimum throttle for flying wing in GPS assisted modes | -| nav_fw_pitch2thr | 10 | Amount of throttle applied related to pitch attitude in GPS assisted modes. Throttle = nav_fw_cruise_throttle - (nav_fw_pitch2thr * pitch_angle). (notice that pitch_angle is in degrees and is negative when climbing and positive when diving, and throttle value is constrained between nav_fw_min_thr and nav_fw_max_thr) | -| nav_fw_pos_hdg_d | 0 | D gain of heading trajectory PID controller. (Fixedwing, rovers, boats) | -| nav_fw_pos_hdg_i | 0 | I gain of heading trajectory PID controller. (Fixedwing, rovers, boats) | -| nav_fw_pos_hdg_p | 60 | P gain of heading PID controller. (Fixedwing, rovers, boats) | -| nav_fw_pos_hdg_pidsum_limit | 350 | Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats) | -| nav_fw_pos_xy_d | 8 | D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero | -| nav_fw_pos_xy_i | 5 | I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero | -| nav_fw_pos_xy_p | 75 | P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH | -| nav_fw_pos_z_d | 0 | D gain of altitude PID controller (Fixedwing) | -| nav_fw_pos_z_i | 0 | I gain of altitude PID controller (Fixedwing) | -| nav_fw_pos_z_p | 50 | P gain of altitude PID controller (Fixedwing) | -| nav_fw_yaw_deadband | 0 | Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course | -| nav_land_slowdown_maxalt | 2000 | Defines at what altitude the descent velocity should start to ramp down from 100% nav_landing_speed to 25% nav_landing_speed. [cm] | -| nav_land_slowdown_minalt | 500 | Defines at what altitude the descent velocity should start to be 25% of nav_landing_speed [cm] | -| nav_landing_speed | 200 | Vertical descent velocity during the RTH landing phase. [cm/s] | -| nav_manual_climb_rate | 200 | Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] | -| nav_manual_speed | 500 | Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only] | -| nav_mc_auto_disarm_delay | 2000 | | -| nav_mc_bank_angle | 30 | Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude | -| nav_mc_braking_bank_angle | 40 | max angle that MR is allowed to bank in BOOST mode | -| nav_mc_braking_boost_disengage_speed | 100 | BOOST will be disabled when speed goes below this value | -| nav_mc_braking_boost_factor | 100 | acceleration factor for BOOST phase | -| nav_mc_braking_boost_speed_threshold | 150 | BOOST can be enabled when speed is above this value | -| nav_mc_braking_boost_timeout | 750 | how long in ms BOOST phase can happen | -| nav_mc_braking_disengage_speed | 75 | braking is disabled when speed goes below this value | -| nav_mc_braking_speed_threshold | 100 | min speed in cm/s above which braking can happen | -| nav_mc_braking_timeout | 2000 | timeout in ms for braking | -| nav_mc_heading_p | 60 | P gain of Heading Hold controller (Multirotor) | -| nav_mc_hover_thr | 1500 | Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering. | -| nav_mc_pos_deceleration_time | 120 | Used for stoping distance calculation. Stop position is computed as _speed_ * _nav_mc_pos_deceleration_time_ from the place where sticks are released. Braking mode overrides this setting | -| nav_mc_pos_expo | 10 | Expo for PosHold control | -| nav_mc_pos_xy_p | 65 | Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity | -| nav_mc_pos_z_p | 50 | P gain of altitude PID controller (Multirotor) | -| nav_mc_vel_xy_d | 100 | D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target. | -| nav_mc_vel_xy_i | 15 | I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot | -| nav_mc_vel_xy_p | 40 | P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause "nervous" behavior and oscillations | -| nav_mc_vel_z_d | 10 | D gain of velocity PID controller | -| nav_mc_vel_z_i | 50 | I gain of velocity PID controller | -| nav_mc_vel_z_p | 100 | P gain of velocity PID controller | -| nav_min_rth_distance | 500 | Minimum distance from homepoint when RTH full procedure will be activated [cm]. Below this distance, the mode will activate at the current location and the final phase is executed (loiter / land). Above this distance, the full procedure is activated, which may include initial climb and flying directly to the homepoint before entering the loiter / land phase. | -| nav_overrides_motor_stop | ON | Setting to OFF combined with MOTOR_STOP feature will allow user to stop motor when in autonomous modes. On most places this setting is likely to cause a stall. | -| nav_position_timeout | 5 | If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable) | -| nav_rth_abort_threshold | 50000 | RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. [cm] | -| nav_rth_allow_landing | ALWAYS | If set to ON drone will land as a last phase of RTH. | -| nav_rth_alt_mode | AT_LEAST | Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details | -| nav_rth_altitude | 1000 | Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters) | -| nav_rth_climb_first | ON | If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way. | -| nav_rth_climb_ignore_emerg | OFF | If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status. | -| nav_rth_home_altitude | 0 | Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm] | -| nav_rth_home_offset_direction | 0 | Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) | -| nav_rth_home_offset_distance | 0 | Distance offset from GPS established home to "safe" position used for RTH (cm, 0 disables) | -| nav_rth_tail_first | OFF | If set to ON drone will return tail-first. Obviously meaningless for airplanes. | -| nav_use_fw_yaw_control | OFF | Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats | -| nav_use_midthr_for_althold | OFF | If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude | -| nav_user_control_mode | ATTI | Defines how Pitch/Roll input from RC receiver affects flight in POSHOLD mode: ATTI - pitch/roll controls attitude like in ANGLE mode; CRUISE - pitch/roll controls velocity in forward and right direction. | -| nav_wp_radius | 100 | Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius | -| nav_wp_safe_distance | 10000 | First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check. | -| osd_ahi_style | DEFAULT | Sets OSD Artificial Horizon style "DEFAULT" or "LINE" for the FrSky Graphical OSD. | -| osd_alt_alarm | 100 | Value above which to make the OSD relative altitude indicator blink (meters) | -| osd_artificial_horizon_max_pitch | 20 | Max pitch, in degrees, for OSD artificial horizon | -| osd_baro_temp_alarm_max | 600 | Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade) | -| osd_baro_temp_alarm_min | -200 | Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade) | -| osd_current_alarm | 0 | Value above which the OSD current consumption element will start blinking. Measured in full Amperes. | -| osd_dist_alarm | 1000 | Value above which to make the OSD distance from home indicator blink (meters) | -| osd_esc_temp_alarm_max | 900 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | -| osd_esc_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | -| osd_estimations_wind_compensation | ON | Use wind estimation for remaining flight time/distance estimation | -| osd_failsafe_switch_layout | OFF | If enabled the OSD automatically switches to the first layout during failsafe | -| osd_gforce_alarm | 5 | Value above which the OSD g force indicator will blink (g) | -| osd_gforce_axis_alarm_max | 5 | Value above which the OSD axis g force indicators will blink (g) | -| osd_gforce_axis_alarm_min | -5 | Value under which the OSD axis g force indicators will blink (g) | -| osd_hud_wp_disp | OFF | Controls display of the next waypoints in the HUD. | -| osd_imu_temp_alarm_max | 600 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | -| osd_imu_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | -| osd_main_voltage_decimals | 1 | Number of decimals for the battery voltages displayed in the OSD [1-2]. | -| osd_neg_alt_alarm | 5 | Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters) | -| osd_row_shiftdown | 0 | Number of rows to shift the OSD display (increase if top rows are cut off) | -| osd_rssi_alarm | 20 | Value bellow which to make the OSD RSSI indicator blink | -| osd_stats_energy_unit | MAH | Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour) | -| osd_temp_label_align | LEFT | Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT` | -| osd_time_alarm | 10 | Value above which to make the OSD flight time indicator blink (minutes) | -| osd_units | METRIC | IMPERIAL, METRIC, UK | -| osd_video_system | AUTO | Video system used. Possible values are `AUTO`, `PAL` and `NTSC` | -| pid_type | | Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID` | -| pidsum_limit | 500 | A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | -| pidsum_limit_yaw | 400 | A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | -| pitch_rate | 20 | Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. | -| platform_type | "MULTIROTOR" | Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented | -| pos_hold_deadband | 20 | Stick deadband in [r/c points], applied after r/c deadband and expo | -| rangefinder_median_filter | OFF | 3-point median filtering for rangefinder readouts | -| rate_accel_limit_roll_pitch | 0 | Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting. | -| rate_accel_limit_yaw | 10000 | Limits acceleration of YAW rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 180 dps^2). When set correctly, it greatly improves stopping performance and general stability during yaw turns. Value of 0 disables limiting. | -| rc_expo | 70 | Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`) | -| rc_filter_frequency | 50 | RC data biquad filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay. Practical values are 20-50. Set to zero to disable entirely and use unsmoothed RC stick values | -| rc_yaw_expo | 20 | Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`) | -| reboot_character | 82 | Special character used to trigger reboot | -| report_cell_voltage | OFF | S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON | -| roll_rate | 20 | Defines rotation rate on ROLL axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. | -| rpm_gyro_filter_enabled | `OFF` | Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV | -| rpm_gyro_harmonics | 1 | Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine | -| rpm_gyro_min_hz | 150 | The lowest frequency for gyro RPM filtere. Default `150` is fine for 5" mini-quads. On 7-inch drones you can lower even down to `60`-`70` | -| rpm_gyro_q | 500 | Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting | -| rssi_adc_channel | - | ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled | -| rssi_channel | 0 | RX channel containing the RSSI signal | -| rssi_max | 100 | The maximum RSSI value sent by the receiver, in %. For example, if your receiver's maximum RSSI value shows as 83% in the configurator/OSD set this parameter to 83. See also rssi_min. | -| rssi_min | 0 | The minimum RSSI value sent by the receiver, in %. For example, if your receiver's minimum RSSI value shows as 42% in the configurator/OSD set this parameter to 42. See also rssi_max. Note that rssi_min can be set to a value bigger than rssi_max to invert the RSSI calculation (i.e. bigger values mean lower RSSI). | -| rssi_source | `AUTO` | Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP` | -| rth_energy_margin | 5 | Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation | -| rx_max_usec | 2115 | Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of mid_rc. | -| rx_min_usec | 885 | Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc. | -| sdcard_detect_inverted | `TARGET dependent` | This setting drives the way SD card is detected in card slot. On some targets (AnyFC F7 clone) different card slot was used and depending of hardware revision ON or OFF setting might be required. If card is not detected, change this value. | -| serialrx_halfduplex | OFF | Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire | -| serialrx_inverted | OFF | Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY). | -| serialrx_provider | SPEK1024 | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. | -| servo_center_pulse | 1500 | Servo midpoint | -| servo_lpf_hz | 20 | Selects the servo PWM output cutoff frequency. Value is in [Hz] | -| servo_protocol | PWM | An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SERVO_DRIVER` (I2C PCA9685 peripheral), `SBUS` (S.Bus protocol output via a configured serial port) | -| servo_pwm_rate | 50 | Output frequency (in Hz) servo pins. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz. | -| sim_ground_station_number | Empty string | Number of phone that is used to communicate with SIM module. Messages / calls from other numbers are ignored. If undefined, can be set by calling or sending a message to the module. | -| sim_low_altitude | 0 | Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`. | -| sim_pin | Empty string | PIN code for the SIM module | -| sim_transmit_flags | F | String specifying text message transmit condition flags for the SIM module. Flags can be given in any order. Empty string means the module only sends response messages. `A`: acceleration events, `T`: continuous transmission, `F`: continuous transmission in failsafe mode, `L`: continuous transmission when altitude is below `sim_low_altitude`, `G`: continuous transmission when GPS signal quality is low | -| sim_transmit_interval | 60 | Text message transmission interval in seconds for SIM module. Minimum value: 10 | -| small_angle | 25 | If the aircraft tilt angle exceed this value the copter will refuse to arm. | -| smartport_fuel_unit | MAH | S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH] | -| spektrum_sat_bind | 0 | 0 = disabled. Used to bind the spektrum satellite to RX | -| stats | OFF | General switch of the statistics recording feature (a.k.a. odometer) | -| stats_total_dist | 0 | Total flight distance [in meters]. The value is updated on every disarm when "stats" are enabled. | -| stats_total_time | 0 | Total flight time [in seconds]. The value is updated on every disarm when "stats" are enabled. | -| switch_disarm_delay | 250 | Delay before disarming when requested by switch (ms) [0-1000] | -| telemetry_halfduplex | OFF | S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details | -| telemetry_inverted | OFF | Determines if the telemetry protocol default signal inversion is reversed. This should be OFF in most cases unless a custom or hacked RX is used. | -| telemetry_switch | OFF | Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed. | -| thr_comp_weight | 0.692 | Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage) | -| thr_expo | 0 | Throttle exposition value | -| thr_mid | 50 | Throttle value when the stick is set to mid-position. Used in the throttle curve calculation. | -| throttle_idle | 15 | The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle. | -| throttle_scale | 1.000 | Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50% | -| throttle_tilt_comp_str | 0 | Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled. | -| tpa_breakpoint | 1500 | See tpa_rate. | -| tpa_rate | 0 | Throttle PID attenuation reduces influence of P on ROLL and PITCH as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate. | -| tri_unarmed_servo | ON | On tricopter mix only, if this is set to ON, servo will always be correcting regardless of armed state. to disable this, set it to OFF. | -| tz_automatic_dst | OFF | Automatically add Daylight Saving Time to the GPS time when needed or simply ignore it. Includes presets for EU and the USA - if you live outside these areas it is suggested to manage DST manually via `tz_offset`. | -| tz_offset | 0 | Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs | -| vbat_adc_channel | - | ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled | -| vbat_cell_detect_voltage | 430 | Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units, default is 4.30V | -| vbat_max_cell_voltage | 420 | Maximum voltage per cell in 0.01V units, default is 4.20V | -| vbat_meter_type | `ADC` | Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running | -| vbat_min_cell_voltage | 330 | Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V) | -| vbat_scale | 1100 | Battery voltage calibration value. 1100 = 11:1 voltage divider (10k:1k) x 100. Adjust this slightly if reported pack voltage is different from multimeter reading. You can get current voltage by typing "status" in cli. | -| vbat_warning_cell_voltage | 350 | Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V) | -| vtx_band | 4 | Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race. | -| vtx_channel | 1 | Channel to use within the configured `vtx_band`. Valid values are [1, 8]. | -| vtx_halfduplex | ON | Use half duplex UART to communicate with the VTX, using only a TX pin in the FC. | -| vtx_low_power_disarm | OFF | When the craft is disarmed, set the VTX to its lowest power. `ON` will set the power to its minimum value on startup, increase it to `vtx_power` when arming and change it back to its lowest setting after disarming. `UNTIL_FIRST_ARM` will start with minimum power, but once the craft is armed it will increase to `vtx_power` and it will never decrease until the craft is power cycled. | -| vtx_power | 1 | VTX RF power level to use. The exact number of mw depends on the VTX hardware. | -| yaw_deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. | -| yaw_lpf_hz | 30 | Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below) | -| yaw_rate | 20 | Defines rotation rate on YAW axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. | - - > Note: this table is autogenerated. Do not edit it manually. +See [Settings.md](Settings.md). diff --git a/docs/Settings.md b/docs/Settings.md new file mode 100644 index 00000000000..8e3ca620fdc --- /dev/null +++ b/docs/Settings.md @@ -0,0 +1,393 @@ +# CLI Variable Reference + +| Variable Name | Default Value | Description | +| ------------- | ------------- | ----------- | +| 3d_deadband_high | 1514 | High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead) | +| 3d_deadband_low | 1406 | Low value of throttle deadband for 3D mode (when stick is in the 3d_deadband_throttle range, the fixed values of 3d_deadband_low / _high are used instead) | +| 3d_deadband_throttle | 50 | Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter. | +| 3d_neutral | 1460 | Neutral (stop) throttle value for 3D mode | +| acc_event_threshold_high | 0 | Acceleration threshold [cm/s/s] for impact / high g event text messages sent by SIM module. Acceleration values greater than 4 g can occur in fixed wing flight without an impact, so a setting of 4000 or greater is suggested. 0 = detection off. | +| acc_event_threshold_low | 0 | Acceleration threshold [cm/s/s] for low-g / freefall detection text messages sent by SIM module. A setting of less than 100 is suggested. Valid values: [0-900], 0 = detection off. | +| acc_event_threshold_neg_x | 0 | Acceleration threshold [cm/s/s] for backwards acceleration / fixed wing landing detection text messages sent by SIM module. Suggested value for fixed wing: 1100. 0 = detection off. | +| acc_hardware | AUTO | Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info | +| acc_lpf_hz | 15 | Software-based filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. | +| acc_lpf_type | BIQUAD | Specifies the type of the software LPF of the acc signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. | +| accgain_x | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | +| accgain_y | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | +| accgain_z | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | +| acczero_x | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | +| acczero_y | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | +| acczero_z | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | +| airspeed_adc_channel | 0 | ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0 | +| align_acc | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. | +| align_board_pitch | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | +| align_board_roll | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | +| align_board_yaw | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | +| align_gyro | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. | +| align_mag | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. | +| align_mag_pitch | 0 | Same as align_mag_roll, but for the pitch axis. | +| align_mag_roll | 0 | Set the external mag alignment on the roll axis (in 0.1 degree steps). If this value is non-zero, the compass is assumed to be externally mounted and both the board and on-board compass alignent (align_mag) are ignored. See also align_mag_pitch and align_mag_yaw. | +| align_mag_yaw | 0 | Same as align_mag_roll, but for the yaw axis. | +| align_opflow | 5 | Optical flow module alignment (default CW0_DEG_FLIP) | +| alt_hold_deadband | 50 | Defines the deadband of throttle during alt_hold [r/c points] | +| antigravity_accelerator | 1 | | +| antigravity_cutoff_lpf_hz | 15 | Antigravity cutoff frequenct for Throtte filter. Antigravity is based on the difference between actual and filtered throttle input. The bigger is the difference, the bigger Antigravity gain | +| antigravity_gain | 1 | Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements | +| baro_cal_tolerance | 150 | Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]. | +| baro_hardware | AUTO | Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info | +| baro_median_filter | ON | 3-point median filtering for barometer readouts. No reason to change this setting | +| bat_cells | 0 | Number of cells of the battery (0 = autodetect), see battery documentation | +| bat_voltage_src | RAW | Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP` | +| battery_capacity | 0 | Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity. | +| battery_capacity_critical | 0 | If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps. | +| battery_capacity_unit | MAH | Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour). | +| battery_capacity_warning | 0 | If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink. | +| blackbox_device | SPIFLASH | Selection of where to write blackbox data | +| blackbox_rate_denom | 1 | Blackbox logging rate denominator. See blackbox_rate_num. | +| blackbox_rate_num | 1 | Blackbox logging rate numerator. Use num/denom settings to decide if a frame should be logged, allowing control of the portion of logged loop iterations | +| cpu_underclock | OFF | This option is only available on certain architectures (F3 CPUs at the moment). It makes CPU clock lower to reduce interference to long-range RC systems working at 433MHz | +| cruise_power | 0 | Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit | +| current_adc_channel | - | ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled | +| current_meter_offset | 0 | This sets the output offset voltage of the current sensor in millivolts. | +| current_meter_scale | 400 | This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt. | +| current_meter_type | ADC | ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position. | +| deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. | +| disarm_kill_switch | ON | Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel. | +| display_force_sw_blink | OFF | OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON | +| dterm_lpf2_hz | 0 | Cutoff frequency for stage 2 D-term low pass filter | +| dterm_lpf2_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | +| dterm_lpf_hz | 40 | Dterm low pass filter cutoff frequency. Default setting is very conservative and small multirotors should use higher value between 80 and 100Hz. 80 seems like a gold spot for 7-inch builds while 100 should work best with 5-inch machines. If motors are getting too hot, lower the value | +| dterm_lpf_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | +| dynamic_gyro_notch_enabled | `OFF` | Enable/disable dynamic gyro notch also known as Matrix Filter | +| dynamic_gyro_notch_min_hz | 150 | Minimum frequency for dynamic notches. Default value of `150` works best with 5" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7" drones. 10" can go down to `60` - `70` | +| dynamic_gyro_notch_q | 120 | Q factor for dynamic notches | +| dynamic_gyro_notch_range | `MEDIUM` | Range for dynamic gyro notches. `MEDIUM` for 5", `HIGH` for 3" and `MEDIUM`/`LOW` for 7" and bigger propellers | +| failsafe_delay | 5 | Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). | +| failsafe_fw_pitch_angle | 100 | Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb | +| failsafe_fw_roll_angle | -200 | Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll | +| failsafe_fw_yaw_rate | -45 | Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn | +| failsafe_lights | ON | Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]. | +| failsafe_lights_flash_on_time | 100 | Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]. | +| failsafe_lights_flash_period | 1000 | Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]. | +| failsafe_min_distance | 0 | If failsafe happens when craft is closer than this distance in centimeters from home, failsafe will not execute regular failsafe_procedure, but will execute procedure specified in failsafe_min_distance_procedure instead. 0 = Normal failsafe_procedure always taken. | +| failsafe_min_distance_procedure | DROP | What failsafe procedure to initiate in Stage 2 when craft is closer to home than failsafe_min_distance. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | +| failsafe_mission | ON | If set to `OFF` the failsafe procedure won't be triggered and the mission will continue if the FC is in WP (automatic mission) mode | +| failsafe_off_delay | 200 | Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay). | +| failsafe_procedure | SET-THR | What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | +| failsafe_recovery_delay | 5 | Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay). | +| failsafe_stick_threshold | 50 | Threshold for stick motion to consider failsafe condition resolved. If non-zero failsafe won't clear even if RC link is restored - you have to move sticks to exit failsafe. | +| failsafe_throttle | 1000 | Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | +| failsafe_throttle_low_delay | 100 | If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout | +| fixed_wing_auto_arm | OFF | Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured. | +| flaperon_throw_offset | 200 | Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated. | +| frsky_coordinates_format | 0 | D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA | +| frsky_default_latitude | 0.000 | D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. | +| frsky_default_longitude | 0.000 | D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. | +| frsky_pitch_roll | OFF | S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data | +| frsky_unit | METRIC | Not used? [METRIC/IMPERIAL] | +| frsky_vfas_precision | 0 | D-Series telemetry only: Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method | +| fw_autotune_ff_to_i_tc | 600 | FF to I time (defines time for I to reach the same level of response as FF) [ms] | +| fw_autotune_ff_to_p_gain | 10 | FF to P gain (strength relationship) [%] | +| fw_autotune_overshoot_time | 100 | Time [ms] to detect sustained overshoot | +| fw_autotune_threshold | 50 | Threshold [%] of max rate to consider overshoot/undershoot detection | +| fw_autotune_undershoot_time | 200 | Time [ms] to detect sustained undershoot | +| fw_d_level | 75 | Fixed-wing attitude stabilisation HORIZON transition point | +| fw_ff_pitch | 50 | Fixed-wing rate stabilisation FF-gain for PITCH | +| fw_ff_roll | 50 | Fixed-wing rate stabilisation FF-gain for ROLL | +| fw_ff_yaw | 60 | Fixed-wing rate stabilisation FF-gain for YAW | +| fw_i_level | 5 | Fixed-wing attitude stabilisation low-pass filter cutoff | +| fw_i_pitch | 7 | Fixed-wing rate stabilisation I-gain for PITCH | +| fw_i_roll | 7 | Fixed-wing rate stabilisation I-gain for ROLL | +| fw_i_yaw | 10 | Fixed-wing rate stabilisation I-gain for YAW | +| fw_iterm_limit_stick_position | 0.5 | Iterm is not allowed to grow when stick position is above threshold. This solves the problem of bounceback or followthrough when full stick deflection is applied on poorely tuned fixed wings. In other words, stabilization is partialy disabled when pilot is actively controlling the aircraft and active when sticks are not touched. `0` mean stick is in center position, `1` means it is fully deflected to either side | +| fw_iterm_throw_limit | 165 | Limits max/min I-term value in stabilization PID controller in case of Fixed Wing. It solves the problem of servo saturation before take-off/throwing the airplane into the air. By default, error accumulated in I-term can not exceed 1/3 of servo throw (around 165us). Set 0 to disable completely. | +| fw_loiter_direction | RIGHT | Direction of loitering: center point on right wing (clockwise - default), or center point on left wing (counterclockwise). If equal YAW then can be changed in flight using a yaw stick. | +| fw_min_throttle_down_pitch | 0 | Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees) | +| fw_p_level | 20 | Fixed-wing attitude stabilisation P-gain | +| fw_p_pitch | 5 | Fixed-wing rate stabilisation P-gain for PITCH | +| fw_p_roll | 5 | Fixed-wing rate stabilisation P-gain for ROLL | +| fw_p_yaw | 6 | Fixed-wing rate stabilisation P-gain for YAW | +| fw_reference_airspeed | 1000 | Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present. | +| fw_tpa_time_constant | 0 | TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. Planes with low thrust/weight ratio generally need higher time constant. Default is zero for compatibility with old setups | +| fw_turn_assist_yaw_gain | 1 | Gain required to keep the yaw rate consistent with the turn rate for a coordinated turn (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter | +| gps_auto_baud | ON | Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS. When used with NAZA/DJI it will automatic detect GPS baudrate and change to it, ignoring the selected baudrate set in ports | +| gps_auto_config | ON | Enable automatic configuration of UBlox GPS receivers. | +| gps_dyn_model | AIR_1G | GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying. | +| gps_min_sats | 6 | Minimum number of GPS satellites in view to acquire GPS_FIX and consider GPS position valid. Some GPS receivers appeared to be very inaccurate with low satellite count. | +| gps_provider | UBLOX | Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N). | +| gps_sbas_mode | NONE | Which SBAS mode to be used | +| gps_ublox_use_galileo | OFF | Enable use of Galileo satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires M8N and Ublox firmware 3.x (or later) [OFF/ON]. | +| gyro_hardware_lpf | 42HZ | Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first. | +| gyro_lpf_hz | 60 | Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. | +| gyro_lpf_type | BIQUAD | Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. | +| gyro_stage2_lowpass_hz | 0 | Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz) | +| gyro_stage2_lowpass_type | `BIQUAD` | Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | +| gyro_sync | OFF | This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf | +| has_flaps | OFF | Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot | +| heading_hold_rate_limit | 90 | This setting limits yaw rotation rate that HEADING_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when HEADING_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes. | +| hott_alarm_sound_interval | 5 | Battery alarm delay in seconds for Hott telemetry | +| i2c_speed | 400KHZ | This setting controls the clock speed of I2C bus. 400KHZ is the default that most setups are able to use. Some noise-free setups may be overclocked to 800KHZ. Some sensor chips or setups with long wires may work unreliably at 400KHZ - user can try lowering the clock speed to 200KHZ or even 100KHZ. User need to bear in mind that lower clock speeds might require higher looptimes (lower looptime rate) | +| ibus_telemetry_type | 0 | Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details. | +| idle_power | 0 | Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit | +| imu_acc_ignore_rate | 0 | Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes | +| imu_acc_ignore_slope | 0 | Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight) | +| imu_dcm_ki | 50 | Inertial Measurement Unit KI Gain for accelerometer measurements | +| imu_dcm_ki_mag | 0 | Inertial Measurement Unit KI Gain for compass measurements | +| imu_dcm_kp | 2500 | Inertial Measurement Unit KP Gain for accelerometer measurements | +| imu_dcm_kp_mag | 10000 | Inertial Measurement Unit KP Gain for compass measurements | +| inav_auto_mag_decl | ON | Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored. | +| inav_baro_epv | 100.000 | Uncertainty value for barometric sensor [cm] | +| inav_gravity_cal_tolerance | 5 | Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value. | +| inav_max_eph_epv | 1000.000 | Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm] | +| inav_max_surface_altitude | 200 | Max allowed altitude for surface following mode. [cm] | +| inav_reset_altitude | FIRST_ARM | Defines when relative estimated altitude is reset to zero. Variants - `NEVER` (once reference is acquired it's used regardless); `FIRST_ARM` (keep altitude at zero until firstly armed), `EACH_ARM` (altitude is reset to zero on each arming) | +| inav_reset_home | FIRST_ARM | Allows to chose when the home position is reset. Can help prevent resetting home position after accidental mid-air disarm. Possible values are: NEVER, FIRST_ARM and EACH_ARM | +| inav_use_gps_velned | ON | Defined if iNav should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF iNav will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance. | +| inav_w_acc_bias | 0.010 | Weight for accelerometer drift estimation | +| inav_w_xy_gps_p | 1.000 | Weight of GPS coordinates in estimated UAV position and speed. | +| inav_w_xy_gps_v | 2.000 | Weight of GPS velocity data in estimated UAV speed | +| inav_w_xy_res_v | 0.500 | Decay coefficient for estimated velocity when GPS reference for position is lost | +| inav_w_z_baro_p | 0.350 | Weight of barometer measurements in estimated altitude and climb rate | +| inav_w_z_gps_p | 0.200 | Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes | +| inav_w_z_gps_v | 0.500 | Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero | +| inav_w_z_res_v | 0.500 | Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost | +| iterm_windup | 50 | Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter) | +| ledstrip_visual_beeper | OFF | | +| looptime | 1000 | This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible. | +| ltm_update_rate | NORMAL | Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details. | +| mag_calibration_time | 30 | Adjust how long time the Calibration of mag will last. | +| mag_declination | 0 | Current location magnetic declination in format. For example, -6deg 37min = -637 for Japan. Leading zero in ddd not required. Get your local magnetic declination here: http://magnetic-declination.com/ . Not in use if inav_auto_mag_decl is turned on and you acquire valid GPS fix. | +| mag_hardware | AUTO | Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info | +| mag_to_use | | Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target | +| magzero_x | 0 | Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed. | +| magzero_y | 0 | Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed. | +| magzero_z | 0 | Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed. | +| manual_pitch_rate | 100 | Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]% | +| manual_rc_expo | 70 | Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100] | +| manual_rc_yaw_expo | 20 | Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100] | +| manual_roll_rate | 100 | Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]% | +| manual_yaw_rate | 100 | Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]% | +| max_angle_inclination_pit | 300 | Maximum inclination in level (angle) mode (PITCH axis). 100=10° | +| max_angle_inclination_rll | 300 | Maximum inclination in level (angle) mode (ROLL axis). 100=10° | +| max_check | 1900 | These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value. | +| max_throttle | 1850 | This is the maximum value (in us) sent to esc when armed. Default of 1850 are OK for everyone (legacy). For modern ESCs, higher values (c. 2000) may be more appropriate. If you have brushed motors, the value should be set to 2000. | +| mc_airmode_threshold | 1300 | Defines airmode THROTTLE activation threshold when `mc_airmode_type` **THROTTLE_THRESHOLD** is used | +| mc_airmode_type | STICK_CENTER | Defines the Airmode state handling type for Multirotors. Default **STICK_CENTER** is the classical approach in which Airmode is always active if enabled, but when the throttle is low and ROLL/PITCH/YAW sticks are centered, Iterms is not allowed to grow (ANTI_WINDUP). **THROTTLE_THRESHOLD** is the Airmode behavior known from Betaflight. In this mode, Airmode is active as soon THROTTLE position is above `mc_airmode_threshold` and stays active until disarm. ANTI_WINDUP is never triggered. For small Multirotors (up to 7-inch propellers) it is suggested to switch to **THROTTLE_THRESHOLD** since it keeps full stabilization no matter what pilot does with the sticks. Fixed Wings always use **STICK_CENTER** mode. | +| mc_cd_lpf_hz | 30 | Cutoff frequency for Control Derivative. Lower value smoother reaction on fast stick movements. With higher values, response will be more aggressive, jerky | +| mc_cd_pitch | 60 | Multicopter Control Derivative gain for PITCH | +| mc_cd_roll | 60 | Multicopter Control Derivative gain for ROLL | +| mc_cd_yaw | 60 | Multicopter Control Derivative gain for YAW | +| mc_d_level | 75 | Multicopter attitude stabilisation HORIZON transition point | +| mc_d_pitch | 23 | Multicopter rate stabilisation D-gain for PITCH | +| mc_d_roll | 23 | Multicopter rate stabilisation D-gain for ROLL | +| mc_d_yaw | 0 | Multicopter rate stabilisation D-gain for YAW | +| mc_i_level | 15 | Multicopter attitude stabilisation low-pass filter cutoff | +| mc_i_pitch | 30 | Multicopter rate stabilisation I-gain for PITCH | +| mc_i_roll | 30 | Multicopter rate stabilisation I-gain for ROLL | +| mc_i_yaw | 45 | Multicopter rate stabilisation I-gain for YAW | +| mc_p_level | 20 | Multicopter attitude stabilisation P-gain | +| mc_p_pitch | 40 | Multicopter rate stabilisation P-gain for PITCH | +| mc_p_roll | 40 | Multicopter rate stabilisation P-gain for ROLL | +| mc_p_yaw | 85 | Multicopter rate stabilisation P-gain for YAW | +| min_check | 1100 | These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value. | +| min_command | 1000 | This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly when powered up, try decreasing this value. It can also be used for calibrating all ESCs at once. | +| mode_range_logic_operator | OR | Control how Mode selection works in flight modes. If you example have Angle mode configured on two different Aux channels, this controls if you need both activated ( AND ) or if you only need one activated ( OR ) to active angle mode. | +| model_preview_type | -1 | ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons. | +| moron_threshold | 32 | When powering up, gyro bias is calculated. If the model is shaking/moving during this initial calibration, offsets are calculated incorrectly, and could lead to poor flying performance. This threshold means how much average gyro reading could differ before re-calibration is triggered. | +| motor_accel_time | 0 | Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000] | +| motor_decel_time | 0 | Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000] | +| motor_direction_inverted | OFF | Use if you need to inverse yaw motor direction. | +| motor_pwm_protocol | STANDARD | Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED | +| motor_pwm_rate | 400 | Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000. | +| name | Empty string | Craft name | +| nav_auto_climb_rate | 500 | Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s] | +| nav_auto_speed | 300 | Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only] | +| nav_disarm_on_landing | OFF | If set to ON, iNav disarms the FC after landing | +| nav_emerg_landing_speed | 500 | Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s] | +| nav_extra_arming_safety | ON | If set to ON drone won't arm if no GPS fix and any navigation mode like RTH or POSHOLD is configured. ALLOW_BYPASS allows the user to momentarily disable this check by holding yaw high (left stick held at the bottom right in mode 2) when switch arming is used | +| nav_fw_allow_manual_thr_increase | OFF | Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing | +| nav_fw_bank_angle | 20 | Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll | +| nav_fw_climb_angle | 20 | Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit | +| nav_fw_control_smoothness | 0 | How smoothly the autopilot controls the airplane to correct the navigation error | +| nav_fw_cruise_speed | 0 | Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s | +| nav_fw_cruise_thr | 1400 | Cruise throttle in GPS assisted modes, this includes RTH. Should be set high enough to avoid stalling. This values gives INAV a base for throttle when flying straight, and it will increase or decrease throttle based on pitch of airplane and the parameters below. In addition it will increase throttle if GPS speed gets below 7m/s ( hardcoded ) | +| nav_fw_cruise_yaw_rate | 20 | Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps] | +| nav_fw_dive_angle | 15 | Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit | +| nav_fw_heading_p | 60 | P gain of Heading Hold controller (Fixedwing) | +| nav_fw_land_dive_angle | 2 | Dive angle that airplane will use during final landing phase. During dive phase, motor is stopped or IDLE and roll control is locked to 0 degrees | +| nav_fw_launch_accel | 1863 | Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s | +| nav_fw_launch_climb_angle | 18 | Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit | +| nav_fw_launch_detect_time | 40 | Time for which thresholds have to breached to consider launch happened [ms] | +| nav_fw_launch_idle_thr | 1000 | Launch idle throttle - throttle to be set before launch sequence is initiated. If set below minimum throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above minimum throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position) | +| nav_fw_launch_max_altitude | 0 | Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]. | +| nav_fw_launch_max_angle | 45 | Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg] | +| nav_fw_launch_min_time | 0 | Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]. | +| nav_fw_launch_motor_delay | 500 | Delay between detected launch and launch sequence start and throttling up (ms) | +| nav_fw_launch_spinup_time | 100 | Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller | +| nav_fw_launch_thr | 1700 | Launch throttle - throttle to be set during launch sequence (pwm units) | +| nav_fw_launch_timeout | 5000 | Maximum time for launch sequence to be executed. After this time LAUNCH mode will be turned off and regular flight mode will take over (ms) | +| nav_fw_launch_velocity | 300 | Forward velocity threshold for swing-launch detection [cm/s] | +| nav_fw_loiter_radius | 5000 | PosHold radius. 3000 to 7500 is a good value (30-75m) [cm] | +| nav_fw_max_thr | 1700 | Maximum throttle for flying wing in GPS assisted modes | +| nav_fw_min_thr | 1200 | Minimum throttle for flying wing in GPS assisted modes | +| nav_fw_pitch2thr | 10 | Amount of throttle applied related to pitch attitude in GPS assisted modes. Throttle = nav_fw_cruise_throttle - (nav_fw_pitch2thr * pitch_angle). (notice that pitch_angle is in degrees and is negative when climbing and positive when diving, and throttle value is constrained between nav_fw_min_thr and nav_fw_max_thr) | +| nav_fw_pos_hdg_d | 0 | D gain of heading trajectory PID controller. (Fixedwing, rovers, boats) | +| nav_fw_pos_hdg_i | 0 | I gain of heading trajectory PID controller. (Fixedwing, rovers, boats) | +| nav_fw_pos_hdg_p | 60 | P gain of heading PID controller. (Fixedwing, rovers, boats) | +| nav_fw_pos_hdg_pidsum_limit | 350 | Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats) | +| nav_fw_pos_xy_d | 8 | D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero | +| nav_fw_pos_xy_i | 5 | I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero | +| nav_fw_pos_xy_p | 75 | P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH | +| nav_fw_pos_z_d | 0 | D gain of altitude PID controller (Fixedwing) | +| nav_fw_pos_z_i | 0 | I gain of altitude PID controller (Fixedwing) | +| nav_fw_pos_z_p | 50 | P gain of altitude PID controller (Fixedwing) | +| nav_fw_yaw_deadband | 0 | Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course | +| nav_land_slowdown_maxalt | 2000 | Defines at what altitude the descent velocity should start to ramp down from 100% nav_landing_speed to 25% nav_landing_speed. [cm] | +| nav_land_slowdown_minalt | 500 | Defines at what altitude the descent velocity should start to be 25% of nav_landing_speed [cm] | +| nav_landing_speed | 200 | Vertical descent velocity during the RTH landing phase. [cm/s] | +| nav_manual_climb_rate | 200 | Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] | +| nav_manual_speed | 500 | Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only] | +| nav_mc_auto_disarm_delay | 2000 | | +| nav_mc_bank_angle | 30 | Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude | +| nav_mc_braking_bank_angle | 40 | max angle that MR is allowed to bank in BOOST mode | +| nav_mc_braking_boost_disengage_speed | 100 | BOOST will be disabled when speed goes below this value | +| nav_mc_braking_boost_factor | 100 | acceleration factor for BOOST phase | +| nav_mc_braking_boost_speed_threshold | 150 | BOOST can be enabled when speed is above this value | +| nav_mc_braking_boost_timeout | 750 | how long in ms BOOST phase can happen | +| nav_mc_braking_disengage_speed | 75 | braking is disabled when speed goes below this value | +| nav_mc_braking_speed_threshold | 100 | min speed in cm/s above which braking can happen | +| nav_mc_braking_timeout | 2000 | timeout in ms for braking | +| nav_mc_heading_p | 60 | P gain of Heading Hold controller (Multirotor) | +| nav_mc_hover_thr | 1500 | Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering. | +| nav_mc_pos_deceleration_time | 120 | Used for stoping distance calculation. Stop position is computed as _speed_ * _nav_mc_pos_deceleration_time_ from the place where sticks are released. Braking mode overrides this setting | +| nav_mc_pos_expo | 10 | Expo for PosHold control | +| nav_mc_pos_xy_p | 65 | Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity | +| nav_mc_pos_z_p | 50 | P gain of altitude PID controller (Multirotor) | +| nav_mc_vel_xy_d | 100 | D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target. | +| nav_mc_vel_xy_i | 15 | I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot | +| nav_mc_vel_xy_p | 40 | P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause "nervous" behavior and oscillations | +| nav_mc_vel_z_d | 10 | D gain of velocity PID controller | +| nav_mc_vel_z_i | 50 | I gain of velocity PID controller | +| nav_mc_vel_z_p | 100 | P gain of velocity PID controller | +| nav_min_rth_distance | 500 | Minimum distance from homepoint when RTH full procedure will be activated [cm]. Below this distance, the mode will activate at the current location and the final phase is executed (loiter / land). Above this distance, the full procedure is activated, which may include initial climb and flying directly to the homepoint before entering the loiter / land phase. | +| nav_overrides_motor_stop | ON | Setting to OFF combined with MOTOR_STOP feature will allow user to stop motor when in autonomous modes. On most places this setting is likely to cause a stall. | +| nav_position_timeout | 5 | If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable) | +| nav_rth_abort_threshold | 50000 | RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. [cm] | +| nav_rth_allow_landing | ALWAYS | If set to ON drone will land as a last phase of RTH. | +| nav_rth_alt_mode | AT_LEAST | Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details | +| nav_rth_altitude | 1000 | Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters) | +| nav_rth_climb_first | ON | If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way. | +| nav_rth_climb_ignore_emerg | OFF | If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status. | +| nav_rth_home_altitude | 0 | Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm] | +| nav_rth_home_offset_direction | 0 | Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) | +| nav_rth_home_offset_distance | 0 | Distance offset from GPS established home to "safe" position used for RTH (cm, 0 disables) | +| nav_rth_tail_first | OFF | If set to ON drone will return tail-first. Obviously meaningless for airplanes. | +| nav_use_fw_yaw_control | OFF | Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats | +| nav_use_midthr_for_althold | OFF | If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude | +| nav_user_control_mode | ATTI | Defines how Pitch/Roll input from RC receiver affects flight in POSHOLD mode: ATTI - pitch/roll controls attitude like in ANGLE mode; CRUISE - pitch/roll controls velocity in forward and right direction. | +| nav_wp_radius | 100 | Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius | +| nav_wp_safe_distance | 10000 | First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check. | +| osd_ahi_style | DEFAULT | Sets OSD Artificial Horizon style "DEFAULT" or "LINE" for the FrSky Graphical OSD. | +| osd_alt_alarm | 100 | Value above which to make the OSD relative altitude indicator blink (meters) | +| osd_artificial_horizon_max_pitch | 20 | Max pitch, in degrees, for OSD artificial horizon | +| osd_baro_temp_alarm_max | 600 | Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade) | +| osd_baro_temp_alarm_min | -200 | Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade) | +| osd_current_alarm | 0 | Value above which the OSD current consumption element will start blinking. Measured in full Amperes. | +| osd_dist_alarm | 1000 | Value above which to make the OSD distance from home indicator blink (meters) | +| osd_esc_temp_alarm_max | 900 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | +| osd_esc_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | +| osd_estimations_wind_compensation | ON | Use wind estimation for remaining flight time/distance estimation | +| osd_failsafe_switch_layout | OFF | If enabled the OSD automatically switches to the first layout during failsafe | +| osd_gforce_alarm | 5 | Value above which the OSD g force indicator will blink (g) | +| osd_gforce_axis_alarm_max | 5 | Value above which the OSD axis g force indicators will blink (g) | +| osd_gforce_axis_alarm_min | -5 | Value under which the OSD axis g force indicators will blink (g) | +| osd_hud_wp_disp | OFF | Controls display of the next waypoints in the HUD. | +| osd_imu_temp_alarm_max | 600 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | +| osd_imu_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | +| osd_main_voltage_decimals | 1 | Number of decimals for the battery voltages displayed in the OSD [1-2]. | +| osd_neg_alt_alarm | 5 | Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters) | +| osd_row_shiftdown | 0 | Number of rows to shift the OSD display (increase if top rows are cut off) | +| osd_rssi_alarm | 20 | Value bellow which to make the OSD RSSI indicator blink | +| osd_stats_energy_unit | MAH | Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour) | +| osd_temp_label_align | LEFT | Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT` | +| osd_time_alarm | 10 | Value above which to make the OSD flight time indicator blink (minutes) | +| osd_units | METRIC | IMPERIAL, METRIC, UK | +| osd_video_system | AUTO | Video system used. Possible values are `AUTO`, `PAL` and `NTSC` | +| pid_type | | Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID` | +| pidsum_limit | 500 | A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | +| pidsum_limit_yaw | 400 | A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | +| pitch_rate | 20 | Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. | +| platform_type | "MULTIROTOR" | Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented | +| pos_hold_deadband | 20 | Stick deadband in [r/c points], applied after r/c deadband and expo | +| rangefinder_median_filter | OFF | 3-point median filtering for rangefinder readouts | +| rate_accel_limit_roll_pitch | 0 | Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting. | +| rate_accel_limit_yaw | 10000 | Limits acceleration of YAW rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 180 dps^2). When set correctly, it greatly improves stopping performance and general stability during yaw turns. Value of 0 disables limiting. | +| rc_expo | 70 | Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`) | +| rc_filter_frequency | 50 | RC data biquad filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay. Practical values are 20-50. Set to zero to disable entirely and use unsmoothed RC stick values | +| rc_yaw_expo | 20 | Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`) | +| reboot_character | 82 | Special character used to trigger reboot | +| report_cell_voltage | OFF | S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON | +| roll_rate | 20 | Defines rotation rate on ROLL axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. | +| rpm_gyro_filter_enabled | `OFF` | Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV | +| rpm_gyro_harmonics | 1 | Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine | +| rpm_gyro_min_hz | 150 | The lowest frequency for gyro RPM filtere. Default `150` is fine for 5" mini-quads. On 7-inch drones you can lower even down to `60`-`70` | +| rpm_gyro_q | 500 | Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting | +| rssi_adc_channel | - | ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled | +| rssi_channel | 0 | RX channel containing the RSSI signal | +| rssi_max | 100 | The maximum RSSI value sent by the receiver, in %. For example, if your receiver's maximum RSSI value shows as 83% in the configurator/OSD set this parameter to 83. See also rssi_min. | +| rssi_min | 0 | The minimum RSSI value sent by the receiver, in %. For example, if your receiver's minimum RSSI value shows as 42% in the configurator/OSD set this parameter to 42. See also rssi_max. Note that rssi_min can be set to a value bigger than rssi_max to invert the RSSI calculation (i.e. bigger values mean lower RSSI). | +| rssi_source | `AUTO` | Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP` | +| rth_energy_margin | 5 | Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation | +| rx_max_usec | 2115 | Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of mid_rc. | +| rx_min_usec | 885 | Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc. | +| sdcard_detect_inverted | `TARGET dependent` | This setting drives the way SD card is detected in card slot. On some targets (AnyFC F7 clone) different card slot was used and depending of hardware revision ON or OFF setting might be required. If card is not detected, change this value. | +| serialrx_halfduplex | OFF | Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire | +| serialrx_inverted | OFF | Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY). | +| serialrx_provider | SPEK1024 | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. | +| servo_center_pulse | 1500 | Servo midpoint | +| servo_lpf_hz | 20 | Selects the servo PWM output cutoff frequency. Value is in [Hz] | +| servo_protocol | PWM | An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SERVO_DRIVER` (I2C PCA9685 peripheral), `SBUS` (S.Bus protocol output via a configured serial port) | +| servo_pwm_rate | 50 | Output frequency (in Hz) servo pins. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz. | +| sim_ground_station_number | Empty string | Number of phone that is used to communicate with SIM module. Messages / calls from other numbers are ignored. If undefined, can be set by calling or sending a message to the module. | +| sim_low_altitude | 0 | Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`. | +| sim_pin | Empty string | PIN code for the SIM module | +| sim_transmit_flags | F | String specifying text message transmit condition flags for the SIM module. Flags can be given in any order. Empty string means the module only sends response messages. `A`: acceleration events, `T`: continuous transmission, `F`: continuous transmission in failsafe mode, `L`: continuous transmission when altitude is below `sim_low_altitude`, `G`: continuous transmission when GPS signal quality is low | +| sim_transmit_interval | 60 | Text message transmission interval in seconds for SIM module. Minimum value: 10 | +| small_angle | 25 | If the aircraft tilt angle exceed this value the copter will refuse to arm. | +| smartport_fuel_unit | MAH | S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH] | +| spektrum_sat_bind | 0 | 0 = disabled. Used to bind the spektrum satellite to RX | +| stats | OFF | General switch of the statistics recording feature (a.k.a. odometer) | +| stats_total_dist | 0 | Total flight distance [in meters]. The value is updated on every disarm when "stats" are enabled. | +| stats_total_time | 0 | Total flight time [in seconds]. The value is updated on every disarm when "stats" are enabled. | +| switch_disarm_delay | 250 | Delay before disarming when requested by switch (ms) [0-1000] | +| telemetry_halfduplex | OFF | S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details | +| telemetry_inverted | OFF | Determines if the telemetry protocol default signal inversion is reversed. This should be OFF in most cases unless a custom or hacked RX is used. | +| telemetry_switch | OFF | Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed. | +| thr_comp_weight | 0.692 | Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage) | +| thr_expo | 0 | Throttle exposition value | +| thr_mid | 50 | Throttle value when the stick is set to mid-position. Used in the throttle curve calculation. | +| throttle_idle | 15 | The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle. | +| throttle_scale | 1.000 | Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50% | +| throttle_tilt_comp_str | 0 | Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled. | +| tpa_breakpoint | 1500 | See tpa_rate. | +| tpa_rate | 0 | Throttle PID attenuation reduces influence of P on ROLL and PITCH as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate. | +| tri_unarmed_servo | ON | On tricopter mix only, if this is set to ON, servo will always be correcting regardless of armed state. to disable this, set it to OFF. | +| tz_automatic_dst | OFF | Automatically add Daylight Saving Time to the GPS time when needed or simply ignore it. Includes presets for EU and the USA - if you live outside these areas it is suggested to manage DST manually via `tz_offset`. | +| tz_offset | 0 | Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs | +| vbat_adc_channel | - | ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled | +| vbat_cell_detect_voltage | 430 | Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units, default is 4.30V | +| vbat_max_cell_voltage | 420 | Maximum voltage per cell in 0.01V units, default is 4.20V | +| vbat_meter_type | `ADC` | Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running | +| vbat_min_cell_voltage | 330 | Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V) | +| vbat_scale | 1100 | Battery voltage calibration value. 1100 = 11:1 voltage divider (10k:1k) x 100. Adjust this slightly if reported pack voltage is different from multimeter reading. You can get current voltage by typing "status" in cli. | +| vbat_warning_cell_voltage | 350 | Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V) | +| vtx_band | 4 | Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race. | +| vtx_channel | 1 | Channel to use within the configured `vtx_band`. Valid values are [1, 8]. | +| vtx_halfduplex | ON | Use half duplex UART to communicate with the VTX, using only a TX pin in the FC. | +| vtx_low_power_disarm | OFF | When the craft is disarmed, set the VTX to its lowest power. `ON` will set the power to its minimum value on startup, increase it to `vtx_power` when arming and change it back to its lowest setting after disarming. `UNTIL_FIRST_ARM` will start with minimum power, but once the craft is armed it will increase to `vtx_power` and it will never decrease until the craft is power cycled. | +| vtx_power | 1 | VTX RF power level to use. The exact number of mw depends on the VTX hardware. | +| yaw_deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. | +| yaw_lpf_hz | 30 | Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below) | +| yaw_rate | 20 | Defines rotation rate on YAW axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. | + +> Note: this table is autogenerated. Do not edit it manually. \ No newline at end of file diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index be3096bc727..e832b7a48d9 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -151,38 +151,38 @@ groups: headers: ["sensors/gyro.h"] members: - name: looptime - docs_description: "This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible." - docs_default_value: "1000" + description: "This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible." + default_value: "1000" max: 9000 - name: gyro_sync - docs_description: "This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf" - docs_default_value: "OFF" + description: "This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf" + default_value: "OFF" field: gyroSync type: bool - name: align_gyro - docs_description: "When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP." - docs_default_value: "DEFAULT" + description: "When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP." + default_value: "DEFAULT" field: gyro_align type: uint8_t table: alignment - name: gyro_hardware_lpf - docs_description: "Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first." - docs_default_value: "42HZ" + description: "Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first." + default_value: "42HZ" field: gyro_lpf table: gyro_lpf - name: gyro_lpf_hz - docs_description: "Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value." - docs_default_value: "60" + description: "Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value." + default_value: "60" field: gyro_soft_lpf_hz max: 200 - name: gyro_lpf_type - docs_description: "Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds." - docs_default_value: "BIQUAD" + description: "Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds." + default_value: "BIQUAD" field: gyro_soft_lpf_type table: filter_type - name: moron_threshold - docs_description: "When powering up, gyro bias is calculated. If the model is shaking/moving during this initial calibration, offsets are calculated incorrectly, and could lead to poor flying performance. This threshold means how much average gyro reading could differ before re-calibration is triggered." - docs_default_value: "32" + description: "When powering up, gyro bias is calculated. If the model is shaking/moving during this initial calibration, offsets are calculated incorrectly, and could lead to poor flying performance. This threshold means how much average gyro reading could differ before re-calibration is triggered." + default_value: "32" field: gyroMovementCalibrationThreshold max: 128 - name: gyro_notch_hz @@ -193,38 +193,38 @@ groups: min: 1 max: 500 - name: gyro_stage2_lowpass_hz - docs_description: "Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz)" - docs_default_value: "0" + description: "Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz)" + default_value: "0" field: gyro_stage2_lowpass_hz min: 0 max: 500 - name: gyro_stage2_lowpass_type - docs_description: "Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation." - docs_default_value: "`BIQUAD`" + description: "Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation." + default_value: "`BIQUAD`" field: gyro_stage2_lowpass_type table: filter_type - name: dynamic_gyro_notch_enabled - docs_description: "Enable/disable dynamic gyro notch also known as Matrix Filter" - docs_default_value: "`OFF`" + description: "Enable/disable dynamic gyro notch also known as Matrix Filter" + default_value: "`OFF`" field: dynamicGyroNotchEnabled condition: USE_DYNAMIC_FILTERS type: bool - name: dynamic_gyro_notch_range - docs_description: "Range for dynamic gyro notches. `MEDIUM` for 5\", `HIGH` for 3\" and `MEDIUM`/`LOW` for 7\" and bigger propellers" - docs_default_value: "`MEDIUM`" + description: "Range for dynamic gyro notches. `MEDIUM` for 5\", `HIGH` for 3\" and `MEDIUM`/`LOW` for 7\" and bigger propellers" + default_value: "`MEDIUM`" field: dynamicGyroNotchRange condition: USE_DYNAMIC_FILTERS table: dynamicFilterRangeTable - name: dynamic_gyro_notch_q - docs_description: "Q factor for dynamic notches" - docs_default_value: "120" + description: "Q factor for dynamic notches" + default_value: "120" field: dynamicGyroNotchQ condition: USE_DYNAMIC_FILTERS min: 1 max: 1000 - name: dynamic_gyro_notch_min_hz - docs_description: "Minimum frequency for dynamic notches. Default value of `150` works best with 5\" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7\" drones. 10\" can go down to `60` - `70`" - docs_default_value: "150" + description: "Minimum frequency for dynamic notches. Default value of `150` works best with 5\" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7\" drones. 10\" can go down to `60` - `70`" + default_value: "150" field: dynamicGyroNotchMinHz condition: USE_DYNAMIC_FILTERS min: 30 @@ -259,26 +259,26 @@ groups: condition: USE_ADC members: - name: vbat_adc_channel - docs_description: "ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled" - docs_default_value: "-" + description: "ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled" + default_value: "-" field: adcFunctionChannel[ADC_BATTERY] min: ADC_CHN_NONE max: ADC_CHN_MAX - name: rssi_adc_channel - docs_description: "ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled" - docs_default_value: "-" + description: "ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled" + default_value: "-" field: adcFunctionChannel[ADC_RSSI] min: ADC_CHN_NONE max: ADC_CHN_MAX - name: current_adc_channel - docs_description: "ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled" - docs_default_value: "-" + description: "ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled" + default_value: "-" field: adcFunctionChannel[ADC_CURRENT] min: ADC_CHN_NONE max: ADC_CHN_MAX - name: airspeed_adc_channel - docs_description: "ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0" - docs_default_value: "0" + description: "ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0" + default_value: "0" field: adcFunctionChannel[ADC_AIRSPEED] min: ADC_CHN_NONE max: ADC_CHN_MAX @@ -294,58 +294,58 @@ groups: min: 1 max: 255 - name: align_acc - docs_description: "When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP." - docs_default_value: "DEFAULT" + description: "When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP." + default_value: "DEFAULT" field: acc_align type: uint8_t table: alignment - name: acc_hardware - docs_description: "Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info" - docs_default_value: "AUTO" + description: "Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info" + default_value: "AUTO" table: acc_hardware - name: acc_lpf_hz - docs_description: "Software-based filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value." - docs_default_value: "15" + description: "Software-based filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value." + default_value: "15" min: 0 max: 200 - name: acc_lpf_type - docs_description: "Specifies the type of the software LPF of the acc signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds." - docs_default_value: "BIQUAD" + description: "Specifies the type of the software LPF of the acc signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds." + default_value: "BIQUAD" field: acc_soft_lpf_type table: filter_type - name: acczero_x - docs_description: "Calculated value after '6 position avanced calibration'. See Wiki page." - docs_default_value: "0" + description: "Calculated value after '6 position avanced calibration'. See Wiki page." + default_value: "0" field: accZero.raw[X] min: INT16_MIN max: INT16_MAX - name: acczero_y - docs_description: "Calculated value after '6 position avanced calibration'. See Wiki page." - docs_default_value: "0" + description: "Calculated value after '6 position avanced calibration'. See Wiki page." + default_value: "0" field: accZero.raw[Y] min: INT16_MIN max: INT16_MAX - name: acczero_z - docs_description: "Calculated value after '6 position avanced calibration'. See Wiki page." - docs_default_value: "0" + description: "Calculated value after '6 position avanced calibration'. See Wiki page." + default_value: "0" field: accZero.raw[Z] min: INT16_MIN max: INT16_MAX - name: accgain_x - docs_description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page." - docs_default_value: "4096" + description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page." + default_value: "4096" field: accGain.raw[X] min: 1 max: 8192 - name: accgain_y - docs_description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page." - docs_default_value: "4096" + description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page." + default_value: "4096" field: accGain.raw[Y] min: 1 max: 8192 - name: accgain_z - docs_description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page." - docs_default_value: "4096" + description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page." + default_value: "4096" field: accGain.raw[Z] min: 1 max: 8192 @@ -358,8 +358,8 @@ groups: - name: rangefinder_hardware table: rangefinder_hardware - name: rangefinder_median_filter - docs_description: "3-point median filtering for rangefinder readouts" - docs_default_value: "OFF" + description: "3-point median filtering for rangefinder readouts" + default_value: "OFF" field: use_median_filtering type: bool @@ -374,8 +374,8 @@ groups: min: 0 max: 10000 - name: align_opflow - docs_description: "Optical flow module alignment (default CW0_DEG_FLIP)" - docs_default_value: "5" + description: "Optical flow module alignment (default CW0_DEG_FLIP)" + default_value: "5" field: opflow_align type: uint8_t table: alignment @@ -386,64 +386,64 @@ groups: condition: USE_MAG members: - name: align_mag - docs_description: "When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP." - docs_default_value: "DEFAULT" + description: "When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP." + default_value: "DEFAULT" field: mag_align type: uint8_t table: alignment - name: mag_hardware - docs_description: "Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info" - docs_default_value: "AUTO" + description: "Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info" + default_value: "AUTO" table: mag_hardware - name: mag_declination - docs_description: "Current location magnetic declination in format. For example, -6deg 37min = -637 for Japan. Leading zero in ddd not required. Get your local magnetic declination here: http://magnetic-declination.com/ . Not in use if inav_auto_mag_decl is turned on and you acquire valid GPS fix." - docs_default_value: "0" + description: "Current location magnetic declination in format. For example, -6deg 37min = -637 for Japan. Leading zero in ddd not required. Get your local magnetic declination here: http://magnetic-declination.com/ . Not in use if inav_auto_mag_decl is turned on and you acquire valid GPS fix." + default_value: "0" min: -18000 max: 18000 - name: magzero_x - docs_description: "Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed." - docs_default_value: "0" + description: "Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed." + default_value: "0" field: magZero.raw[X] min: INT16_MIN max: INT16_MAX - name: magzero_y - docs_description: "Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed." - docs_default_value: "0" + description: "Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed." + default_value: "0" field: magZero.raw[Y] min: INT16_MIN max: INT16_MAX - name: magzero_z - docs_description: "Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed." - docs_default_value: "0" + description: "Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed." + default_value: "0" field: magZero.raw[Z] min: INT16_MIN max: INT16_MAX - name: mag_calibration_time - docs_description: "Adjust how long time the Calibration of mag will last." - docs_default_value: "30" + description: "Adjust how long time the Calibration of mag will last." + default_value: "30" field: magCalibrationTimeLimit min: 30 max: 120 - name: mag_to_use - docs_description: "Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target" + description: "Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target" condition: USE_DUAL_MAG min: 0 max: 1 - name: align_mag_roll - docs_description: "Set the external mag alignment on the roll axis (in 0.1 degree steps). If this value is non-zero, the compass is assumed to be externally mounted and both the board and on-board compass alignent (align_mag) are ignored. See also align_mag_pitch and align_mag_yaw." - docs_default_value: "0" + description: "Set the external mag alignment on the roll axis (in 0.1 degree steps). If this value is non-zero, the compass is assumed to be externally mounted and both the board and on-board compass alignent (align_mag) are ignored. See also align_mag_pitch and align_mag_yaw." + default_value: "0" field: rollDeciDegrees min: -1800 max: 3600 - name: align_mag_pitch - docs_description: "Same as align_mag_roll, but for the pitch axis." - docs_default_value: "0" + description: "Same as align_mag_roll, but for the pitch axis." + default_value: "0" field: pitchDeciDegrees min: -1800 max: 3600 - name: align_mag_yaw - docs_description: "Same as align_mag_roll, but for the yaw axis." - docs_default_value: "0" + description: "Same as align_mag_roll, but for the yaw axis." + default_value: "0" field: yawDeciDegrees min: -1800 max: 3600 @@ -454,17 +454,17 @@ groups: condition: USE_BARO members: - name: baro_hardware - docs_description: "Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info" - docs_default_value: "AUTO" + description: "Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info" + default_value: "AUTO" table: baro_hardware - name: baro_median_filter - docs_description: "3-point median filtering for barometer readouts. No reason to change this setting" - docs_default_value: "ON" + description: "3-point median filtering for barometer readouts. No reason to change this setting" + default_value: "ON" field: use_median_filtering type: bool - name: baro_cal_tolerance - docs_description: "Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]." - docs_default_value: "150" + description: "Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]." + default_value: "150" field: baro_calibration_tolerance min: 0 max: 1000 @@ -491,36 +491,36 @@ groups: field: receiverType table: receiver_type - name: min_check - docs_description: "These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value." - docs_default_value: "1100" + description: "These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value." + default_value: "1100" field: mincheck min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: max_check - docs_description: "These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value." - docs_default_value: "1900" + description: "These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value." + default_value: "1900" field: maxcheck min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: rssi_source - docs_description: "Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP`" - docs_default_value: "`AUTO`" + description: "Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP`" + default_value: "`AUTO`" field: rssi_source table: rssi_source - name: rssi_channel - docs_description: "RX channel containing the RSSI signal" - docs_default_value: "0" + description: "RX channel containing the RSSI signal" + default_value: "0" min: 0 max: MAX_SUPPORTED_RC_CHANNEL_COUNT - name: rssi_min - docs_description: "The minimum RSSI value sent by the receiver, in %. For example, if your receiver's minimum RSSI value shows as 42% in the configurator/OSD set this parameter to 42. See also rssi_max. Note that rssi_min can be set to a value bigger than rssi_max to invert the RSSI calculation (i.e. bigger values mean lower RSSI)." - docs_default_value: "0" + description: "The minimum RSSI value sent by the receiver, in %. For example, if your receiver's minimum RSSI value shows as 42% in the configurator/OSD set this parameter to 42. See also rssi_max. Note that rssi_min can be set to a value bigger than rssi_max to invert the RSSI calculation (i.e. bigger values mean lower RSSI)." + default_value: "0" field: rssiMin min: RSSI_VISIBLE_VALUE_MIN max: RSSI_VISIBLE_VALUE_MAX - name: rssi_max - docs_description: "The maximum RSSI value sent by the receiver, in %. For example, if your receiver's maximum RSSI value shows as 83% in the configurator/OSD set this parameter to 83. See also rssi_min." - docs_default_value: "100" + description: "The maximum RSSI value sent by the receiver, in %. For example, if your receiver's maximum RSSI value shows as 83% in the configurator/OSD set this parameter to 83. See also rssi_min." + default_value: "100" field: rssiMax min: RSSI_VISIBLE_VALUE_MIN max: RSSI_VISIBLE_VALUE_MAX @@ -529,19 +529,19 @@ groups: min: 500 max: 10000 - name: rc_filter_frequency - docs_description: "RC data biquad filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay. Practical values are 20-50. Set to zero to disable entirely and use unsmoothed RC stick values" - docs_default_value: "50" + description: "RC data biquad filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay. Practical values are 20-50. Set to zero to disable entirely and use unsmoothed RC stick values" + default_value: "50" field: rcFilterFrequency min: 0 max: 100 - name: serialrx_provider - docs_description: "When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section." - docs_default_value: "SPEK1024" + description: "When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section." + default_value: "SPEK1024" condition: USE_SERIAL_RX table: serial_rx - name: serialrx_inverted - docs_description: "Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY)." - docs_default_value: "OFF" + description: "Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY)." + default_value: "OFF" condition: USE_SERIAL_RX type: bool - name: rx_spi_protocol @@ -555,24 +555,24 @@ groups: min: 0 max: 8 - name: spektrum_sat_bind - docs_description: "0 = disabled. Used to bind the spektrum satellite to RX" - docs_default_value: "0" + description: "0 = disabled. Used to bind the spektrum satellite to RX" + default_value: "0" condition: USE_SPEKTRUM_BIND min: SPEKTRUM_SAT_BIND_DISABLED max: SPEKTRUM_SAT_BIND_MAX - name: rx_min_usec - docs_description: "Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc." - docs_default_value: "885" + description: "Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc." + default_value: "885" min: PWM_PULSE_MIN max: PWM_PULSE_MAX - name: rx_max_usec - docs_description: "Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of mid_rc." - docs_default_value: "2115" + description: "Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of mid_rc." + default_value: "2115" min: PWM_PULSE_MIN max: PWM_PULSE_MAX - name: serialrx_halfduplex - docs_description: "Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire" - docs_default_value: "OFF" + description: "Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire" + default_value: "OFF" field: halfDuplex type: bool - name: msp_override_channels @@ -587,25 +587,25 @@ groups: condition: USE_BLACKBOX members: - name: blackbox_rate_num - docs_description: "Blackbox logging rate numerator. Use num/denom settings to decide if a frame should be logged, allowing control of the portion of logged loop iterations" - docs_default_value: "1" + description: "Blackbox logging rate numerator. Use num/denom settings to decide if a frame should be logged, allowing control of the portion of logged loop iterations" + default_value: "1" field: rate_num min: 1 max: 65535 - name: blackbox_rate_denom - docs_description: "Blackbox logging rate denominator. See blackbox_rate_num." - docs_default_value: "1" + description: "Blackbox logging rate denominator. See blackbox_rate_num." + default_value: "1" field: rate_denom min: 1 max: 65535 - name: blackbox_device - docs_description: "Selection of where to write blackbox data" - docs_default_value: "SPIFLASH" + description: "Selection of where to write blackbox data" + default_value: "SPIFLASH" field: device table: blackbox_device - name: sdcard_detect_inverted - docs_description: "This setting drives the way SD card is detected in card slot. On some targets (AnyFC F7 clone) different card slot was used and depending of hardware revision ON or OFF setting might be required. If card is not detected, change this value." - docs_default_value: "`TARGET dependent`" + description: "This setting drives the way SD card is detected in card slot. On some targets (AnyFC F7 clone) different card slot was used and depending of hardware revision ON or OFF setting might be required. If card is not detected, change this value." + default_value: "`TARGET dependent`" field: invertedCardDetection condition: USE_SDCARD type: bool @@ -615,49 +615,49 @@ groups: headers: ["flight/mixer.h"] members: - name: max_throttle - docs_description: "This is the maximum value (in us) sent to esc when armed. Default of 1850 are OK for everyone (legacy). For modern ESCs, higher values (c. 2000) may be more appropriate. If you have brushed motors, the value should be set to 2000." - docs_default_value: "1850" + description: "This is the maximum value (in us) sent to esc when armed. Default of 1850 are OK for everyone (legacy). For modern ESCs, higher values (c. 2000) may be more appropriate. If you have brushed motors, the value should be set to 2000." + default_value: "1850" field: maxthrottle min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: min_command - docs_description: "This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly when powered up, try decreasing this value. It can also be used for calibrating all ESCs at once." - docs_default_value: "1000" + description: "This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly when powered up, try decreasing this value. It can also be used for calibrating all ESCs at once." + default_value: "1000" field: mincommand min: 0 max: PWM_RANGE_MAX - name: motor_pwm_rate - docs_description: "Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000." - docs_default_value: "400" + description: "Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000." + default_value: "400" field: motorPwmRate min: 50 max: 32000 - name: motor_accel_time - docs_description: "Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000]" - docs_default_value: "0" + description: "Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000]" + default_value: "0" field: motorAccelTimeMs min: 0 max: 1000 - name: motor_decel_time - docs_description: "Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000]" - docs_default_value: "0" + description: "Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000]" + default_value: "0" field: motorDecelTimeMs min: 0 max: 1000 - name: motor_pwm_protocol - docs_description: "Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED" - docs_default_value: "STANDARD" + description: "Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED" + default_value: "STANDARD" field: motorPwmProtocol table: motor_pwm_protocol - name: throttle_scale - docs_description: "Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50%" - docs_default_value: "1.000" + description: "Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50%" + default_value: "1.000" field: throttleScale min: 0 max: 1 - name: throttle_idle - docs_description: "The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle." - docs_default_value: "15" + description: "The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle." + default_value: "15" field: throttleIdle min: 4 max: 30 @@ -671,67 +671,67 @@ groups: headers: ["flight/failsafe.h"] members: - name: failsafe_delay - docs_description: "Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay)." - docs_default_value: "5" + description: "Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay)." + default_value: "5" min: 0 max: 200 - name: failsafe_recovery_delay - docs_description: "Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay)." - docs_default_value: "5" + description: "Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay)." + default_value: "5" min: 0 max: 200 - name: failsafe_off_delay - docs_description: "Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay)." - docs_default_value: "200" + description: "Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay)." + default_value: "200" min: 0 max: 200 - name: failsafe_throttle - docs_description: "Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle)." - docs_default_value: "1000" + description: "Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle)." + default_value: "1000" min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: failsafe_throttle_low_delay - docs_description: "If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout" - docs_default_value: "100" + description: "If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout" + default_value: "100" min: 0 max: 300 - name: failsafe_procedure - docs_description: "What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle)." - docs_default_value: "SET-THR" + description: "What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle)." + default_value: "SET-THR" table: failsafe_procedure - name: failsafe_stick_threshold - docs_description: "Threshold for stick motion to consider failsafe condition resolved. If non-zero failsafe won't clear even if RC link is restored - you have to move sticks to exit failsafe." - docs_default_value: "50" + description: "Threshold for stick motion to consider failsafe condition resolved. If non-zero failsafe won't clear even if RC link is restored - you have to move sticks to exit failsafe." + default_value: "50" field: failsafe_stick_motion_threshold min: 0 max: 500 - name: failsafe_fw_roll_angle - docs_description: "Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll" - docs_default_value: "-200" + description: "Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll" + default_value: "-200" min: -800 max: 800 - name: failsafe_fw_pitch_angle - docs_description: "Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb" - docs_default_value: "100" + description: "Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb" + default_value: "100" min: -800 max: 800 - name: failsafe_fw_yaw_rate - docs_description: "Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn" - docs_default_value: "-45" + description: "Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn" + default_value: "-45" min: -1000 max: 1000 - name: failsafe_min_distance - docs_description: "If failsafe happens when craft is closer than this distance in centimeters from home, failsafe will not execute regular failsafe_procedure, but will execute procedure specified in failsafe_min_distance_procedure instead. 0 = Normal failsafe_procedure always taken." - docs_default_value: "0" + description: "If failsafe happens when craft is closer than this distance in centimeters from home, failsafe will not execute regular failsafe_procedure, but will execute procedure specified in failsafe_min_distance_procedure instead. 0 = Normal failsafe_procedure always taken." + default_value: "0" min: 0 max: 65000 - name: failsafe_min_distance_procedure - docs_description: "What failsafe procedure to initiate in Stage 2 when craft is closer to home than failsafe_min_distance. See [Failsafe documentation](Failsafe.md#failsafe_throttle)." - docs_default_value: "DROP" + description: "What failsafe procedure to initiate in Stage 2 when craft is closer to home than failsafe_min_distance. See [Failsafe documentation](Failsafe.md#failsafe_throttle)." + default_value: "DROP" table: failsafe_procedure - name: failsafe_mission - docs_description: "If set to `OFF` the failsafe procedure won't be triggered and the mission will continue if the FC is in WP (automatic mission) mode" - docs_default_value: "ON" + description: "If set to `OFF` the failsafe procedure won't be triggered and the mission will continue if the FC is in WP (automatic mission) mode" + default_value: "ON" type: bool - name: PG_LIGHTS_CONFIG @@ -740,19 +740,19 @@ groups: condition: USE_LIGHTS members: - name: failsafe_lights - docs_description: "Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]." - docs_default_value: "ON" + description: "Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]." + default_value: "ON" field: failsafe.enabled type: bool - name: failsafe_lights_flash_period - docs_description: "Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]." - docs_default_value: "1000" + description: "Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]." + default_value: "1000" field: failsafe.flash_period min: 40 max: 65535 - name: failsafe_lights_flash_on_time - docs_description: "Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]." - docs_default_value: "100" + description: "Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]." + default_value: "100" field: failsafe.flash_on_time min: 20 max: 65535 @@ -762,20 +762,20 @@ groups: headers: ["sensors/boardalignment.h"] members: - name: align_board_roll - docs_description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc" - docs_default_value: "0" + description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc" + default_value: "0" field: rollDeciDegrees min: -1800 max: 3600 - name: align_board_pitch - docs_description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc" - docs_default_value: "0" + description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc" + default_value: "0" field: pitchDeciDegrees min: -1800 max: 3600 - name: align_board_yaw - docs_description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc" - docs_default_value: "0" + description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc" + default_value: "0" field: yawDeciDegrees min: -1800 max: 3600 @@ -785,62 +785,62 @@ groups: headers: ["sensors/battery.h"] members: - name: vbat_meter_type - docs_description: "Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running" - docs_default_value: "`ADC`" + description: "Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running" + default_value: "`ADC`" field: voltage.type table: voltage_sensor type: uint8_t - name: vbat_scale - docs_description: "Battery voltage calibration value. 1100 = 11:1 voltage divider (10k:1k) x 100. Adjust this slightly if reported pack voltage is different from multimeter reading. You can get current voltage by typing \"status\" in cli." - docs_default_value: "1100" + description: "Battery voltage calibration value. 1100 = 11:1 voltage divider (10k:1k) x 100. Adjust this slightly if reported pack voltage is different from multimeter reading. You can get current voltage by typing \"status\" in cli." + default_value: "1100" field: voltage.scale condition: USE_ADC min: VBAT_SCALE_MIN max: VBAT_SCALE_MAX - name: current_meter_scale - docs_description: "This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt." - docs_default_value: "400" + description: "This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt." + default_value: "400" field: current.scale min: -10000 max: 10000 - name: current_meter_offset - docs_description: "This sets the output offset voltage of the current sensor in millivolts." - docs_default_value: "0" + description: "This sets the output offset voltage of the current sensor in millivolts." + default_value: "0" field: current.offset min: -32768 max: 32767 - name: current_meter_type - docs_description: "ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position." - docs_default_value: "ADC" + description: "ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position." + default_value: "ADC" field: current.type table: current_sensor type: uint8_t - name: bat_voltage_src - docs_description: "Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP`" - docs_default_value: "RAW" + description: "Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP`" + default_value: "RAW" field: voltageSource table: bat_voltage_source type: uint8_t - name: cruise_power - docs_description: "Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit" - docs_default_value: "0" + description: "Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit" + default_value: "0" field: cruise_power min: 0 max: 4294967295 - name: idle_power - docs_description: "Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit" - docs_default_value: "0" + description: "Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit" + default_value: "0" field: idle_power min: 0 max: 65535 - name: rth_energy_margin - docs_description: "Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation" - docs_default_value: "5" + description: "Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation" + default_value: "5" min: 0 max: 100 - name: thr_comp_weight - docs_description: "Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage)" - docs_default_value: "0.692" + description: "Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage)" + default_value: "0.692" field: throttle_compensation_weight min: 0 max: 2 @@ -851,61 +851,61 @@ groups: value_type: BATTERY_CONFIG_VALUE members: - name: bat_cells - docs_description: "Number of cells of the battery (0 = autodetect), see battery documentation" - docs_default_value: "0" + description: "Number of cells of the battery (0 = autodetect), see battery documentation" + default_value: "0" field: cells condition: USE_ADC min: 0 max: 8 - name: vbat_cell_detect_voltage - docs_description: "Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units, default is 4.30V" - docs_default_value: "430" + description: "Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units, default is 4.30V" + default_value: "430" field: voltage.cellDetect condition: USE_ADC min: 100 max: 500 - name: vbat_max_cell_voltage - docs_description: "Maximum voltage per cell in 0.01V units, default is 4.20V" - docs_default_value: "420" + description: "Maximum voltage per cell in 0.01V units, default is 4.20V" + default_value: "420" field: voltage.cellMax condition: USE_ADC min: 100 max: 500 - name: vbat_min_cell_voltage - docs_description: "Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V)" - docs_default_value: "330" + description: "Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V)" + default_value: "330" field: voltage.cellMin condition: USE_ADC min: 100 max: 500 - name: vbat_warning_cell_voltage - docs_description: "Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V)" - docs_default_value: "350" + description: "Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V)" + default_value: "350" field: voltage.cellWarning condition: USE_ADC min: 100 max: 500 - name: battery_capacity - docs_description: "Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity." - docs_default_value: "0" + description: "Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity." + default_value: "0" field: capacity.value min: 0 max: 4294967295 - name: battery_capacity_warning - docs_description: "If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink." - docs_default_value: "0" + description: "If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink." + default_value: "0" field: capacity.warning min: 0 max: 4294967295 - name: battery_capacity_critical - docs_description: "If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps." - docs_default_value: "0" + description: "If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps." + default_value: "0" field: capacity.critical min: 0 max: 4294967295 - name: battery_capacity_unit - docs_description: "Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour)." - docs_default_value: "MAH" + description: "Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour)." + default_value: "MAH" field: capacity.unit table: bat_capacity_unit type: uint8_t @@ -914,30 +914,30 @@ groups: type: mixerConfig_t members: - name: motor_direction_inverted - docs_description: "Use if you need to inverse yaw motor direction." - docs_default_value: "OFF" + description: "Use if you need to inverse yaw motor direction." + default_value: "OFF" field: motorDirectionInverted type: bool - name: platform_type - docs_description: "Defines UAV platform type. Allowed values: \"MULTIROTOR\", \"AIRPLANE\", \"HELICOPTER\", \"TRICOPTER\", \"ROVER\", \"BOAT\". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented" - docs_default_value: "\"MULTIROTOR\"" + description: "Defines UAV platform type. Allowed values: \"MULTIROTOR\", \"AIRPLANE\", \"HELICOPTER\", \"TRICOPTER\", \"ROVER\", \"BOAT\". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented" + default_value: "\"MULTIROTOR\"" field: platformType type: uint8_t table: platform_type - name: has_flaps - docs_description: "Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot" - docs_default_value: "OFF" + description: "Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot" + default_value: "OFF" field: hasFlaps type: bool - name: model_preview_type - docs_description: "ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons." - docs_default_value: "-1" + description: "ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons." + default_value: "-1" field: appliedMixerPreset min: -1 max: INT16_MAX - name: fw_min_throttle_down_pitch - docs_description: "Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)" - docs_default_value: "0" + description: "Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)" + default_value: "0" field: fwMinThrottleDownPitchAngle min: 0 max: 450 @@ -946,20 +946,20 @@ groups: type: reversibleMotorsConfig_t members: - name: 3d_deadband_low - docs_description: "Low value of throttle deadband for 3D mode (when stick is in the 3d_deadband_throttle range, the fixed values of 3d_deadband_low / _high are used instead)" - docs_default_value: "1406" + description: "Low value of throttle deadband for 3D mode (when stick is in the 3d_deadband_throttle range, the fixed values of 3d_deadband_low / _high are used instead)" + default_value: "1406" field: deadband_low min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: 3d_deadband_high - docs_description: "High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead)" - docs_default_value: "1514" + description: "High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead)" + default_value: "1514" field: deadband_high min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: 3d_neutral - docs_description: "Neutral (stop) throttle value for 3D mode" - docs_default_value: "1460" + description: "Neutral (stop) throttle value for 3D mode" + default_value: "1460" field: neutral min: PWM_RANGE_MIN max: PWM_RANGE_MAX @@ -969,36 +969,36 @@ groups: headers: ["flight/servos.h"] members: - name: servo_protocol - docs_description: "An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SERVO_DRIVER` (I2C PCA9685 peripheral), `SBUS` (S.Bus protocol output via a configured serial port)" - docs_default_value: "PWM" + description: "An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SERVO_DRIVER` (I2C PCA9685 peripheral), `SBUS` (S.Bus protocol output via a configured serial port)" + default_value: "PWM" field: servo_protocol table: servo_protocol - name: servo_center_pulse - docs_description: "Servo midpoint" - docs_default_value: "1500" + description: "Servo midpoint" + default_value: "1500" field: servoCenterPulse min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: servo_pwm_rate - docs_description: "Output frequency (in Hz) servo pins. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz." - docs_default_value: "50" + description: "Output frequency (in Hz) servo pins. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz." + default_value: "50" field: servoPwmRate min: 50 max: 498 - name: servo_lpf_hz - docs_description: "Selects the servo PWM output cutoff frequency. Value is in [Hz]" - docs_default_value: "20" + description: "Selects the servo PWM output cutoff frequency. Value is in [Hz]" + default_value: "20" field: servo_lowpass_freq min: 0 max: 400 - name: flaperon_throw_offset - docs_description: "Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated." - docs_default_value: "200" + description: "Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated." + default_value: "200" min: FLAPERON_THROW_MIN max: FLAPERON_THROW_MAX - name: tri_unarmed_servo - docs_description: "On tricopter mix only, if this is set to ON, servo will always be correcting regardless of armed state. to disable this, set it to OFF." - docs_default_value: "ON" + description: "On tricopter mix only, if this is set to ON, servo will always be correcting regardless of armed state. to disable this, set it to OFF." + default_value: "ON" type: bool - name: PG_CONTROL_RATE_PROFILES @@ -1007,94 +1007,94 @@ groups: value_type: CONTROL_RATE_VALUE members: - name: thr_mid - docs_description: "Throttle value when the stick is set to mid-position. Used in the throttle curve calculation." - docs_default_value: "50" + description: "Throttle value when the stick is set to mid-position. Used in the throttle curve calculation." + default_value: "50" field: throttle.rcMid8 min: 0 max: 100 - name: thr_expo - docs_description: "Throttle exposition value" - docs_default_value: "0" + description: "Throttle exposition value" + default_value: "0" field: throttle.rcExpo8 min: 0 max: 100 - name: tpa_rate - docs_description: "Throttle PID attenuation reduces influence of P on ROLL and PITCH as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate." - docs_default_value: "0" + description: "Throttle PID attenuation reduces influence of P on ROLL and PITCH as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate." + default_value: "0" field: throttle.dynPID min: 0 max: CONTROL_RATE_CONFIG_TPA_MAX - name: tpa_breakpoint - docs_description: "See tpa_rate." - docs_default_value: "1500" + description: "See tpa_rate." + default_value: "1500" field: throttle.pa_breakpoint min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: fw_tpa_time_constant - docs_description: "TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. Planes with low thrust/weight ratio generally need higher time constant. Default is zero for compatibility with old setups" - docs_default_value: "0" + description: "TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. Planes with low thrust/weight ratio generally need higher time constant. Default is zero for compatibility with old setups" + default_value: "0" field: throttle.fixedWingTauMs min: 0 max: 5000 - name: rc_expo - docs_description: "Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`)" - docs_default_value: "70" + description: "Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`)" + default_value: "70" field: stabilized.rcExpo8 min: 0 max: 100 - name: rc_yaw_expo - docs_description: "Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`)" - docs_default_value: "20" + description: "Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`)" + default_value: "20" field: stabilized.rcYawExpo8 min: 0 max: 100 # New rates are in dps/10. That means, Rate of 20 means 200dps of rotation speed on given axis. # Rate 180 (1800dps) is max. value gyro can measure reliably - name: roll_rate - docs_description: "Defines rotation rate on ROLL axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure." - docs_default_value: "20" + description: "Defines rotation rate on ROLL axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure." + default_value: "20" field: stabilized.rates[FD_ROLL] min: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN max: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX - name: pitch_rate - docs_description: "Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure." - docs_default_value: "20" + description: "Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure." + default_value: "20" field: stabilized.rates[FD_PITCH] min: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN max: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX - name: yaw_rate - docs_description: "Defines rotation rate on YAW axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure." - docs_default_value: "20" + description: "Defines rotation rate on YAW axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure." + default_value: "20" field: stabilized.rates[FD_YAW] min: CONTROL_RATE_CONFIG_YAW_RATE_MIN max: CONTROL_RATE_CONFIG_YAW_RATE_MAX - name: manual_rc_expo - docs_description: "Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100]" - docs_default_value: "70" + description: "Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100]" + default_value: "70" field: manual.rcExpo8 min: 0 max: 100 - name: manual_rc_yaw_expo - docs_description: "Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100]" - docs_default_value: "20" + description: "Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100]" + default_value: "20" field: manual.rcYawExpo8 min: 0 max: 100 - name: manual_roll_rate - docs_description: "Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]%" - docs_default_value: "100" + description: "Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]%" + default_value: "100" field: manual.rates[FD_ROLL] min: 0 max: 100 - name: manual_pitch_rate - docs_description: "Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]%" - docs_default_value: "100" + description: "Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]%" + default_value: "100" field: manual.rates[FD_PITCH] min: 0 max: 100 - name: manual_yaw_rate - docs_description: "Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]%" - docs_default_value: "100" + description: "Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]%" + default_value: "100" field: manual.rates[FD_YAW] min: 0 max: 100 @@ -1108,8 +1108,8 @@ groups: headers: ["io/serial.h"] members: - name: reboot_character - docs_description: "Special character used to trigger reboot" - docs_default_value: "82" + description: "Special character used to trigger reboot" + default_value: "82" min: 48 max: 126 @@ -1118,39 +1118,39 @@ groups: headers: ["flight/imu.h"] members: - name: imu_dcm_kp - docs_description: "Inertial Measurement Unit KP Gain for accelerometer measurements" - docs_default_value: "2500" + description: "Inertial Measurement Unit KP Gain for accelerometer measurements" + default_value: "2500" field: dcm_kp_acc max: UINT16_MAX - name: imu_dcm_ki - docs_description: "Inertial Measurement Unit KI Gain for accelerometer measurements" - docs_default_value: "50" + description: "Inertial Measurement Unit KI Gain for accelerometer measurements" + default_value: "50" field: dcm_ki_acc max: UINT16_MAX - name: imu_dcm_kp_mag - docs_description: "Inertial Measurement Unit KP Gain for compass measurements" - docs_default_value: "10000" + description: "Inertial Measurement Unit KP Gain for compass measurements" + default_value: "10000" field: dcm_kp_mag max: UINT16_MAX - name: imu_dcm_ki_mag - docs_description: "Inertial Measurement Unit KI Gain for compass measurements" - docs_default_value: "0" + description: "Inertial Measurement Unit KI Gain for compass measurements" + default_value: "0" field: dcm_ki_mag max: UINT16_MAX - name: small_angle - docs_description: "If the aircraft tilt angle exceed this value the copter will refuse to arm." - docs_default_value: "25" + description: "If the aircraft tilt angle exceed this value the copter will refuse to arm." + default_value: "25" min: 0 max: 180 - name: imu_acc_ignore_rate - docs_description: "Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes" - docs_default_value: "0" + description: "Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes" + default_value: "0" field: acc_ignore_rate min: 0 max: 20 - name: imu_acc_ignore_slope - docs_description: "Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight)" - docs_default_value: "0" + description: "Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight)" + default_value: "0" field: acc_ignore_slope min: 0 max: 5 @@ -1159,16 +1159,16 @@ groups: type: armingConfig_t members: - name: fixed_wing_auto_arm - docs_description: "Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured." - docs_default_value: "OFF" + description: "Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured." + default_value: "OFF" type: bool - name: disarm_kill_switch - docs_description: "Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel." - docs_default_value: "ON" + description: "Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel." + default_value: "ON" type: bool - name: switch_disarm_delay - docs_description: "Delay before disarming when requested by switch (ms) [0-1000]" - docs_default_value: "250" + description: "Delay before disarming when requested by switch (ms) [0-1000]" + default_value: "250" field: switchDisarmDelayMs min: 0 max: 1000 @@ -1187,27 +1187,27 @@ groups: type: rpmFilterConfig_t members: - name: rpm_gyro_filter_enabled - docs_description: "Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV" - docs_default_value: "`OFF`" + description: "Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV" + default_value: "`OFF`" field: gyro_filter_enabled type: bool - name: rpm_gyro_harmonics - docs_description: "Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine" - docs_default_value: "1" + description: "Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine" + default_value: "1" field: gyro_harmonics type: uint8_t min: 1 max: 3 - name: rpm_gyro_min_hz - docs_description: "The lowest frequency for gyro RPM filtere. Default `150` is fine for 5\" mini-quads. On 7-inch drones you can lower even down to `60`-`70`" - docs_default_value: "150" + description: "The lowest frequency for gyro RPM filtere. Default `150` is fine for 5\" mini-quads. On 7-inch drones you can lower even down to `60`-`70`" + default_value: "150" field: gyro_min_hz type: uint8_t min: 30 max: 200 - name: rpm_gyro_q - docs_description: "Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting" - docs_default_value: "500" + description: "Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting" + default_value: "500" field: gyro_q type: uint16_t min: 1 @@ -1217,41 +1217,41 @@ groups: condition: USE_GPS members: - name: gps_provider - docs_description: "Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N)." - docs_default_value: "UBLOX" + description: "Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N)." + default_value: "UBLOX" field: provider table: gps_provider type: uint8_t - name: gps_sbas_mode - docs_description: "Which SBAS mode to be used" - docs_default_value: "NONE" + description: "Which SBAS mode to be used" + default_value: "NONE" field: sbasMode table: gps_sbas_mode type: uint8_t - name: gps_dyn_model - docs_description: "GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying." - docs_default_value: "AIR_1G" + description: "GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying." + default_value: "AIR_1G" field: dynModel table: gps_dyn_model type: uint8_t - name: gps_auto_config - docs_description: "Enable automatic configuration of UBlox GPS receivers." - docs_default_value: "ON" + description: "Enable automatic configuration of UBlox GPS receivers." + default_value: "ON" field: autoConfig type: bool - name: gps_auto_baud - docs_description: "Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS. When used with NAZA/DJI it will automatic detect GPS baudrate and change to it, ignoring the selected baudrate set in ports" - docs_default_value: "ON" + description: "Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS. When used with NAZA/DJI it will automatic detect GPS baudrate and change to it, ignoring the selected baudrate set in ports" + default_value: "ON" field: autoBaud type: bool - name: gps_ublox_use_galileo - docs_description: "Enable use of Galileo satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires M8N and Ublox firmware 3.x (or later) [OFF/ON]." - docs_default_value: "OFF" + description: "Enable use of Galileo satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires M8N and Ublox firmware 3.x (or later) [OFF/ON]." + default_value: "OFF" field: ubloxUseGalileo type: bool - name: gps_min_sats - docs_description: "Minimum number of GPS satellites in view to acquire GPS_FIX and consider GPS position valid. Some GPS receivers appeared to be very inaccurate with low satellite count." - docs_default_value: "6" + description: "Minimum number of GPS satellites in view to acquire GPS_FIX and consider GPS position valid. Some GPS receivers appeared to be very inaccurate with low satellite count." + default_value: "6" field: gpsMinSats min: 5 max: 10 @@ -1261,39 +1261,39 @@ groups: headers: ["fc/rc_controls.h"] members: - name: deadband - docs_description: "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle." - docs_default_value: "5" + description: "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle." + default_value: "5" min: 0 max: 32 - name: yaw_deadband - docs_description: "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle." - docs_default_value: "5" + description: "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle." + default_value: "5" min: 0 max: 100 - name: pos_hold_deadband - docs_description: "Stick deadband in [r/c points], applied after r/c deadband and expo" - docs_default_value: "20" + description: "Stick deadband in [r/c points], applied after r/c deadband and expo" + default_value: "20" min: 2 max: 250 - name: alt_hold_deadband - docs_description: "Defines the deadband of throttle during alt_hold [r/c points]" - docs_default_value: "50" + description: "Defines the deadband of throttle during alt_hold [r/c points]" + default_value: "50" min: 10 max: 250 - name: 3d_deadband_throttle - docs_description: "Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter." - docs_default_value: "50" + description: "Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter." + default_value: "50" field: mid_throttle_deadband min: 0 max: 200 - name: mc_airmode_type - docs_description: "Defines the Airmode state handling type for Multirotors. Default **STICK_CENTER** is the classical approach in which Airmode is always active if enabled, but when the throttle is low and ROLL/PITCH/YAW sticks are centered, Iterms is not allowed to grow (ANTI_WINDUP). **THROTTLE_THRESHOLD** is the Airmode behavior known from Betaflight. In this mode, Airmode is active as soon THROTTLE position is above `mc_airmode_threshold` and stays active until disarm. ANTI_WINDUP is never triggered. For small Multirotors (up to 7-inch propellers) it is suggested to switch to **THROTTLE_THRESHOLD** since it keeps full stabilization no matter what pilot does with the sticks. Fixed Wings always use **STICK_CENTER** mode." - docs_default_value: "STICK_CENTER" + description: "Defines the Airmode state handling type for Multirotors. Default **STICK_CENTER** is the classical approach in which Airmode is always active if enabled, but when the throttle is low and ROLL/PITCH/YAW sticks are centered, Iterms is not allowed to grow (ANTI_WINDUP). **THROTTLE_THRESHOLD** is the Airmode behavior known from Betaflight. In this mode, Airmode is active as soon THROTTLE position is above `mc_airmode_threshold` and stays active until disarm. ANTI_WINDUP is never triggered. For small Multirotors (up to 7-inch propellers) it is suggested to switch to **THROTTLE_THRESHOLD** since it keeps full stabilization no matter what pilot does with the sticks. Fixed Wings always use **STICK_CENTER** mode." + default_value: "STICK_CENTER" field: airmodeHandlingType table: airmodeHandlingType - name: mc_airmode_threshold - docs_description: "Defines airmode THROTTLE activation threshold when `mc_airmode_type` **THROTTLE_THRESHOLD** is used" - docs_default_value: "1300" + description: "Defines airmode THROTTLE activation threshold when `mc_airmode_type` **THROTTLE_THRESHOLD** is used" + default_value: "1300" field: airmodeThrottleThreshold min: 1000 max: 2000 @@ -1304,320 +1304,320 @@ groups: value_type: PROFILE_VALUE members: - name: mc_p_pitch - docs_description: "Multicopter rate stabilisation P-gain for PITCH" - docs_default_value: "40" + description: "Multicopter rate stabilisation P-gain for PITCH" + default_value: "40" field: bank_mc.pid[PID_PITCH].P min: 0 max: 200 - name: mc_i_pitch - docs_description: "Multicopter rate stabilisation I-gain for PITCH" - docs_default_value: "30" + description: "Multicopter rate stabilisation I-gain for PITCH" + default_value: "30" field: bank_mc.pid[PID_PITCH].I min: 0 max: 200 - name: mc_d_pitch - docs_description: "Multicopter rate stabilisation D-gain for PITCH" - docs_default_value: "23" + description: "Multicopter rate stabilisation D-gain for PITCH" + default_value: "23" field: bank_mc.pid[PID_PITCH].D min: 0 max: 200 - name: mc_cd_pitch - docs_description: "Multicopter Control Derivative gain for PITCH" - docs_default_value: "60" + description: "Multicopter Control Derivative gain for PITCH" + default_value: "60" field: bank_mc.pid[PID_PITCH].FF min: 0 max: 200 - name: mc_p_roll - docs_description: "Multicopter rate stabilisation P-gain for ROLL" - docs_default_value: "40" + description: "Multicopter rate stabilisation P-gain for ROLL" + default_value: "40" field: bank_mc.pid[PID_ROLL].P min: 0 max: 200 - name: mc_i_roll - docs_description: "Multicopter rate stabilisation I-gain for ROLL" - docs_default_value: "30" + description: "Multicopter rate stabilisation I-gain for ROLL" + default_value: "30" field: bank_mc.pid[PID_ROLL].I min: 0 max: 200 - name: mc_d_roll - docs_description: "Multicopter rate stabilisation D-gain for ROLL" - docs_default_value: "23" + description: "Multicopter rate stabilisation D-gain for ROLL" + default_value: "23" field: bank_mc.pid[PID_ROLL].D min: 0 max: 200 - name: mc_cd_roll - docs_description: "Multicopter Control Derivative gain for ROLL" - docs_default_value: "60" + description: "Multicopter Control Derivative gain for ROLL" + default_value: "60" field: bank_mc.pid[PID_ROLL].FF min: 0 max: 200 - name: mc_p_yaw - docs_description: "Multicopter rate stabilisation P-gain for YAW" - docs_default_value: "85" + description: "Multicopter rate stabilisation P-gain for YAW" + default_value: "85" field: bank_mc.pid[PID_YAW].P min: 0 max: 200 - name: mc_i_yaw - docs_description: "Multicopter rate stabilisation I-gain for YAW" - docs_default_value: "45" + description: "Multicopter rate stabilisation I-gain for YAW" + default_value: "45" field: bank_mc.pid[PID_YAW].I min: 0 max: 200 - name: mc_d_yaw - docs_description: "Multicopter rate stabilisation D-gain for YAW" - docs_default_value: "0" + description: "Multicopter rate stabilisation D-gain for YAW" + default_value: "0" field: bank_mc.pid[PID_YAW].D min: 0 max: 200 - name: mc_cd_yaw - docs_description: "Multicopter Control Derivative gain for YAW" - docs_default_value: "60" + description: "Multicopter Control Derivative gain for YAW" + default_value: "60" field: bank_mc.pid[PID_YAW].FF min: 0 max: 200 - name: mc_p_level - docs_description: "Multicopter attitude stabilisation P-gain" - docs_default_value: "20" + description: "Multicopter attitude stabilisation P-gain" + default_value: "20" field: bank_mc.pid[PID_LEVEL].P min: 0 max: 200 - name: mc_i_level - docs_description: "Multicopter attitude stabilisation low-pass filter cutoff" - docs_default_value: "15" + description: "Multicopter attitude stabilisation low-pass filter cutoff" + default_value: "15" field: bank_mc.pid[PID_LEVEL].I min: 0 max: 200 - name: mc_d_level - docs_description: "Multicopter attitude stabilisation HORIZON transition point" - docs_default_value: "75" + description: "Multicopter attitude stabilisation HORIZON transition point" + default_value: "75" field: bank_mc.pid[PID_LEVEL].D min: 0 max: 200 - name: fw_p_pitch - docs_description: "Fixed-wing rate stabilisation P-gain for PITCH" - docs_default_value: "5" + description: "Fixed-wing rate stabilisation P-gain for PITCH" + default_value: "5" field: bank_fw.pid[PID_PITCH].P min: 0 max: 200 - name: fw_i_pitch - docs_description: "Fixed-wing rate stabilisation I-gain for PITCH" - docs_default_value: "7" + description: "Fixed-wing rate stabilisation I-gain for PITCH" + default_value: "7" field: bank_fw.pid[PID_PITCH].I min: 0 max: 200 - name: fw_ff_pitch - docs_description: "Fixed-wing rate stabilisation FF-gain for PITCH" - docs_default_value: "50" + description: "Fixed-wing rate stabilisation FF-gain for PITCH" + default_value: "50" field: bank_fw.pid[PID_PITCH].FF min: 0 max: 200 - name: fw_p_roll - docs_description: "Fixed-wing rate stabilisation P-gain for ROLL" - docs_default_value: "5" + description: "Fixed-wing rate stabilisation P-gain for ROLL" + default_value: "5" field: bank_fw.pid[PID_ROLL].P min: 0 max: 200 - name: fw_i_roll - docs_description: "Fixed-wing rate stabilisation I-gain for ROLL" - docs_default_value: "7" + description: "Fixed-wing rate stabilisation I-gain for ROLL" + default_value: "7" field: bank_fw.pid[PID_ROLL].I min: 0 max: 200 - name: fw_ff_roll - docs_description: "Fixed-wing rate stabilisation FF-gain for ROLL" - docs_default_value: "50" + description: "Fixed-wing rate stabilisation FF-gain for ROLL" + default_value: "50" field: bank_fw.pid[PID_ROLL].FF min: 0 max: 200 - name: fw_p_yaw - docs_description: "Fixed-wing rate stabilisation P-gain for YAW" - docs_default_value: "6" + description: "Fixed-wing rate stabilisation P-gain for YAW" + default_value: "6" field: bank_fw.pid[PID_YAW].P min: 0 max: 200 - name: fw_i_yaw - docs_description: "Fixed-wing rate stabilisation I-gain for YAW" - docs_default_value: "10" + description: "Fixed-wing rate stabilisation I-gain for YAW" + default_value: "10" field: bank_fw.pid[PID_YAW].I min: 0 max: 200 - name: fw_ff_yaw - docs_description: "Fixed-wing rate stabilisation FF-gain for YAW" - docs_default_value: "60" + description: "Fixed-wing rate stabilisation FF-gain for YAW" + default_value: "60" field: bank_fw.pid[PID_YAW].FF min: 0 max: 200 - name: fw_p_level - docs_description: "Fixed-wing attitude stabilisation P-gain" - docs_default_value: "20" + description: "Fixed-wing attitude stabilisation P-gain" + default_value: "20" field: bank_fw.pid[PID_LEVEL].P min: 0 max: 200 - name: fw_i_level - docs_description: "Fixed-wing attitude stabilisation low-pass filter cutoff" - docs_default_value: "5" + description: "Fixed-wing attitude stabilisation low-pass filter cutoff" + default_value: "5" field: bank_fw.pid[PID_LEVEL].I min: 0 max: 200 - name: fw_d_level - docs_description: "Fixed-wing attitude stabilisation HORIZON transition point" - docs_default_value: "75" + description: "Fixed-wing attitude stabilisation HORIZON transition point" + default_value: "75" field: bank_fw.pid[PID_LEVEL].D min: 0 max: 200 - name: max_angle_inclination_rll - docs_description: "Maximum inclination in level (angle) mode (ROLL axis). 100=10°" - docs_default_value: "300" + description: "Maximum inclination in level (angle) mode (ROLL axis). 100=10°" + default_value: "300" field: max_angle_inclination[FD_ROLL] min: 100 max: 900 - name: max_angle_inclination_pit - docs_description: "Maximum inclination in level (angle) mode (PITCH axis). 100=10°" - docs_default_value: "300" + description: "Maximum inclination in level (angle) mode (PITCH axis). 100=10°" + default_value: "300" field: max_angle_inclination[FD_PITCH] min: 100 max: 900 - name: dterm_lpf_hz - docs_description: "Dterm low pass filter cutoff frequency. Default setting is very conservative and small multirotors should use higher value between 80 and 100Hz. 80 seems like a gold spot for 7-inch builds while 100 should work best with 5-inch machines. If motors are getting too hot, lower the value" - docs_default_value: "40" + description: "Dterm low pass filter cutoff frequency. Default setting is very conservative and small multirotors should use higher value between 80 and 100Hz. 80 seems like a gold spot for 7-inch builds while 100 should work best with 5-inch machines. If motors are getting too hot, lower the value" + default_value: "40" min: 0 max: 500 - name: dterm_lpf_type - docs_description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation." - docs_default_value: "`BIQUAD`" + description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation." + default_value: "`BIQUAD`" field: dterm_lpf_type table: filter_type - name: dterm_lpf2_hz - docs_description: "Cutoff frequency for stage 2 D-term low pass filter" - docs_default_value: "0" + description: "Cutoff frequency for stage 2 D-term low pass filter" + default_value: "0" min: 0 max: 500 - name: dterm_lpf2_type - docs_description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation." - docs_default_value: "`BIQUAD`" + description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation." + default_value: "`BIQUAD`" field: dterm_lpf2_type table: filter_type - name: yaw_lpf_hz - docs_description: "Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below)" - docs_default_value: "30" + description: "Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below)" + default_value: "30" min: 0 max: 200 - name: fw_iterm_throw_limit - docs_description: "Limits max/min I-term value in stabilization PID controller in case of Fixed Wing. It solves the problem of servo saturation before take-off/throwing the airplane into the air. By default, error accumulated in I-term can not exceed 1/3 of servo throw (around 165us). Set 0 to disable completely." - docs_default_value: "165" + description: "Limits max/min I-term value in stabilization PID controller in case of Fixed Wing. It solves the problem of servo saturation before take-off/throwing the airplane into the air. By default, error accumulated in I-term can not exceed 1/3 of servo throw (around 165us). Set 0 to disable completely." + default_value: "165" field: fixedWingItermThrowLimit min: FW_ITERM_THROW_LIMIT_MIN max: FW_ITERM_THROW_LIMIT_MAX - name: fw_loiter_direction - docs_description: "Direction of loitering: center point on right wing (clockwise - default), or center point on left wing (counterclockwise). If equal YAW then can be changed in flight using a yaw stick." - docs_default_value: "RIGHT" + description: "Direction of loitering: center point on right wing (clockwise - default), or center point on left wing (counterclockwise). If equal YAW then can be changed in flight using a yaw stick." + default_value: "RIGHT" field: loiter_direction condition: USE_NAV table: direction - name: fw_reference_airspeed - docs_description: "Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present." - docs_default_value: "1000" + description: "Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present." + default_value: "1000" field: fixedWingReferenceAirspeed min: 1 max: 5000 - name: fw_turn_assist_yaw_gain - docs_description: "Gain required to keep the yaw rate consistent with the turn rate for a coordinated turn (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter" - docs_default_value: "1" + description: "Gain required to keep the yaw rate consistent with the turn rate for a coordinated turn (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter" + default_value: "1" field: fixedWingCoordinatedYawGain min: 0 max: 2 - name: fw_iterm_limit_stick_position - docs_description: "Iterm is not allowed to grow when stick position is above threshold. This solves the problem of bounceback or followthrough when full stick deflection is applied on poorely tuned fixed wings. In other words, stabilization is partialy disabled when pilot is actively controlling the aircraft and active when sticks are not touched. `0` mean stick is in center position, `1` means it is fully deflected to either side" - docs_default_value: "0.5" + description: "Iterm is not allowed to grow when stick position is above threshold. This solves the problem of bounceback or followthrough when full stick deflection is applied on poorely tuned fixed wings. In other words, stabilization is partialy disabled when pilot is actively controlling the aircraft and active when sticks are not touched. `0` mean stick is in center position, `1` means it is fully deflected to either side" + default_value: "0.5" field: fixedWingItermLimitOnStickPosition min: 0 max: 1 - name: pidsum_limit - docs_description: "A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help" - docs_default_value: "500" + description: "A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help" + default_value: "500" field: pidSumLimit min: PID_SUM_LIMIT_MIN max: PID_SUM_LIMIT_MAX - name: pidsum_limit_yaw - docs_description: "A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help" - docs_default_value: "400" + description: "A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help" + default_value: "400" field: pidSumLimitYaw min: PID_SUM_LIMIT_MIN max: PID_SUM_LIMIT_MAX - name: iterm_windup - docs_description: "Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter)" - docs_default_value: "50" + description: "Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter)" + default_value: "50" field: itermWindupPointPercent min: 0 max: 90 - name: rate_accel_limit_roll_pitch - docs_description: "Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting." - docs_default_value: "0" + description: "Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting." + default_value: "0" field: axisAccelerationLimitRollPitch max: 500000 - name: rate_accel_limit_yaw - docs_description: "Limits acceleration of YAW rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 180 dps^2). When set correctly, it greatly improves stopping performance and general stability during yaw turns. Value of 0 disables limiting." - docs_default_value: "10000" + description: "Limits acceleration of YAW rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 180 dps^2). When set correctly, it greatly improves stopping performance and general stability during yaw turns. Value of 0 disables limiting." + default_value: "10000" field: axisAccelerationLimitYaw max: 500000 - name: heading_hold_rate_limit - docs_description: "This setting limits yaw rotation rate that HEADING_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when HEADING_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes." - docs_default_value: "90" + description: "This setting limits yaw rotation rate that HEADING_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when HEADING_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes." + default_value: "90" min: HEADING_HOLD_RATE_LIMIT_MIN max: HEADING_HOLD_RATE_LIMIT_MAX - name: nav_mc_pos_z_p - docs_description: "P gain of altitude PID controller (Multirotor)" - docs_default_value: "50" + description: "P gain of altitude PID controller (Multirotor)" + default_value: "50" field: bank_mc.pid[PID_POS_Z].P condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_z_p - docs_description: "P gain of velocity PID controller" - docs_default_value: "100" + description: "P gain of velocity PID controller" + default_value: "100" field: bank_mc.pid[PID_VEL_Z].P condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_z_i - docs_description: "I gain of velocity PID controller" - docs_default_value: "50" + description: "I gain of velocity PID controller" + default_value: "50" field: bank_mc.pid[PID_VEL_Z].I condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_z_d - docs_description: "D gain of velocity PID controller" - docs_default_value: "10" + description: "D gain of velocity PID controller" + default_value: "10" field: bank_mc.pid[PID_VEL_Z].D condition: USE_NAV min: 0 max: 255 - name: nav_mc_pos_xy_p - docs_description: "Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity" - docs_default_value: "65" + description: "Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity" + default_value: "65" field: bank_mc.pid[PID_POS_XY].P condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_xy_p - docs_description: "P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause \"nervous\" behavior and oscillations" - docs_default_value: "40" + description: "P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause \"nervous\" behavior and oscillations" + default_value: "40" field: bank_mc.pid[PID_VEL_XY].P condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_xy_i - docs_description: "I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot" - docs_default_value: "15" + description: "I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot" + default_value: "15" field: bank_mc.pid[PID_VEL_XY].I condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_xy_d - docs_description: "D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target." - docs_default_value: "100" + description: "D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target." + default_value: "100" field: bank_mc.pid[PID_VEL_XY].D condition: USE_NAV min: 0 @@ -1628,8 +1628,8 @@ groups: min: 0 max: 255 - name: nav_mc_heading_p - docs_description: "P gain of Heading Hold controller (Multirotor)" - docs_default_value: "60" + description: "P gain of Heading Hold controller (Multirotor)" + default_value: "60" field: bank_mc.pid[PID_HEADING].P condition: USE_NAV min: 0 @@ -1639,78 +1639,78 @@ groups: min: 0 max: 100 - name: nav_fw_pos_z_p - docs_description: "P gain of altitude PID controller (Fixedwing)" - docs_default_value: "50" + description: "P gain of altitude PID controller (Fixedwing)" + default_value: "50" field: bank_fw.pid[PID_POS_Z].P condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_z_i - docs_description: "I gain of altitude PID controller (Fixedwing)" - docs_default_value: "0" + description: "I gain of altitude PID controller (Fixedwing)" + default_value: "0" field: bank_fw.pid[PID_POS_Z].I condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_z_d - docs_description: "D gain of altitude PID controller (Fixedwing)" - docs_default_value: "0" + description: "D gain of altitude PID controller (Fixedwing)" + default_value: "0" field: bank_fw.pid[PID_POS_Z].D condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_xy_p - docs_description: "P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH" - docs_default_value: "75" + description: "P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH" + default_value: "75" field: bank_fw.pid[PID_POS_XY].P condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_xy_i - docs_description: "I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero" - docs_default_value: "5" + description: "I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero" + default_value: "5" field: bank_fw.pid[PID_POS_XY].I condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_xy_d - docs_description: "D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero" - docs_default_value: "8" + description: "D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero" + default_value: "8" field: bank_fw.pid[PID_POS_XY].D condition: USE_NAV min: 0 max: 255 - name: nav_fw_heading_p - docs_description: "P gain of Heading Hold controller (Fixedwing)" - docs_default_value: "60" + description: "P gain of Heading Hold controller (Fixedwing)" + default_value: "60" field: bank_fw.pid[PID_HEADING].P condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_hdg_p - docs_description: "P gain of heading PID controller. (Fixedwing, rovers, boats)" - docs_default_value: "60" + description: "P gain of heading PID controller. (Fixedwing, rovers, boats)" + default_value: "60" field: bank_fw.pid[PID_POS_HEADING].P condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_hdg_i - docs_description: "I gain of heading trajectory PID controller. (Fixedwing, rovers, boats)" - docs_default_value: "0" + description: "I gain of heading trajectory PID controller. (Fixedwing, rovers, boats)" + default_value: "0" field: bank_fw.pid[PID_POS_HEADING].I condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_hdg_d - docs_description: "D gain of heading trajectory PID controller. (Fixedwing, rovers, boats)" - docs_default_value: "0" + description: "D gain of heading trajectory PID controller. (Fixedwing, rovers, boats)" + default_value: "0" field: bank_fw.pid[PID_POS_HEADING].D condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_hdg_pidsum_limit - docs_description: "Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats)" - docs_default_value: "350" + description: "Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats)" + default_value: "350" field: navFwPosHdgPidsumLimit min: PID_SUM_LIMIT_MIN max: PID_SUM_LIMIT_MAX @@ -1740,33 +1740,33 @@ groups: min: 10 max: 250 - name: antigravity_gain - docs_description: "Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements" - docs_default_value: "1" + description: "Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements" + default_value: "1" field: antigravityGain condition: USE_ANTIGRAVITY min: 1 max: 20 - name: antigravity_accelerator - docs_description: "" - docs_default_value: "1" + description: "" + default_value: "1" field: antigravityAccelerator condition: USE_ANTIGRAVITY min: 1 max: 20 - name: antigravity_cutoff_lpf_hz - docs_description: "Antigravity cutoff frequenct for Throtte filter. Antigravity is based on the difference between actual and filtered throttle input. The bigger is the difference, the bigger Antigravity gain" - docs_default_value: "15" + description: "Antigravity cutoff frequenct for Throtte filter. Antigravity is based on the difference between actual and filtered throttle input. The bigger is the difference, the bigger Antigravity gain" + default_value: "15" field: antigravityCutoff condition: USE_ANTIGRAVITY min: 1 max: 30 - name: pid_type - docs_description: "Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID`" + description: "Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID`" field: pidControllerType table: pidTypeTable - name: mc_cd_lpf_hz - docs_description: "Cutoff frequency for Control Derivative. Lower value smoother reaction on fast stick movements. With higher values, response will be more aggressive, jerky" - docs_default_value: "30" + description: "Cutoff frequency for Control Derivative. Lower value smoother reaction on fast stick movements. With higher values, response will be more aggressive, jerky" + default_value: "30" field: controlDerivativeLpfHz min: 0 max: 200 @@ -1776,32 +1776,32 @@ groups: condition: USE_NAV && USE_AUTOTUNE_FIXED_WING members: - name: fw_autotune_overshoot_time - docs_description: "Time [ms] to detect sustained overshoot" - docs_default_value: "100" + description: "Time [ms] to detect sustained overshoot" + default_value: "100" field: fw_overshoot_time min: 50 max: 500 - name: fw_autotune_undershoot_time - docs_description: "Time [ms] to detect sustained undershoot" - docs_default_value: "200" + description: "Time [ms] to detect sustained undershoot" + default_value: "200" field: fw_undershoot_time min: 50 max: 500 - name: fw_autotune_threshold - docs_description: "Threshold [%] of max rate to consider overshoot/undershoot detection" - docs_default_value: "50" + description: "Threshold [%] of max rate to consider overshoot/undershoot detection" + default_value: "50" field: fw_max_rate_threshold min: 0 max: 100 - name: fw_autotune_ff_to_p_gain - docs_description: "FF to P gain (strength relationship) [%]" - docs_default_value: "10" + description: "FF to P gain (strength relationship) [%]" + default_value: "10" field: fw_ff_to_p_gain min: 0 max: 100 - name: fw_autotune_ff_to_i_tc - docs_description: "FF to I time (defines time for I to reach the same level of response as FF) [ms]" - docs_default_value: "600" + description: "FF to I time (defines time for I to reach the same level of response as FF) [ms]" + default_value: "600" field: fw_ff_to_i_time_constant min: 100 max: 5000 @@ -1811,37 +1811,37 @@ groups: condition: USE_NAV members: - name: inav_auto_mag_decl - docs_description: "Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored." - docs_default_value: "ON" + description: "Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored." + default_value: "ON" field: automatic_mag_declination type: bool - name: inav_gravity_cal_tolerance - docs_description: "Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value." - docs_default_value: "5" + description: "Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value." + default_value: "5" field: gravity_calibration_tolerance min: 0 max: 255 - name: inav_use_gps_velned - docs_description: "Defined if iNav should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF iNav will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance." - docs_default_value: "ON" + description: "Defined if iNav should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF iNav will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance." + default_value: "ON" field: use_gps_velned type: bool - name: inav_allow_dead_reckoning field: allow_dead_reckoning type: bool - name: inav_reset_altitude - docs_description: "Defines when relative estimated altitude is reset to zero. Variants - `NEVER` (once reference is acquired it's used regardless); `FIRST_ARM` (keep altitude at zero until firstly armed), `EACH_ARM` (altitude is reset to zero on each arming)" - docs_default_value: "FIRST_ARM" + description: "Defines when relative estimated altitude is reset to zero. Variants - `NEVER` (once reference is acquired it's used regardless); `FIRST_ARM` (keep altitude at zero until firstly armed), `EACH_ARM` (altitude is reset to zero on each arming)" + default_value: "FIRST_ARM" field: reset_altitude_type table: reset_type - name: inav_reset_home - docs_description: "Allows to chose when the home position is reset. Can help prevent resetting home position after accidental mid-air disarm. Possible values are: NEVER, FIRST_ARM and EACH_ARM" - docs_default_value: "FIRST_ARM" + description: "Allows to chose when the home position is reset. Can help prevent resetting home position after accidental mid-air disarm. Possible values are: NEVER, FIRST_ARM and EACH_ARM" + default_value: "FIRST_ARM" field: reset_home_type table: reset_type - name: inav_max_surface_altitude - docs_description: "Max allowed altitude for surface following mode. [cm]" - docs_default_value: "200" + description: "Max allowed altitude for surface following mode. [cm]" + default_value: "200" field: max_surface_altitude min: 0 max: 1000 @@ -1862,44 +1862,44 @@ groups: min: 0 max: 100 - name: inav_w_z_baro_p - docs_description: "Weight of barometer measurements in estimated altitude and climb rate" - docs_default_value: "0.350" + description: "Weight of barometer measurements in estimated altitude and climb rate" + default_value: "0.350" field: w_z_baro_p min: 0 max: 10 - name: inav_w_z_gps_p - docs_description: "Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes" - docs_default_value: "0.200" + description: "Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes" + default_value: "0.200" field: w_z_gps_p min: 0 max: 10 - name: inav_w_z_gps_v - docs_description: "Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero" - docs_default_value: "0.500" + description: "Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero" + default_value: "0.500" field: w_z_gps_v min: 0 max: 10 - name: inav_w_xy_gps_p - docs_description: "Weight of GPS coordinates in estimated UAV position and speed." - docs_default_value: "1.000" + description: "Weight of GPS coordinates in estimated UAV position and speed." + default_value: "1.000" field: w_xy_gps_p min: 0 max: 10 - name: inav_w_xy_gps_v - docs_description: "Weight of GPS velocity data in estimated UAV speed" - docs_default_value: "2.000" + description: "Weight of GPS velocity data in estimated UAV speed" + default_value: "2.000" field: w_xy_gps_v min: 0 max: 10 - name: inav_w_z_res_v - docs_description: "Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost" - docs_default_value: "0.500" + description: "Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost" + default_value: "0.500" field: w_z_res_v min: 0 max: 10 - name: inav_w_xy_res_v - docs_description: "Decay coefficient for estimated velocity when GPS reference for position is lost" - docs_default_value: "0.500" + description: "Decay coefficient for estimated velocity when GPS reference for position is lost" + default_value: "0.500" field: w_xy_res_v min: 0 max: 10 @@ -1908,20 +1908,20 @@ groups: min: 0 max: 1 - name: inav_w_acc_bias - docs_description: "Weight for accelerometer drift estimation" - docs_default_value: "0.010" + description: "Weight for accelerometer drift estimation" + default_value: "0.010" field: w_acc_bias min: 0 max: 1 - name: inav_max_eph_epv - docs_description: "Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm]" - docs_default_value: "1000.000" + description: "Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm]" + default_value: "1000.000" field: max_eph_epv min: 0 max: 9999 - name: inav_baro_epv - docs_description: "Uncertainty value for barometric sensor [cm]" - docs_default_value: "100.000" + description: "Uncertainty value for barometric sensor [cm]" + default_value: "100.000" field: baro_epv min: 0 max: 9999 @@ -1932,401 +1932,401 @@ groups: condition: USE_NAV members: - name: nav_disarm_on_landing - docs_description: "If set to ON, iNav disarms the FC after landing" - docs_default_value: "OFF" + description: "If set to ON, iNav disarms the FC after landing" + default_value: "OFF" field: general.flags.disarm_on_landing type: bool - name: nav_use_midthr_for_althold - docs_description: "If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude" - docs_default_value: "OFF" + description: "If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude" + default_value: "OFF" field: general.flags.use_thr_mid_for_althold type: bool - name: nav_extra_arming_safety - docs_description: "If set to ON drone won't arm if no GPS fix and any navigation mode like RTH or POSHOLD is configured. ALLOW_BYPASS allows the user to momentarily disable this check by holding yaw high (left stick held at the bottom right in mode 2) when switch arming is used" - docs_default_value: "ON" + description: "If set to ON drone won't arm if no GPS fix and any navigation mode like RTH or POSHOLD is configured. ALLOW_BYPASS allows the user to momentarily disable this check by holding yaw high (left stick held at the bottom right in mode 2) when switch arming is used" + default_value: "ON" field: general.flags.extra_arming_safety table: nav_extra_arming_safety - name: nav_user_control_mode - docs_description: "Defines how Pitch/Roll input from RC receiver affects flight in POSHOLD mode: ATTI - pitch/roll controls attitude like in ANGLE mode; CRUISE - pitch/roll controls velocity in forward and right direction." - docs_default_value: "ATTI" + description: "Defines how Pitch/Roll input from RC receiver affects flight in POSHOLD mode: ATTI - pitch/roll controls attitude like in ANGLE mode; CRUISE - pitch/roll controls velocity in forward and right direction." + default_value: "ATTI" field: general.flags.user_control_mode table: nav_user_control_mode - name: nav_position_timeout - docs_description: "If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable)" - docs_default_value: "5" + description: "If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable)" + default_value: "5" field: general.pos_failure_timeout min: 0 max: 10 - name: nav_wp_radius - docs_description: "Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius" - docs_default_value: "100" + description: "Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius" + default_value: "100" field: general.waypoint_radius min: 10 max: 10000 - name: nav_wp_safe_distance - docs_description: "First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check." - docs_default_value: "10000" + description: "First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check." + default_value: "10000" field: general.waypoint_safe_distance max: 65000 - name: nav_auto_speed - docs_description: "Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only]" - docs_default_value: "300" + description: "Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only]" + default_value: "300" field: general.max_auto_speed min: 10 max: 2000 - name: nav_auto_climb_rate - docs_description: "Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]" - docs_default_value: "500" + description: "Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]" + default_value: "500" field: general.max_auto_climb_rate min: 10 max: 2000 - name: nav_manual_speed - docs_description: "Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only]" - docs_default_value: "500" + description: "Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only]" + default_value: "500" field: general.max_manual_speed min: 10 max: 2000 - name: nav_manual_climb_rate - docs_description: "Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]" - docs_default_value: "200" + description: "Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]" + default_value: "200" field: general.max_manual_climb_rate min: 10 max: 2000 - name: nav_landing_speed - docs_description: "Vertical descent velocity during the RTH landing phase. [cm/s]" - docs_default_value: "200" + description: "Vertical descent velocity during the RTH landing phase. [cm/s]" + default_value: "200" field: general.land_descent_rate min: 100 max: 2000 - name: nav_land_slowdown_minalt - docs_description: "Defines at what altitude the descent velocity should start to be 25% of nav_landing_speed [cm]" - docs_default_value: "500" + description: "Defines at what altitude the descent velocity should start to be 25% of nav_landing_speed [cm]" + default_value: "500" field: general.land_slowdown_minalt min: 50 max: 1000 - name: nav_land_slowdown_maxalt - docs_description: "Defines at what altitude the descent velocity should start to ramp down from 100% nav_landing_speed to 25% nav_landing_speed. [cm]" - docs_default_value: "2000" + description: "Defines at what altitude the descent velocity should start to ramp down from 100% nav_landing_speed to 25% nav_landing_speed. [cm]" + default_value: "2000" field: general.land_slowdown_maxalt min: 500 max: 4000 - name: nav_emerg_landing_speed - docs_description: "Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s]" - docs_default_value: "500" + description: "Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s]" + default_value: "500" field: general.emerg_descent_rate min: 100 max: 2000 - name: nav_min_rth_distance - docs_description: "Minimum distance from homepoint when RTH full procedure will be activated [cm]. Below this distance, the mode will activate at the current location and the final phase is executed (loiter / land). Above this distance, the full procedure is activated, which may include initial climb and flying directly to the homepoint before entering the loiter / land phase." - docs_default_value: "500" + description: "Minimum distance from homepoint when RTH full procedure will be activated [cm]. Below this distance, the mode will activate at the current location and the final phase is executed (loiter / land). Above this distance, the full procedure is activated, which may include initial climb and flying directly to the homepoint before entering the loiter / land phase." + default_value: "500" field: general.min_rth_distance min: 0 max: 5000 - name: nav_overrides_motor_stop - docs_description: "Setting to OFF combined with MOTOR_STOP feature will allow user to stop motor when in autonomous modes. On most places this setting is likely to cause a stall." - docs_default_value: "ON" + description: "Setting to OFF combined with MOTOR_STOP feature will allow user to stop motor when in autonomous modes. On most places this setting is likely to cause a stall." + default_value: "ON" field: general.flags.auto_overrides_motor_stop type: bool - name: nav_rth_climb_first - docs_description: "If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way." - docs_default_value: "ON" + description: "If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way." + default_value: "ON" field: general.flags.rth_climb_first type: bool - name: nav_rth_climb_ignore_emerg - docs_description: "If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status." - docs_default_value: "OFF" + description: "If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status." + default_value: "OFF" field: general.flags.rth_climb_ignore_emerg type: bool - name: nav_rth_tail_first - docs_description: "If set to ON drone will return tail-first. Obviously meaningless for airplanes." - docs_default_value: "OFF" + description: "If set to ON drone will return tail-first. Obviously meaningless for airplanes." + default_value: "OFF" field: general.flags.rth_tail_first type: bool - name: nav_rth_allow_landing - docs_description: "If set to ON drone will land as a last phase of RTH." - docs_default_value: "ALWAYS" + description: "If set to ON drone will land as a last phase of RTH." + default_value: "ALWAYS" field: general.flags.rth_allow_landing table: nav_rth_allow_landing - name: nav_rth_alt_mode - docs_description: "Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details" - docs_default_value: "AT_LEAST" + description: "Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details" + default_value: "AT_LEAST" field: general.flags.rth_alt_control_mode table: nav_rth_alt_mode - name: nav_rth_abort_threshold - docs_description: "RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. [cm]" - docs_default_value: "50000" + description: "RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. [cm]" + default_value: "50000" field: general.rth_abort_threshold max: 65000 - name: nav_max_terrain_follow_alt field: general.max_terrain_follow_altitude max: 1000 - name: nav_rth_altitude - docs_description: "Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters)" - docs_default_value: "1000" + description: "Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters)" + default_value: "1000" field: general.rth_altitude max: 65000 - name: nav_rth_home_altitude - docs_description: "Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm]" - docs_default_value: "0" + description: "Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm]" + default_value: "0" field: general.rth_home_altitude max: 65000 - name: nav_rth_home_offset_distance - docs_description: "Distance offset from GPS established home to \"safe\" position used for RTH (cm, 0 disables)" - docs_default_value: "0" + description: "Distance offset from GPS established home to \"safe\" position used for RTH (cm, 0 disables)" + default_value: "0" field: general.rth_home_offset_distance max: 65000 - name: nav_rth_home_offset_direction - docs_description: "Direction offset from GPS established home to \"safe\" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance)" - docs_default_value: "0" + description: "Direction offset from GPS established home to \"safe\" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance)" + default_value: "0" field: general.rth_home_offset_direction max: 359 - name: nav_mc_bank_angle - docs_description: "Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude" - docs_default_value: "30" + description: "Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude" + default_value: "30" field: mc.max_bank_angle min: 15 max: 45 - name: nav_mc_hover_thr - docs_description: "Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering." - docs_default_value: "1500" + description: "Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering." + default_value: "1500" field: mc.hover_throttle min: 1000 max: 2000 - name: nav_mc_auto_disarm_delay - docs_description: "" - docs_default_value: "2000" + description: "" + default_value: "2000" field: mc.auto_disarm_delay min: 100 max: 10000 - name: nav_mc_braking_speed_threshold - docs_description: "min speed in cm/s above which braking can happen" - docs_default_value: "100" + description: "min speed in cm/s above which braking can happen" + default_value: "100" field: mc.braking_speed_threshold condition: USE_MR_BRAKING_MODE min: 0 max: 1000 - name: nav_mc_braking_disengage_speed - docs_description: "braking is disabled when speed goes below this value" - docs_default_value: "75" + description: "braking is disabled when speed goes below this value" + default_value: "75" field: mc.braking_disengage_speed condition: USE_MR_BRAKING_MODE min: 0 max: 1000 - name: nav_mc_braking_timeout - docs_description: "timeout in ms for braking" - docs_default_value: "2000" + description: "timeout in ms for braking" + default_value: "2000" field: mc.braking_timeout condition: USE_MR_BRAKING_MODE min: 100 max: 5000 - name: nav_mc_braking_boost_factor - docs_description: "acceleration factor for BOOST phase" - docs_default_value: "100" + description: "acceleration factor for BOOST phase" + default_value: "100" field: mc.braking_boost_factor condition: USE_MR_BRAKING_MODE min: 0 max: 200 - name: nav_mc_braking_boost_timeout - docs_description: "how long in ms BOOST phase can happen" - docs_default_value: "750" + description: "how long in ms BOOST phase can happen" + default_value: "750" field: mc.braking_boost_timeout condition: USE_MR_BRAKING_MODE min: 0 max: 5000 - name: nav_mc_braking_boost_speed_threshold - docs_description: "BOOST can be enabled when speed is above this value" - docs_default_value: "150" + description: "BOOST can be enabled when speed is above this value" + default_value: "150" field: mc.braking_boost_speed_threshold condition: USE_MR_BRAKING_MODE min: 100 max: 1000 - name: nav_mc_braking_boost_disengage_speed - docs_description: "BOOST will be disabled when speed goes below this value" - docs_default_value: "100" + description: "BOOST will be disabled when speed goes below this value" + default_value: "100" field: mc.braking_boost_disengage_speed condition: USE_MR_BRAKING_MODE min: 0 max: 1000 - name: nav_mc_braking_bank_angle - docs_description: "max angle that MR is allowed to bank in BOOST mode" - docs_default_value: "40" + description: "max angle that MR is allowed to bank in BOOST mode" + default_value: "40" field: mc.braking_bank_angle condition: USE_MR_BRAKING_MODE min: 15 max: 60 - name: nav_mc_pos_deceleration_time - docs_description: "Used for stoping distance calculation. Stop position is computed as _speed_ * _nav_mc_pos_deceleration_time_ from the place where sticks are released. Braking mode overrides this setting" - docs_default_value: "120" + description: "Used for stoping distance calculation. Stop position is computed as _speed_ * _nav_mc_pos_deceleration_time_ from the place where sticks are released. Braking mode overrides this setting" + default_value: "120" field: mc.posDecelerationTime condition: USE_NAV min: 0 max: 255 - name: nav_mc_pos_expo - docs_description: "Expo for PosHold control" - docs_default_value: "10" + description: "Expo for PosHold control" + default_value: "10" field: mc.posResponseExpo condition: USE_NAV min: 0 max: 255 - name: nav_fw_cruise_thr - docs_description: "Cruise throttle in GPS assisted modes, this includes RTH. Should be set high enough to avoid stalling. This values gives INAV a base for throttle when flying straight, and it will increase or decrease throttle based on pitch of airplane and the parameters below. In addition it will increase throttle if GPS speed gets below 7m/s ( hardcoded )" - docs_default_value: "1400" + description: "Cruise throttle in GPS assisted modes, this includes RTH. Should be set high enough to avoid stalling. This values gives INAV a base for throttle when flying straight, and it will increase or decrease throttle based on pitch of airplane and the parameters below. In addition it will increase throttle if GPS speed gets below 7m/s ( hardcoded )" + default_value: "1400" field: fw.cruise_throttle min: 1000 max: 2000 - name: nav_fw_min_thr - docs_description: "Minimum throttle for flying wing in GPS assisted modes" - docs_default_value: "1200" + description: "Minimum throttle for flying wing in GPS assisted modes" + default_value: "1200" field: fw.min_throttle min: 1000 max: 2000 - name: nav_fw_max_thr - docs_description: "Maximum throttle for flying wing in GPS assisted modes" - docs_default_value: "1700" + description: "Maximum throttle for flying wing in GPS assisted modes" + default_value: "1700" field: fw.max_throttle min: 1000 max: 2000 - name: nav_fw_bank_angle - docs_description: "Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll" - docs_default_value: "20" + description: "Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll" + default_value: "20" field: fw.max_bank_angle min: 5 max: 80 - name: nav_fw_climb_angle - docs_description: "Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit" - docs_default_value: "20" + description: "Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit" + default_value: "20" field: fw.max_climb_angle min: 5 max: 80 - name: nav_fw_dive_angle - docs_description: "Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit" - docs_default_value: "15" + description: "Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit" + default_value: "15" field: fw.max_dive_angle min: 5 max: 80 - name: nav_fw_pitch2thr - docs_description: "Amount of throttle applied related to pitch attitude in GPS assisted modes. Throttle = nav_fw_cruise_throttle - (nav_fw_pitch2thr * pitch_angle). (notice that pitch_angle is in degrees and is negative when climbing and positive when diving, and throttle value is constrained between nav_fw_min_thr and nav_fw_max_thr)" - docs_default_value: "10" + description: "Amount of throttle applied related to pitch attitude in GPS assisted modes. Throttle = nav_fw_cruise_throttle - (nav_fw_pitch2thr * pitch_angle). (notice that pitch_angle is in degrees and is negative when climbing and positive when diving, and throttle value is constrained between nav_fw_min_thr and nav_fw_max_thr)" + default_value: "10" field: fw.pitch_to_throttle min: 0 max: 100 - name: nav_fw_loiter_radius - docs_description: "PosHold radius. 3000 to 7500 is a good value (30-75m) [cm]" - docs_default_value: "5000" + description: "PosHold radius. 3000 to 7500 is a good value (30-75m) [cm]" + default_value: "5000" field: fw.loiter_radius min: 0 max: 10000 - name: nav_fw_cruise_speed - docs_description: "Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s" - docs_default_value: "0" + description: "Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s" + default_value: "0" field: fw.cruise_speed min: 0 max: 65535 - name: nav_fw_control_smoothness - docs_description: "How smoothly the autopilot controls the airplane to correct the navigation error" - docs_default_value: "0" + description: "How smoothly the autopilot controls the airplane to correct the navigation error" + default_value: "0" field: fw.control_smoothness min: 0 max: 9 - name: nav_fw_land_dive_angle - docs_description: "Dive angle that airplane will use during final landing phase. During dive phase, motor is stopped or IDLE and roll control is locked to 0 degrees" - docs_default_value: "2" + description: "Dive angle that airplane will use during final landing phase. During dive phase, motor is stopped or IDLE and roll control is locked to 0 degrees" + default_value: "2" field: fw.land_dive_angle condition: NAV_FIXED_WING_LANDING min: -20 max: 20 - name: nav_fw_launch_velocity - docs_description: "Forward velocity threshold for swing-launch detection [cm/s]" - docs_default_value: "300" + description: "Forward velocity threshold for swing-launch detection [cm/s]" + default_value: "300" field: fw.launch_velocity_thresh min: 100 max: 10000 - name: nav_fw_launch_accel - docs_description: "Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s" - docs_default_value: "1863" + description: "Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s" + default_value: "1863" field: fw.launch_accel_thresh min: 1000 max: 20000 - name: nav_fw_launch_max_angle - docs_description: "Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg]" - docs_default_value: "45" + description: "Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg]" + default_value: "45" field: fw.launch_max_angle min: 5 max: 180 - name: nav_fw_launch_detect_time - docs_description: "Time for which thresholds have to breached to consider launch happened [ms]" - docs_default_value: "40" + description: "Time for which thresholds have to breached to consider launch happened [ms]" + default_value: "40" field: fw.launch_time_thresh min: 10 max: 1000 - name: nav_fw_launch_thr - docs_description: "Launch throttle - throttle to be set during launch sequence (pwm units)" - docs_default_value: "1700" + description: "Launch throttle - throttle to be set during launch sequence (pwm units)" + default_value: "1700" field: fw.launch_throttle min: 1000 max: 2000 - name: nav_fw_launch_idle_thr - docs_description: "Launch idle throttle - throttle to be set before launch sequence is initiated. If set below minimum throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above minimum throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position)" - docs_default_value: "1000" + description: "Launch idle throttle - throttle to be set before launch sequence is initiated. If set below minimum throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above minimum throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position)" + default_value: "1000" field: fw.launch_idle_throttle min: 1000 max: 2000 - name: nav_fw_launch_motor_delay - docs_description: "Delay between detected launch and launch sequence start and throttling up (ms)" - docs_default_value: "500" + description: "Delay between detected launch and launch sequence start and throttling up (ms)" + default_value: "500" field: fw.launch_motor_timer min: 0 max: 5000 - name: nav_fw_launch_spinup_time - docs_description: "Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller" - docs_default_value: "100" + description: "Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller" + default_value: "100" field: fw.launch_motor_spinup_time min: 0 max: 1000 - name: nav_fw_launch_min_time - docs_description: "Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]." - docs_default_value: "0" + description: "Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]." + default_value: "0" field: fw.launch_min_time min: 0 max: 60000 - name: nav_fw_launch_timeout - docs_description: "Maximum time for launch sequence to be executed. After this time LAUNCH mode will be turned off and regular flight mode will take over (ms)" - docs_default_value: "5000" + description: "Maximum time for launch sequence to be executed. After this time LAUNCH mode will be turned off and regular flight mode will take over (ms)" + default_value: "5000" field: fw.launch_timeout max: 60000 - name: nav_fw_launch_max_altitude - docs_description: "Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]." - docs_default_value: "0" + description: "Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]." + default_value: "0" field: fw.launch_max_altitude min: 0 max: 60000 - name: nav_fw_launch_climb_angle - docs_description: "Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit" - docs_default_value: "18" + description: "Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit" + default_value: "18" field: fw.launch_climb_angle min: 5 max: 45 - name: nav_fw_cruise_yaw_rate - docs_description: "Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps]" - docs_default_value: "20" + description: "Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps]" + default_value: "20" field: fw.cruise_yaw_rate min: 0 max: 60 - name: nav_fw_allow_manual_thr_increase - docs_description: "Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing" - docs_default_value: "OFF" + description: "Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing" + default_value: "OFF" field: fw.allow_manual_thr_increase type: bool - name: nav_use_fw_yaw_control - docs_description: "Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats" - docs_default_value: "OFF" + description: "Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats" + default_value: "OFF" field: fw.useFwNavYawControl type: bool - name: nav_fw_yaw_deadband - docs_description: "Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course" - docs_default_value: "0" + description: "Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course" + default_value: "0" field: fw.yawControlDeadband min: 0 max: 90 @@ -2337,136 +2337,136 @@ groups: condition: USE_TELEMETRY members: - name: telemetry_switch - docs_description: "Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed." - docs_default_value: "OFF" + description: "Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed." + default_value: "OFF" type: bool - name: telemetry_inverted - docs_description: "Determines if the telemetry protocol default signal inversion is reversed. This should be OFF in most cases unless a custom or hacked RX is used." - docs_default_value: "OFF" + description: "Determines if the telemetry protocol default signal inversion is reversed. This should be OFF in most cases unless a custom or hacked RX is used." + default_value: "OFF" type: bool - name: frsky_default_latitude - docs_description: "D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired." - docs_default_value: "0.000" + description: "D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired." + default_value: "0.000" field: gpsNoFixLatitude min: -90 max: 90 - name: frsky_default_longitude - docs_description: "D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired." - docs_default_value: "0.000" + description: "D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired." + default_value: "0.000" field: gpsNoFixLongitude min: -180 max: 180 - name: frsky_coordinates_format - docs_description: "D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA" - docs_default_value: "0" + description: "D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA" + default_value: "0" field: frsky_coordinate_format min: 0 max: FRSKY_FORMAT_NMEA type: uint8_t # TODO: This seems to use an enum, we should use table: - name: frsky_unit - docs_description: "Not used? [METRIC/IMPERIAL]" - docs_default_value: "METRIC" + description: "Not used? [METRIC/IMPERIAL]" + default_value: "METRIC" table: frsky_unit type: uint8_t - name: frsky_vfas_precision - docs_description: "D-Series telemetry only: Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method" - docs_default_value: "0" + description: "D-Series telemetry only: Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method" + default_value: "0" min: FRSKY_VFAS_PRECISION_LOW max: FRSKY_VFAS_PRECISION_HIGH - name: frsky_pitch_roll - docs_description: "S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data" - docs_default_value: "OFF" + description: "S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data" + default_value: "OFF" type: bool - name: report_cell_voltage - docs_description: "S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON" - docs_default_value: "OFF" + description: "S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON" + default_value: "OFF" type: bool - name: hott_alarm_sound_interval - docs_description: "Battery alarm delay in seconds for Hott telemetry" - docs_default_value: "5" + description: "Battery alarm delay in seconds for Hott telemetry" + default_value: "5" field: hottAlarmSoundInterval min: 0 max: 120 - name: telemetry_halfduplex - docs_description: "S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details" - docs_default_value: "OFF" + description: "S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details" + default_value: "OFF" field: halfDuplex type: bool - name: smartport_fuel_unit - docs_description: "S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH]" - docs_default_value: "MAH" + description: "S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH]" + default_value: "MAH" field: smartportFuelUnit condition: USE_TELEMETRY_SMARTPORT type: uint8_t table: smartport_fuel_unit - name: ibus_telemetry_type - docs_description: "Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details." - docs_default_value: "0" + description: "Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details." + default_value: "0" field: ibusTelemetryType min: 0 max: 255 - name: ltm_update_rate - docs_description: "Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details." - docs_default_value: "NORMAL" + description: "Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details." + default_value: "NORMAL" field: ltmUpdateRate condition: USE_TELEMETRY_LTM table: ltm_rates - name: sim_ground_station_number - docs_description: "Number of phone that is used to communicate with SIM module. Messages / calls from other numbers are ignored. If undefined, can be set by calling or sending a message to the module." - docs_default_value: "Empty string" + description: "Number of phone that is used to communicate with SIM module. Messages / calls from other numbers are ignored. If undefined, can be set by calling or sending a message to the module." + default_value: "Empty string" field: simGroundStationNumber condition: USE_TELEMETRY_SIM type: string max: 16 - name: sim_pin - docs_description: "PIN code for the SIM module" - docs_default_value: "Empty string" + description: "PIN code for the SIM module" + default_value: "Empty string" field: simPin condition: USE_TELEMETRY_SIM type: string max: 8 - name: sim_transmit_interval - docs_description: "Text message transmission interval in seconds for SIM module. Minimum value: 10" - docs_default_value: "60" + description: "Text message transmission interval in seconds for SIM module. Minimum value: 10" + default_value: "60" field: simTransmitInterval condition: USE_TELEMETRY_SIM type: uint16_t min: SIM_MIN_TRANSMIT_INTERVAL max: 65535 - name: sim_transmit_flags - docs_description: "String specifying text message transmit condition flags for the SIM module. Flags can be given in any order. Empty string means the module only sends response messages. `A`: acceleration events, `T`: continuous transmission, `F`: continuous transmission in failsafe mode, `L`: continuous transmission when altitude is below `sim_low_altitude`, `G`: continuous transmission when GPS signal quality is low" - docs_default_value: "F" + description: "String specifying text message transmit condition flags for the SIM module. Flags can be given in any order. Empty string means the module only sends response messages. `A`: acceleration events, `T`: continuous transmission, `F`: continuous transmission in failsafe mode, `L`: continuous transmission when altitude is below `sim_low_altitude`, `G`: continuous transmission when GPS signal quality is low" + default_value: "F" field: simTransmitFlags condition: USE_TELEMETRY_SIM type: string max: SIM_N_TX_FLAGS - name: acc_event_threshold_high - docs_description: "Acceleration threshold [cm/s/s] for impact / high g event text messages sent by SIM module. Acceleration values greater than 4 g can occur in fixed wing flight without an impact, so a setting of 4000 or greater is suggested. 0 = detection off." - docs_default_value: "0" + description: "Acceleration threshold [cm/s/s] for impact / high g event text messages sent by SIM module. Acceleration values greater than 4 g can occur in fixed wing flight without an impact, so a setting of 4000 or greater is suggested. 0 = detection off." + default_value: "0" field: accEventThresholdHigh condition: USE_TELEMETRY_SIM type: uint16_t min: 0 max: 65535 - name: acc_event_threshold_low - docs_description: "Acceleration threshold [cm/s/s] for low-g / freefall detection text messages sent by SIM module. A setting of less than 100 is suggested. Valid values: [0-900], 0 = detection off." - docs_default_value: "0" + description: "Acceleration threshold [cm/s/s] for low-g / freefall detection text messages sent by SIM module. A setting of less than 100 is suggested. Valid values: [0-900], 0 = detection off." + default_value: "0" field: accEventThresholdLow condition: USE_TELEMETRY_SIM type: uint16_t min: 0 max: 900 - name: acc_event_threshold_neg_x - docs_description: "Acceleration threshold [cm/s/s] for backwards acceleration / fixed wing landing detection text messages sent by SIM module. Suggested value for fixed wing: 1100. 0 = detection off." - docs_default_value: "0" + description: "Acceleration threshold [cm/s/s] for backwards acceleration / fixed wing landing detection text messages sent by SIM module. Suggested value for fixed wing: 1100. 0 = detection off." + default_value: "0" field: accEventThresholdNegX condition: USE_TELEMETRY_SIM type: uint16_t min: 0 max: 65535 - name: sim_low_altitude - docs_description: "Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`." - docs_default_value: "0" + description: "Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`." + default_value: "0" field: simLowAltitude condition: USE_TELEMETRY_SIM type: int16_t @@ -2534,8 +2534,8 @@ groups: condition: USE_LED_STRIP members: - name: ledstrip_visual_beeper - docs_description: "" - docs_default_value: "OFF" + description: "" + default_value: "OFF" type: bool - name: PG_OSD_CONFIG @@ -2544,125 +2544,125 @@ groups: condition: USE_OSD members: - name: osd_video_system - docs_description: "Video system used. Possible values are `AUTO`, `PAL` and `NTSC`" - docs_default_value: "AUTO" + description: "Video system used. Possible values are `AUTO`, `PAL` and `NTSC`" + default_value: "AUTO" table: osd_video_system field: video_system type: uint8_t - name: osd_row_shiftdown - docs_description: "Number of rows to shift the OSD display (increase if top rows are cut off)" - docs_default_value: "0" + description: "Number of rows to shift the OSD display (increase if top rows are cut off)" + default_value: "0" field: row_shiftdown min: 0 max: 1 - name: osd_units - docs_description: "IMPERIAL, METRIC, UK" - docs_default_value: "METRIC" + description: "IMPERIAL, METRIC, UK" + default_value: "METRIC" field: units table: osd_unit type: uint8_t - name: osd_stats_energy_unit - docs_description: "Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour)" - docs_default_value: "MAH" + description: "Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour)" + default_value: "MAH" field: stats_energy_unit table: osd_stats_energy_unit type: uint8_t - name: osd_rssi_alarm - docs_description: "Value bellow which to make the OSD RSSI indicator blink" - docs_default_value: "20" + description: "Value bellow which to make the OSD RSSI indicator blink" + default_value: "20" field: rssi_alarm min: 0 max: 100 - name: osd_time_alarm - docs_description: "Value above which to make the OSD flight time indicator blink (minutes)" - docs_default_value: "10" + description: "Value above which to make the OSD flight time indicator blink (minutes)" + default_value: "10" field: time_alarm min: 0 max: 600 - name: osd_alt_alarm - docs_description: "Value above which to make the OSD relative altitude indicator blink (meters)" - docs_default_value: "100" + description: "Value above which to make the OSD relative altitude indicator blink (meters)" + default_value: "100" field: alt_alarm min: 0 max: 10000 - name: osd_dist_alarm - docs_description: "Value above which to make the OSD distance from home indicator blink (meters)" - docs_default_value: "1000" + description: "Value above which to make the OSD distance from home indicator blink (meters)" + default_value: "1000" field: dist_alarm min: 0 max: 50000 - name: osd_neg_alt_alarm - docs_description: "Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters)" - docs_default_value: "5" + description: "Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters)" + default_value: "5" field: neg_alt_alarm min: 0 max: 10000 - name: osd_current_alarm - docs_description: "Value above which the OSD current consumption element will start blinking. Measured in full Amperes." - docs_default_value: "0" + description: "Value above which the OSD current consumption element will start blinking. Measured in full Amperes." + default_value: "0" field: current_alarm min: 0 max: 255 - name: osd_gforce_alarm - docs_description: "Value above which the OSD g force indicator will blink (g)" - docs_default_value: "5" + description: "Value above which the OSD g force indicator will blink (g)" + default_value: "5" field: gforce_alarm min: 0 max: 20 - name: osd_gforce_axis_alarm_min - docs_description: "Value under which the OSD axis g force indicators will blink (g)" - docs_default_value: "-5" + description: "Value under which the OSD axis g force indicators will blink (g)" + default_value: "-5" field: gforce_axis_alarm_min min: -20 max: 20 - name: osd_gforce_axis_alarm_max - docs_description: "Value above which the OSD axis g force indicators will blink (g)" - docs_default_value: "5" + description: "Value above which the OSD axis g force indicators will blink (g)" + default_value: "5" field: gforce_axis_alarm_max min: -20 max: 20 - name: osd_imu_temp_alarm_min - docs_description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)" - docs_default_value: "-200" + description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)" + default_value: "-200" field: imu_temp_alarm_min min: -550 max: 1250 - name: osd_imu_temp_alarm_max - docs_description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)" - docs_default_value: "600" + description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)" + default_value: "600" field: imu_temp_alarm_max min: -550 max: 1250 - name: osd_esc_temp_alarm_max - docs_description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)" - docs_default_value: "900" + description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)" + default_value: "900" field: esc_temp_alarm_max min: -550 max: 1500 - name: osd_esc_temp_alarm_min - docs_description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)" - docs_default_value: "-200" + description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)" + default_value: "-200" field: esc_temp_alarm_min min: -550 max: 1500 - name: osd_baro_temp_alarm_min - docs_description: "Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade)" - docs_default_value: "-200" + description: "Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade)" + default_value: "-200" field: baro_temp_alarm_min condition: USE_BARO min: -550 max: 1250 - name: osd_baro_temp_alarm_max - docs_description: "Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade)" - docs_default_value: "600" + description: "Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade)" + default_value: "600" field: baro_temp_alarm_max condition: USE_BARO min: -550 max: 1250 - name: osd_temp_label_align - docs_description: "Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT`" - docs_default_value: "LEFT" + description: "Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT`" + default_value: "LEFT" field: temp_label_align condition: USE_TEMPERATURE_SENSOR table: osd_alignment @@ -2672,8 +2672,8 @@ groups: field: ahi_reverse_roll type: bool - name: osd_artificial_horizon_max_pitch - docs_description: "Max pitch, in degrees, for OSD artificial horizon" - docs_default_value: "20" + description: "Max pitch, in degrees, for OSD artificial horizon" + default_value: "20" field: ahi_max_pitch min: 10 max: 90 @@ -2728,8 +2728,8 @@ groups: min: 0 max: 4000 - name: osd_hud_wp_disp - docs_description: "Controls display of the next waypoints in the HUD." - docs_default_value: "OFF" + description: "Controls display of the next waypoints in the HUD." + default_value: "OFF" field: hud_wp_disp min: 0 max: 3 @@ -2745,8 +2745,8 @@ groups: field: sidebar_scroll_arrows type: bool - name: osd_main_voltage_decimals - docs_description: "Number of decimals for the battery voltages displayed in the OSD [1-2]." - docs_default_value: "1" + description: "Number of decimals for the battery voltages displayed in the OSD [1-2]." + default_value: "1" field: main_voltage_decimals min: 1 max: 2 @@ -2756,15 +2756,15 @@ groups: max: 11 - name: osd_estimations_wind_compensation - docs_description: "Use wind estimation for remaining flight time/distance estimation" - docs_default_value: "ON" + description: "Use wind estimation for remaining flight time/distance estimation" + default_value: "ON" condition: USE_WIND_ESTIMATOR field: estimations_wind_compensation type: bool - name: osd_failsafe_switch_layout - docs_description: "If enabled the OSD automatically switches to the first layout during failsafe" - docs_default_value: "OFF" + description: "If enabled the OSD automatically switches to the first layout during failsafe" + default_value: "OFF" type: bool - name: osd_plus_code_digits @@ -2773,8 +2773,8 @@ groups: max: 13 - name: osd_ahi_style - docs_description: "Sets OSD Artificial Horizon style \"DEFAULT\" or \"LINE\" for the FrSky Graphical OSD." - docs_default_value: "DEFAULT" + description: "Sets OSD Artificial Horizon style \"DEFAULT\" or \"LINE\" for the FrSky Graphical OSD." + default_value: "DEFAULT" table: osd_ahi_style - name: PG_SYSTEM_CONFIG @@ -2782,35 +2782,35 @@ groups: headers: ["fc/config.h"] members: - name: i2c_speed - docs_description: "This setting controls the clock speed of I2C bus. 400KHZ is the default that most setups are able to use. Some noise-free setups may be overclocked to 800KHZ. Some sensor chips or setups with long wires may work unreliably at 400KHZ - user can try lowering the clock speed to 200KHZ or even 100KHZ. User need to bear in mind that lower clock speeds might require higher looptimes (lower looptime rate)" - docs_default_value: "400KHZ" + description: "This setting controls the clock speed of I2C bus. 400KHZ is the default that most setups are able to use. Some noise-free setups may be overclocked to 800KHZ. Some sensor chips or setups with long wires may work unreliably at 400KHZ - user can try lowering the clock speed to 200KHZ or even 100KHZ. User need to bear in mind that lower clock speeds might require higher looptimes (lower looptime rate)" + default_value: "400KHZ" condition: USE_I2C table: i2c_speed - name: cpu_underclock - docs_description: "This option is only available on certain architectures (F3 CPUs at the moment). It makes CPU clock lower to reduce interference to long-range RC systems working at 433MHz" - docs_default_value: "OFF" + description: "This option is only available on certain architectures (F3 CPUs at the moment). It makes CPU clock lower to reduce interference to long-range RC systems working at 433MHz" + default_value: "OFF" field: cpuUnderclock condition: USE_UNDERCLOCK type: bool - name: debug_mode table: debug_modes - name: throttle_tilt_comp_str - docs_description: "Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled." - docs_default_value: "0" + description: "Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled." + default_value: "0" field: throttle_tilt_compensation_strength min: 0 max: 100 - name: name - docs_description: "Craft name" - docs_default_value: "Empty string" + description: "Craft name" + default_value: "Empty string" - name: PG_MODE_ACTIVATION_OPERATOR_CONFIG type: modeActivationOperatorConfig_t headers: ["fc/rc_modes.h"] members: - name: mode_range_logic_operator - docs_description: "Control how Mode selection works in flight modes. If you example have Angle mode configured on two different Aux channels, this controls if you need both activated ( AND ) or if you only need one activated ( OR ) to active angle mode." - docs_default_value: "OR" + description: "Control how Mode selection works in flight modes. If you example have Angle mode configured on two different Aux channels, this controls if you need both activated ( AND ) or if you only need one activated ( OR ) to active angle mode." + default_value: "OR" field: modeActivationOperator table: aux_operator type: uint8_t @@ -2821,17 +2821,17 @@ groups: condition: USE_STATS members: - name: stats - docs_description: "General switch of the statistics recording feature (a.k.a. odometer)" - docs_default_value: "OFF" + description: "General switch of the statistics recording feature (a.k.a. odometer)" + default_value: "OFF" field: stats_enabled type: bool - name: stats_total_time - docs_description: "Total flight time [in seconds]. The value is updated on every disarm when \"stats\" are enabled." - docs_default_value: "0" + description: "Total flight time [in seconds]. The value is updated on every disarm when \"stats\" are enabled." + default_value: "0" max: INT32_MAX - name: stats_total_dist - docs_description: "Total flight distance [in meters]. The value is updated on every disarm when \"stats\" are enabled." - docs_default_value: "0" + description: "Total flight distance [in meters]. The value is updated on every disarm when \"stats\" are enabled." + default_value: "0" max: INT32_MAX - name: stats_total_energy max: INT32_MAX @@ -2842,13 +2842,13 @@ groups: headers: ["common/time.h"] members: - name: tz_offset - docs_description: "Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs" - docs_default_value: "0" + description: "Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs" + default_value: "0" min: -1440 max: 1440 - name: tz_automatic_dst - docs_description: "Automatically add Daylight Saving Time to the GPS time when needed or simply ignore it. Includes presets for EU and the USA - if you live outside these areas it is suggested to manage DST manually via `tz_offset`." - docs_default_value: "OFF" + description: "Automatically add Daylight Saving Time to the GPS time when needed or simply ignore it. Includes presets for EU and the USA - if you live outside these areas it is suggested to manage DST manually via `tz_offset`." + default_value: "OFF" type: uint8_t table: tz_automatic_dst @@ -2857,8 +2857,8 @@ groups: headers: ["drivers/display.h"] members: - name: display_force_sw_blink - docs_description: "OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON" - docs_default_value: "OFF" + description: "OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON" + default_value: "OFF" field: force_sw_blink type: bool @@ -2868,8 +2868,8 @@ groups: condition: USE_VTX_CONTROL members: - name: vtx_halfduplex - docs_description: "Use half duplex UART to communicate with the VTX, using only a TX pin in the FC." - docs_default_value: "ON" + description: "Use half duplex UART to communicate with the VTX, using only a TX pin in the FC." + default_value: "ON" field: halfDuplex type: bool @@ -2878,26 +2878,26 @@ groups: headers: ["drivers/vtx_common.h", "io/vtx.h"] members: - name: vtx_band - docs_description: "Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race." - docs_default_value: "4" + description: "Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race." + default_value: "4" field: band min: VTX_SETTINGS_NO_BAND max: VTX_SETTINGS_MAX_BAND - name: vtx_channel - docs_description: "Channel to use within the configured `vtx_band`. Valid values are [1, 8]." - docs_default_value: "1" + description: "Channel to use within the configured `vtx_band`. Valid values are [1, 8]." + default_value: "1" field: channel min: VTX_SETTINGS_MIN_CHANNEL max: VTX_SETTINGS_MAX_CHANNEL - name: vtx_power - docs_description: "VTX RF power level to use. The exact number of mw depends on the VTX hardware." - docs_default_value: "1" + description: "VTX RF power level to use. The exact number of mw depends on the VTX hardware." + default_value: "1" field: power min: VTX_SETTINGS_MIN_POWER max: VTX_SETTINGS_MAX_POWER - name: vtx_low_power_disarm - docs_description: "When the craft is disarmed, set the VTX to its lowest power. `ON` will set the power to its minimum value on startup, increase it to `vtx_power` when arming and change it back to its lowest setting after disarming. `UNTIL_FIRST_ARM` will start with minimum power, but once the craft is armed it will increase to `vtx_power` and it will never decrease until the craft is power cycled." - docs_default_value: "OFF" + description: "When the craft is disarmed, set the VTX to its lowest power. `ON` will set the power to its minimum value on startup, increase it to `vtx_power` when arming and change it back to its lowest setting after disarming. `UNTIL_FIRST_ARM` will start with minimum power, but once the craft is armed it will increase to `vtx_power` and it will never decrease until the craft is power cycled." + default_value: "OFF" field: lowPowerDisarm table: vtx_low_power_disarm type: uint8_t diff --git a/src/utils/update_cli_docs.py b/src/utils/update_cli_docs.py index 4fe2bacd352..47bd255ab65 100755 --- a/src/utils/update_cli_docs.py +++ b/src/utils/update_cli_docs.py @@ -2,18 +2,12 @@ import yaml # pyyaml / python-yaml -CLI_MD_PATH = "docs/Cli.md" +SETTINGS_MD_PATH = "docs/Settings.md" SETTINGS_YAML_PATH = "src/main/fc/settings.yaml" -CLI_MD_SECTION_HEADER = "## CLI Variable Reference" - -# Read the contents of the markdown CLI docs -def read_cli_md(): - with open(CLI_MD_PATH, "r") as cli_md: - return cli_md.readlines() - -# Parse the YAML settings specs def parse_settings_yaml(): + """Parse the YAML settings specs""" + with open(SETTINGS_YAML_PATH, "r") as settings_yaml: return yaml.load(settings_yaml, Loader=yaml.Loader) @@ -24,10 +18,10 @@ def generate_md_table_from_yaml(settings_yaml): # Extract description and default value of each setting from the YAML specs (if present) for group in settings_yaml['groups']: for member in group['members']: - if any(key in member for key in ["docs_description", "docs_default_value"]): + if any(key in member for key in ["description", "default_value"]): params[member['name']] = { - "description": member["docs_description"] if "docs_description" in member else "", - "default": member["docs_default_value"] if "docs_default_value" in member else "" + "description": member["description"] if "description" in member else "", + "default": member["default_value"] if "default_value" in member else "" } # MD table header @@ -43,42 +37,17 @@ def generate_md_table_from_yaml(settings_yaml): # Return the assembled table return md_table_lines -def replace_md_table_in_cli_md(cli_md_lines, md_table_lines): - """Update the settings table in the CLI docs - - Copy all the original lines up to $CLI_MD_SECTION_HEADER (including the following newline), then insert - the updated table in place of the next block of text (replace everything until an empty line is found). - """ - new_lines = [] - lines_to_skip = 0 - skip_until_empty_line = False - for line in cli_md_lines: - if lines_to_skip > 0: - lines_to_skip -= 1 - if lines_to_skip == 0: - skip_until_empty_line = True - continue - elif skip_until_empty_line: - if line != "\n": - continue - else: - skip_until_empty_line = False - new_lines.append("\n") - new_lines += md_table_lines - if line.startswith(CLI_MD_SECTION_HEADER): - lines_to_skip = 2 - new_lines.append(line) - - return new_lines +def write_settings_md(lines): + """Write the contents of the CLI settings docs""" -# Write the contents of the markdown CLI docs -def write_cli_md(lines): - with open(CLI_MD_PATH, "w") as cli_md: - cli_md.writelines(lines) + with open(SETTINGS_MD_PATH, "w") as settings_md: + settings_md.writelines(lines) if __name__ == "__main__": settings_yaml = parse_settings_yaml() md_table_lines = generate_md_table_from_yaml(settings_yaml) - cli_md_lines = read_cli_md() - cli_md_lines = replace_md_table_in_cli_md(cli_md_lines, md_table_lines) - write_cli_md(cli_md_lines) + settings_md_lines = \ + ["# CLI Variable Reference\n", "\n" ] + \ + md_table_lines + \ + ["\n", "> Note: this table is autogenerated. Do not edit it manually."] + write_settings_md(settings_md_lines) From e7e431477c9e871d90157ee99f8113fd7671c5b1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 22 Jun 2020 14:45:14 +0100 Subject: [PATCH 029/248] [OSD] Fix overflow in osdGridBufferClearGridRect() Width was added twice, causing an overflow when 2x the rect width ended up being bigger than the screen width in grid columns. --- src/main/drivers/osd.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/osd.c b/src/main/drivers/osd.c index 231d8eec280..bddefea7ce0 100644 --- a/src/main/drivers/osd.c +++ b/src/main/drivers/osd.c @@ -72,7 +72,7 @@ void osdGridBufferClearGridRect(int x, int y, int w, int h) osdGridBufferConstrainRect(&x, &y, &w, &h, OSD_CHARACTER_GRID_MAX_WIDTH, OSD_CHARACTER_GRID_MAX_HEIGHT); int maxX = x + w; int maxY = y + h; - for (int ii = x; ii <= maxX + w; ii++) { + for (int ii = x; ii <= maxX; ii++) { for (int jj = y; jj <= maxY; jj++) { *osdCharacterGridBufferGetEntryPtr(ii, jj) = 0; } From 4fc6da7de28ca7166ab2c141471aaae605fff29d Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Tue, 23 Jun 2020 12:13:13 +0200 Subject: [PATCH 030/248] [BOT] Add no-response bot configuration --- .github/no-response.yml | 12 ++++++++++++ 1 file changed, 12 insertions(+) create mode 100644 .github/no-response.yml diff --git a/.github/no-response.yml b/.github/no-response.yml new file mode 100644 index 00000000000..8002aa3ad96 --- /dev/null +++ b/.github/no-response.yml @@ -0,0 +1,12 @@ +# Configuration for probot-no-response - https://github.com/probot/no-response + +# Number of days of inactivity before an Issue is closed for lack of response +daysUntilClose: 3 +# Label requiring a response +responseRequiredLabel: Missing Information +# Comment to post when closing an Issue for lack of response. Set to `false` to disable +closeComment: > + This issue has been automatically closed because the information we asked + to be provided when opening it was not supplied by the original author. + With only the information that is currently in the issue, we don't have + enough information to take action. \ No newline at end of file From 060a6b10bc178475ca1c65786ab033ed99668d48 Mon Sep 17 00:00:00 2001 From: stronnag Date: Tue, 23 Jun 2020 15:34:15 +0100 Subject: [PATCH 031/248] [DOC] update Generic Linux dev guide (#5848) --- docs/development/Generic_Linux_development.md | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/docs/development/Generic_Linux_development.md b/docs/development/Generic_Linux_development.md index 5dc78125824..5e8a782249d 100644 --- a/docs/development/Generic_Linux_development.md +++ b/docs/development/Generic_Linux_development.md @@ -24,16 +24,22 @@ In addition to a cross-compiler, it is necessary to install some other tools: ### Ubuntu / Debian ``` +$ # make sure the system is updated first +$ sudo apt update && sudo apt upgrade $ sudo apt install gcc git make ruby curl ``` ### Fedora ``` +$ # make sure the system is updated first +$ sudo dnf -y update $ sudo dnf install gcc git make ruby curl ``` ### Arch ``` +$ # make sure the system is updated first +$ sudo pacman -Syu $ sudo pacman -S gcc git make ruby curl ``` From 9cc0368de45143d60109d6adcf0c7250d85dffd4 Mon Sep 17 00:00:00 2001 From: stronnag Date: Tue, 23 Jun 2020 15:38:44 +0100 Subject: [PATCH 032/248] support SET_HEAD and SET_POI (#5851) * support SET_HEAD and SET_POI * [DOC] update Navigation.md for SET_POI and SET_HEAD --- docs/Navigation.md | 6 ++- src/main/fc/cli.c | 8 ++-- src/main/navigation/navigation.c | 70 +++++++++++++++++++++++++------- src/main/navigation/navigation.h | 14 +++++++ 4 files changed, 78 insertions(+), 20 deletions(-) diff --git a/docs/Navigation.md b/docs/Navigation.md index 1b31da12899..66970585a49 100755 --- a/docs/Navigation.md +++ b/docs/Navigation.md @@ -58,12 +58,14 @@ When deciding what altitude to maintain, RTH has 4 different modes of operation Parameters: - * `` - The action to be taken at the WP. The following are enumerations are available in inav 2.5 and later: + * `` - The action to be taken at the WP. The following are enumerations are available in inav 2.6 and later: * 0 - Unused / Unassigned * 1 - WAYPOINT * 3 - POSHOLD_TIME * 4 - RTH + * 5 - SET_POI * 6 - JUMP + * 7 - SET_HEAD * 8 - LAND * `` - Latitude (WGS84), in degrees * 1E7 (for example 123456789 means 12.3456789). @@ -72,7 +74,7 @@ Parameters: * `` - Altitude in cm. - * `` - For a RTH waypoint, p1 > 0 enables landing. For a normal waypoint it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For POSHOLD TIME waypoint it is time to loiter in seconds. For JUMP it is the target WP **index** (not number). + * `` - For a RTH waypoint, p1 > 0 enables landing. For a normal waypoint it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For POSHOLD TIME waypoint it is time to loiter in seconds. For JUMP it is the target WP **index** (not number). For SET_HEAD, it is the desired heading (0-359) or -1 to cancel a previous SET_HEAD or SET_POI. * `` - For a POSHOLD TIME it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For JUMP it is the number of iterations of the JUMP. diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 41dc46a02eb..dc6f43f071f 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -1338,7 +1338,7 @@ static void cliWaypoints(char *cmdline) } else if (sl_strcasecmp(cmdline, "save") == 0) { posControl.waypointListValid = false; for (int i = 0; i < NAV_MAX_WAYPOINTS; i++) { - if (!(posControl.waypointList[i].action == NAV_WP_ACTION_WAYPOINT || posControl.waypointList[i].action == NAV_WP_ACTION_JUMP || posControl.waypointList[i].action == NAV_WP_ACTION_RTH || posControl.waypointList[i].action == NAV_WP_ACTION_HOLD_TIME || posControl.waypointList[i].action == NAV_WP_ACTION_LAND)) break; + if (!(posControl.waypointList[i].action == NAV_WP_ACTION_WAYPOINT || posControl.waypointList[i].action == NAV_WP_ACTION_JUMP || posControl.waypointList[i].action == NAV_WP_ACTION_RTH || posControl.waypointList[i].action == NAV_WP_ACTION_HOLD_TIME || posControl.waypointList[i].action == NAV_WP_ACTION_LAND || posControl.waypointList[i].action == NAV_WP_ACTION_SET_POI || posControl.waypointList[i].action == NAV_WP_ACTION_SET_HEAD)) break; if (posControl.waypointList[i].flag == NAV_WP_FLAG_LAST) { posControl.waypointCount = i + 1; posControl.waypointListValid = true; @@ -1933,9 +1933,9 @@ static void cliGvar(char *cmdline) { int32_t i = args[INDEX]; if ( i >= 0 && i < MAX_GLOBAL_VARIABLES && - args[DEFAULT] >= INT32_MIN && args[DEFAULT] <= INT32_MAX && - args[MIN] >= INT32_MIN && args[MIN] <= INT32_MAX && - args[MAX] >= INT32_MIN && args[MAX] <= INT32_MAX + args[DEFAULT] >= INT32_MIN && args[DEFAULT] <= INT32_MAX && + args[MIN] >= INT32_MIN && args[MIN] <= INT32_MAX && + args[MAX] >= INT32_MIN && args[MAX] <= INT32_MAX ) { globalVariableConfigsMutable(i)->defaultValue = args[DEFAULT]; globalVariableConfigsMutable(i)->min = args[MIN]; diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 402062c1c64..a5de607a305 100755 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -172,6 +172,7 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, } ); +static navWapointHeading_t wpHeadingControl; navigationPosControl_t posControl; navSystemStatus_t NAV_Status; @@ -208,6 +209,8 @@ void calculateInitialHoldPosition(fpVector3_t * pos); void calculateFarAwayTarget(fpVector3_t * farAwayPos, int32_t yaw, int32_t distance); void calculateNewCruiseTarget(fpVector3_t * origin, int32_t yaw, int32_t distance); static bool isWaypointPositionReached(const fpVector3_t * pos, const bool isWaypointHome); +static void mapWaypointToLocalPosition(fpVector3_t * localPos, const navWaypoint_t * waypoint); +static navigationFSMEvent_t nextForNonGeoStates(void); void initializeRTHSanityChecker(const fpVector3_t * pos); bool validateRTHSanityChecker(void); @@ -1415,6 +1418,21 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_INITIALIZE(nav } } +static navigationFSMEvent_t nextForNonGeoStates(void) +{ + /* simple helper for non-geographical states that just set other data */ + const bool isLastWaypoint = (posControl.waypointList[posControl.activeWaypointIndex].flag == NAV_WP_FLAG_LAST) || (posControl.activeWaypointIndex >= (posControl.waypointCount - 1)); + + if (isLastWaypoint) { + // non-geo state is the last waypoint, switch to finish. + return NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_FINISHED; + } else { + // Finished non-geo, move to next WP + posControl.activeWaypointIndex++; + return NAV_FSM_EVENT_NONE; // re-process the state passing to the next WP + } +} + static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_PRE_ACTION(navigationFSMState_t previousState) { /* A helper function to do waypoint-specific action */ @@ -1434,28 +1452,36 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_PRE_ACTION(nav if(posControl.waypointList[posControl.activeWaypointIndex].p3 != -1){ if(posControl.waypointList[posControl.activeWaypointIndex].p3 == 0){ resetJumpCounter(); - const bool isLastWaypoint = (posControl.waypointList[posControl.activeWaypointIndex].flag == NAV_WP_FLAG_LAST) || - (posControl.activeWaypointIndex >= (posControl.waypointCount - 1)); - - if (isLastWaypoint) { - // JUMP is the last waypoint and we reached the last jump, switch to finish. - return NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_FINISHED; - } else { - // Finished JUMP, move to next WP - posControl.activeWaypointIndex++; - return NAV_FSM_EVENT_NONE; // re-process the state passing to the next WP - } + return nextForNonGeoStates(); } else { posControl.waypointList[posControl.activeWaypointIndex].p3--; } } - posControl.activeWaypointIndex = posControl.waypointList[posControl.activeWaypointIndex].p1; - return NAV_FSM_EVENT_NONE; // re-process the state passing to the next WP + case NAV_WP_ACTION_SET_POI: + if (STATE(MULTIROTOR)) { + wpHeadingControl.mode = NAV_WP_HEAD_MODE_POI; + mapWaypointToLocalPosition(&wpHeadingControl.poi_pos, + &posControl.waypointList[posControl.activeWaypointIndex]); + } + return nextForNonGeoStates(); + + case NAV_WP_ACTION_SET_HEAD: + if (STATE(MULTIROTOR)) { + if (posControl.waypointList[posControl.activeWaypointIndex].p1 < 0 || + posControl.waypointList[posControl.activeWaypointIndex].p1 > 359) { + wpHeadingControl.mode = NAV_WP_HEAD_MODE_NONE; + } else { + wpHeadingControl.mode = NAV_WP_HEAD_MODE_FIXED; + wpHeadingControl.heading = DEGREES_TO_CENTIDEGREES(posControl.waypointList[posControl.activeWaypointIndex].p1); + } + } + return nextForNonGeoStates(); + case NAV_WP_ACTION_RTH: posControl.rthState.rthInitialDistance = posControl.homeDistance; initializeRTHSanityChecker(&navGetCurrentActualPositionAndVelocity()->pos); @@ -1487,11 +1513,25 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_IN_PROGRESS(na posControl.wpInitialDistance, posControl.wpInitialDistance / 10.0f, posControl.wpInitialAltitude, posControl.activeWaypoint.pos.z); setDesiredPosition(&tmpWaypoint, 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_BEARING); + if(STATE(MULTIROTOR)) { + switch (wpHeadingControl.mode) { + case NAV_WP_HEAD_MODE_NONE: + break; + case NAV_WP_HEAD_MODE_FIXED: + setDesiredPosition(NULL, wpHeadingControl.heading, NAV_POS_UPDATE_HEADING); + break; + case NAV_WP_HEAD_MODE_POI: + setDesiredPosition(&wpHeadingControl.poi_pos, 0, NAV_POS_UPDATE_BEARING); + break; + } + } return NAV_FSM_EVENT_NONE; // will re-process state in >10ms } break; case NAV_WP_ACTION_JUMP: + case NAV_WP_ACTION_SET_HEAD: + case NAV_WP_ACTION_SET_POI: UNREACHABLE(); case NAV_WP_ACTION_RTH: @@ -1529,6 +1569,8 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_REACHED(naviga return NAV_FSM_EVENT_SUCCESS; // NAV_STATE_WAYPOINT_NEXT case NAV_WP_ACTION_JUMP: + case NAV_WP_ACTION_SET_HEAD: + case NAV_WP_ACTION_SET_POI: UNREACHABLE(); case NAV_WP_ACTION_RTH: @@ -2753,7 +2795,7 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData) } // WP #1 - #NAV_MAX_WAYPOINTS - common waypoints - pre-programmed mission else if ((wpNumber >= 1) && (wpNumber <= NAV_MAX_WAYPOINTS) && !ARMING_FLAG(ARMED)) { - if (wpData->action == NAV_WP_ACTION_WAYPOINT || wpData->action == NAV_WP_ACTION_JUMP || wpData->action == NAV_WP_ACTION_RTH || wpData->action == NAV_WP_ACTION_HOLD_TIME || wpData->action == NAV_WP_ACTION_LAND) { + if (wpData->action == NAV_WP_ACTION_WAYPOINT || wpData->action == NAV_WP_ACTION_JUMP || wpData->action == NAV_WP_ACTION_RTH || wpData->action == NAV_WP_ACTION_HOLD_TIME || wpData->action == NAV_WP_ACTION_LAND || wpData->action == NAV_WP_ACTION_SET_POI || wpData->action == NAV_WP_ACTION_SET_HEAD ) { // Only allow upload next waypoint (continue upload mission) or first waypoint (new mission) if (wpNumber == (posControl.waypointCount + 1) || wpNumber == 1) { posControl.waypointList[wpNumber - 1] = *wpData; diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 57927b06872..6ae99506030 100755 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -237,10 +237,18 @@ typedef enum { NAV_WP_ACTION_WAYPOINT = 0x01, NAV_WP_ACTION_HOLD_TIME = 0x03, NAV_WP_ACTION_RTH = 0x04, + NAV_WP_ACTION_SET_POI = 0x05, NAV_WP_ACTION_JUMP = 0x06, + NAV_WP_ACTION_SET_HEAD = 0x07, NAV_WP_ACTION_LAND = 0x08 } navWaypointActions_e; +typedef enum { + NAV_WP_HEAD_MODE_NONE = 0, + NAV_WP_HEAD_MODE_POI = 1, + NAV_WP_HEAD_MODE_FIXED = 2 +} navWaypointHeadings_e; + typedef enum { NAV_WP_FLAG_LAST = 0xA5 } navWaypointFlags_e; @@ -254,6 +262,12 @@ typedef struct { uint8_t flag; } navWaypoint_t; +typedef struct { + navWaypointHeadings_e mode; + uint32_t heading; // fixed heading * 100 (SET_HEAD) + fpVector3_t poi_pos; // POI location in local coordinates (SET_POI) +} navWapointHeading_t; + typedef struct radar_pois_s { gpsLocation_t gps; uint8_t state; From 249371e5b95a140e81f6432fa9d1dd0f263e21f6 Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Tue, 23 Jun 2020 17:31:56 +0200 Subject: [PATCH 033/248] [DPS310] Fix baro initialization --- src/main/drivers/barometer/barometer_dps310.c | 17 ++++++++++------- src/main/target/FURYF4OSD/target.h | 1 + src/main/target/FURYF4OSD/target.mk | 1 + src/main/target/IFLIGHTF4_TWING/target.h | 1 + src/main/target/IFLIGHTF4_TWING/target.mk | 1 + src/main/target/IFLIGHTF7_TWING/target.h | 1 + src/main/target/IFLIGHTF7_TWING/target.mk | 1 + 7 files changed, 16 insertions(+), 7 deletions(-) diff --git a/src/main/drivers/barometer/barometer_dps310.c b/src/main/drivers/barometer/barometer_dps310.c index 6cc7110ae55..dcedfc373c3 100644 --- a/src/main/drivers/barometer/barometer_dps310.c +++ b/src/main/drivers/barometer/barometer_dps310.c @@ -126,13 +126,14 @@ static void registerSetBits(busDevice_t * busDev, uint8_t reg, uint8_t setbits) } } -static int32_t getTwosComplement(int32_t raw, uint8_t length) +static int32_t getTwosComplement(uint32_t raw, uint8_t length) { if (raw & ((int)1 << (length - 1))) { - raw -= (int)1 << length; + return ((int32_t)raw) - ((int32_t)1 << length); + } + else { + return raw; } - - return raw; } static bool deviceConfigure(busDevice_t * busDev) @@ -221,7 +222,7 @@ static bool deviceReadMeasurement(baroDev_t *baro) // 3. Read the pressure and temperature result from the registers // Read PSR_B2, PSR_B1, PSR_B0, TMP_B2, TMP_B1, TMP_B0 uint8_t buf[6]; - if (busReadBuf(baro->busDev, DPS310_REG_PSR_B2, buf, 6)) { + if (!busReadBuf(baro->busDev, DPS310_REG_PSR_B2, buf, 6)) { return false; } @@ -277,7 +278,7 @@ static bool deviceDetect(busDevice_t * busDev) bool ack = busReadBuf(busDev, DPS310_REG_ID, chipId, 1); - if (ack && chipId[1] == DPS310_ID_REV_AND_PROD_ID) { + if (ack && chipId[0] == DPS310_ID_REV_AND_PROD_ID) { return true; } }; @@ -302,11 +303,13 @@ bool baroDPS310Detect(baroDev_t *baro) return false; } + const uint32_t baroDelay = 1000000 / 32 / 2; // twice the sample rate to capture all new data + baro->ut_delay = 0; baro->start_ut = NULL; baro->get_ut = NULL; - baro->up_delay = 1000000 / 32 / 2; // twice the sample rate to capture all new data + baro->up_delay = baroDelay; baro->start_up = NULL; baro->get_up = deviceReadMeasurement; diff --git a/src/main/target/FURYF4OSD/target.h b/src/main/target/FURYF4OSD/target.h index c4603911cb7..c4459596105 100644 --- a/src/main/target/FURYF4OSD/target.h +++ b/src/main/target/FURYF4OSD/target.h @@ -120,6 +120,7 @@ #define USE_BARO_BMP280 #define USE_BARO_MS5611 #define USE_BARO_BMP085 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS DEFAULT_I2C_BUS diff --git a/src/main/target/FURYF4OSD/target.mk b/src/main/target/FURYF4OSD/target.mk index 0b76bb02356..272b981bb73 100644 --- a/src/main/target/FURYF4OSD/target.mk +++ b/src/main/target/FURYF4OSD/target.mk @@ -7,6 +7,7 @@ TARGET_SRC = \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ drivers/barometer/barometer_ms56xx.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_ak8963.c \ drivers/compass/compass_ak8975.c \ drivers/compass/compass_hmc5883l.c \ diff --git a/src/main/target/IFLIGHTF4_TWING/target.h b/src/main/target/IFLIGHTF4_TWING/target.h index 27d99bdcf75..cbb9d29428e 100644 --- a/src/main/target/IFLIGHTF4_TWING/target.h +++ b/src/main/target/IFLIGHTF4_TWING/target.h @@ -60,6 +60,7 @@ #define USE_BARO #define BARO_I2C_BUS BUS_I2C1 #define USE_BARO_BMP280 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS BUS_I2C1 diff --git a/src/main/target/IFLIGHTF4_TWING/target.mk b/src/main/target/IFLIGHTF4_TWING/target.mk index 89793194927..b4c202b347d 100644 --- a/src/main/target/IFLIGHTF4_TWING/target.mk +++ b/src/main/target/IFLIGHTF4_TWING/target.mk @@ -5,6 +5,7 @@ FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ drivers/compass/compass_ist8310.c \ diff --git a/src/main/target/IFLIGHTF7_TWING/target.h b/src/main/target/IFLIGHTF7_TWING/target.h index a6a9e63de23..bac28ceea0f 100644 --- a/src/main/target/IFLIGHTF7_TWING/target.h +++ b/src/main/target/IFLIGHTF7_TWING/target.h @@ -63,6 +63,7 @@ #define USE_BARO #define BARO_I2C_BUS BUS_I2C2 #define USE_BARO_BMP280 +#define USE_BARO_DPS310 #define USE_MAG #define MAG_I2C_BUS BUS_I2C2 diff --git a/src/main/target/IFLIGHTF7_TWING/target.mk b/src/main/target/IFLIGHTF7_TWING/target.mk index 57bc66e9e85..77545402ae2 100644 --- a/src/main/target/IFLIGHTF7_TWING/target.mk +++ b/src/main/target/IFLIGHTF7_TWING/target.mk @@ -4,6 +4,7 @@ FEATURES += ONBOARDFLASH VCP MSC TARGET_SRC = \ drivers/accgyro/accgyro_mpu6500.c \ drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_dps310.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ drivers/compass/compass_ist8310.c \ From 142aae2c283c6b54ff24e93d69f028a9be9c9c94 Mon Sep 17 00:00:00 2001 From: Nicola Guerrera Date: Wed, 24 Jun 2020 19:08:37 +0200 Subject: [PATCH 034/248] Small error in the Logic Condition docs --- docs/Logic Conditions.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/Logic Conditions.md b/docs/Logic Conditions.md index c04fa063535..97f24933bb4 100644 --- a/docs/Logic Conditions.md +++ b/docs/Logic Conditions.md @@ -9,7 +9,7 @@ Logic conditions can be edited using INAV Configurator user interface, of via CL ## CLI -`logic ` +`logic ` * `` - ID of Logic Condition rule * `` - `0` evaluates as disabled, `1` evaluates as enabled @@ -102,4 +102,4 @@ All flags are reseted on ARM and DISARM event. | bit | Decimal | Function | |---- |---- |---- | -| 0 | 1 | Latch - after activation LC will stay active until LATCH flag is reseted | \ No newline at end of file +| 0 | 1 | Latch - after activation LC will stay active until LATCH flag is reseted | From 004ea0df35c76268e956ceaa5917b84ed4328a38 Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Thu, 25 Jun 2020 11:53:21 +0200 Subject: [PATCH 035/248] Rename the target and add to release list --- make/release.mk | 7 ++++--- .../{IFLIGHT_SucceX_D => IFLIGHTF4_SUCCEXD}/target.c | 0 .../{IFLIGHT_SucceX_D => IFLIGHTF4_SUCCEXD}/target.h | 0 .../{IFLIGHT_SucceX_D => IFLIGHTF4_SUCCEXD}/target.mk | 0 4 files changed, 4 insertions(+), 3 deletions(-) rename src/main/target/{IFLIGHT_SucceX_D => IFLIGHTF4_SUCCEXD}/target.c (100%) rename src/main/target/{IFLIGHT_SucceX_D => IFLIGHTF4_SUCCEXD}/target.h (100%) rename src/main/target/{IFLIGHT_SucceX_D => IFLIGHTF4_SUCCEXD}/target.mk (100%) diff --git a/make/release.mk b/make/release.mk index f80fa989a24..0edda29c66f 100644 --- a/make/release.mk +++ b/make/release.mk @@ -15,7 +15,9 @@ RELEASE_TARGETS += OMNIBUSF4 OMNIBUSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 DYSF4PRO DYSF4 RELEASE_TARGETS += OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS RELEASE_TARGETS += OMNIBUSF7 OMNIBUSF7V2 OMNIBUSF7NXT YUPIF7 +# MATEK targets RELEASE_TARGETS += MATEKF405 MATEKF405_SERVOS6 MATEKF405OSD MATEKF722 MATEKF722_HEXSERVO MATEKF722SE MATEKF722MINI MATEKF405SE MATEKF411 MATEKF411_SFTSRL2 MATEKF411_FD_SFTSRL MATEKF411_RSSI MATEKF411SE MATEKF765 MATEKF722PX +RELEASE_TARGETS += MATEKF765 RELEASE_TARGETS += FOXEERF405 FOXEERF722DUAL @@ -27,10 +29,9 @@ RELEASE_TARGETS += OMNIBUSF4V6 RELEASE_TARGETS += MAMBAF405 MAMBAF405US MAMBAF722 -RELEASE_TARGETS += IFLIGHTF7_TWING IFLIGHTF4_TWING +# IFLIGHT targets +RELEASE_TARGETS += IFLIGHTF7_TWING IFLIGHTF4_TWING IFLIGHTF4_SUCCEXD RELEASE_TARGETS += AIKONF4 -RELEASE_TARGETS += MATEKF765 - RELEASE_TARGETS += ZEEZF7 diff --git a/src/main/target/IFLIGHT_SucceX_D/target.c b/src/main/target/IFLIGHTF4_SUCCEXD/target.c similarity index 100% rename from src/main/target/IFLIGHT_SucceX_D/target.c rename to src/main/target/IFLIGHTF4_SUCCEXD/target.c diff --git a/src/main/target/IFLIGHT_SucceX_D/target.h b/src/main/target/IFLIGHTF4_SUCCEXD/target.h similarity index 100% rename from src/main/target/IFLIGHT_SucceX_D/target.h rename to src/main/target/IFLIGHTF4_SUCCEXD/target.h diff --git a/src/main/target/IFLIGHT_SucceX_D/target.mk b/src/main/target/IFLIGHTF4_SUCCEXD/target.mk similarity index 100% rename from src/main/target/IFLIGHT_SucceX_D/target.mk rename to src/main/target/IFLIGHTF4_SUCCEXD/target.mk From dc2052ba1c6a3b1873a256b9c7d4b4bc0ded93da Mon Sep 17 00:00:00 2001 From: Magnus Ivarsson Date: Sun, 5 Jul 2020 23:08:50 +0200 Subject: [PATCH 036/248] Remove pin conflict between non existent current adc pin and the pwm output 6 https://github.com/iNavFlight/inav/issues/5911 --- src/main/target/PIKOBLX/target.h | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/main/target/PIKOBLX/target.h b/src/main/target/PIKOBLX/target.h index 1d7f31c5315..c60d00116b5 100644 --- a/src/main/target/PIKOBLX/target.h +++ b/src/main/target/PIKOBLX/target.h @@ -64,9 +64,10 @@ #define BOARD_HAS_VOLTAGE_DIVIDER #define USE_ADC #define ADC_INSTANCE ADC2 -#define ADC_CHANNEL_1_PIN PA2 +//#define ADC_CHANNEL_1_PIN PA2 <-- conflict with pwm output 6, and the board does not have current sensor #define ADC_CHANNEL_2_PIN PA5 -#define ADC_CHANNEL_3_PIN PB2 +//#define ADC_CHANNEL_3_PIN PB2 <-- the board does not have a rssi pad + #define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 #define VBAT_ADC_CHANNEL ADC_CHN_2 #define RSSI_ADC_CHANNEL ADC_CHN_3 From 44569790b189d6f4638855ac78763566773b24bf Mon Sep 17 00:00:00 2001 From: Daniel Arruda Ribeiro Date: Mon, 6 Jul 2020 18:04:07 -0300 Subject: [PATCH 037/248] Add Azimuth OSD element --- src/main/cms/cms_menu_osd.c | 1 + src/main/drivers/osd_symbols.h | 2 +- src/main/io/osd.c | 24 ++++++++++++++++++++++++ src/main/io/osd.h | 1 + 4 files changed, 27 insertions(+), 1 deletion(-) diff --git a/src/main/cms/cms_menu_osd.c b/src/main/cms/cms_menu_osd.c index 901bb0e1715..33eab416707 100755 --- a/src/main/cms/cms_menu_osd.c +++ b/src/main/cms/cms_menu_osd.c @@ -184,6 +184,7 @@ static const OSD_Entry menuOsdElemsEntries[] = OSD_ELEMENT_ENTRY("GPS HDOP", OSD_GPS_HDOP), OSD_ELEMENT_ENTRY("3D SPEED", OSD_3D_SPEED), OSD_ELEMENT_ENTRY("PLUS CODE", OSD_PLUS_CODE), + OSD_ELEMENT_ENTRY("AZIMUTH", OSD_AZIMUTH), #endif // GPS OSD_ELEMENT_ENTRY("HEADING", OSD_HEADING), OSD_ELEMENT_ENTRY("HEADING GR.", OSD_HEADING_GRAPH), diff --git a/src/main/drivers/osd_symbols.h b/src/main/drivers/osd_symbols.h index 0b08e7b51dc..d82d1c197f5 100644 --- a/src/main/drivers/osd_symbols.h +++ b/src/main/drivers/osd_symbols.h @@ -118,7 +118,7 @@ #define SYM_RPM 0x8B // 139 RPM #define SYM_WAYPOINT 0x8C // 140 Waypoint -// 0x8D // 141 - +#define SYM_AZIMUTH 0x8D // 141 Azimuth // 0x8E // 142 - // 0x8F // 143 - diff --git a/src/main/io/osd.c b/src/main/io/osd.c index f7a0f2d9434..c3033400dda 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2405,6 +2405,28 @@ static bool osdDrawSingleElement(uint8_t item) break; } + case OSD_AZIMUTH: + { + + buff[0] = SYM_AZIMUTH; + if (osdIsHeadingValid()) { + int16_t h = GPS_directionToHome; + if (h < 0) { + h += 360; + } + if(h >= 180) + h = h - 180; + else + h = h + 180; + + tfp_sprintf(&buff[1], "%3d", h); + } else { + buff[1] = buff[2] = buff[3] = '-'; + } + buff[4] = '\0'; + break; + } + case OSD_MAP_SCALE: { float scaleToUnit; @@ -2644,6 +2666,8 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig) osdConfig->item_pos[0][OSD_FLYMODE] = OSD_POS(13, 12) | OSD_VISIBLE_FLAG; osdConfig->item_pos[0][OSD_GPS_LON] = OSD_POS(18, 12); + osdConfig->item_pos[0][OSD_AZIMUTH] = OSD_POS(2, 12); + osdConfig->item_pos[0][OSD_ROLL_PIDS] = OSD_POS(2, 10); osdConfig->item_pos[0][OSD_PITCH_PIDS] = OSD_POS(2, 11); osdConfig->item_pos[0][OSD_YAW_PIDS] = OSD_POS(2, 12); diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 00dc2fd6d75..c641875e602 100755 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -152,6 +152,7 @@ typedef enum { OSD_VTX_POWER, OSD_ESC_RPM, OSD_ESC_TEMPERATURE, + OSD_AZIMUTH, OSD_ITEM_COUNT // MUST BE LAST } osd_items_e; From 268cc00f6a983c69eeeaddc7128e8232813b34c5 Mon Sep 17 00:00:00 2001 From: Olivier C Date: Tue, 7 Jul 2020 12:44:11 +0200 Subject: [PATCH 038/248] Settings.yaml, adding descriptions and defaults for the hud --- src/main/fc/settings.yaml | 31 +++++++++++++++++++++++++++++-- 1 file changed, 29 insertions(+), 2 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 4af45ae2fd9..5ff8f441b38 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2678,59 +2678,86 @@ groups: min: 10 max: 90 - name: osd_crosshairs_style + description: "To set the visual type for the crosshair" + default_value: "DEFAULT" field: crosshairs_style table: osd_crosshairs_style type: uint8_t - name: osd_horizon_offset + description: "To vertically adjust the whole OSD and AHI and scrolling bars" + default_value: "0" field: horizon_offset min: -2 max: 2 - name: osd_camera_uptilt + description: "Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal" + default_value: "0" field: camera_uptilt min: -40 max: 80 - name: osd_camera_fov_h + description: "Horizontal field of view for the camera in degres" + default_value: "135" field: camera_fov_h min: 60 max: 150 - name: osd_camera_fov_v + description: "Vertical field of view for the camera in degres" + default_value: "85" field: camera_fov_v min: 30 max: 120 - name: osd_hud_margin_h + description: "Left and right margins for the hud area" + default_value: "3" field: hud_margin_h min: 0 max: 4 - name: osd_hud_margin_v + description: "Top and bottom margins for the hud area" + default_value: "3" field: hud_margin_v min: 1 max: 3 - name: osd_hud_homing + description: "To display little arrows around the crossair showing where the home point is in the hud" + default_value: "0" field: hud_homing type: bool - name: osd_hud_homepoint + description: "To 3D-display the home point location in the hud" + default_value: "0" field: hud_homepoint type: bool - name: osd_hud_radar_disp + description: "Maximum count of nearby aircrafts or points of interest to display in the hud, as sent from an ESP32 LoRa module. Set to 0 to disable (show nothing). The nearby aircrafts will appear as markers A, B, C, etc" + default_value: "0" field: hud_radar_disp min: 0 max: 4 - name: osd_hud_radar_range_min + description: "In meters, radar aircrafts closer than this will not be displayed in the hud" + default_value: "3" field: hud_radar_range_min min: 1 max: 30 - name: osd_hud_radar_range_max + description: "In meters, radar aircrafts further away than this will not be displayed in the hud" + default_value: 4000" field: hud_radar_range_max min: 100 max: 9990 - name: osd_hud_radar_nearest + description: "To display an extra bar of informations at the bottom of the hud area for the closest radar aircraft found, if closest than the set value, in meters. Shows relative altitude (meters or feet, with an up or down arrow to indicate if above or below), speed (in m/s or f/s), and absolute heading (in °, 0 is north, 90 is east, 180 is south, 270 is west). Set to 0 (zero) to disable." + default_value: "0" field: hud_radar_nearest min: 0 max: 4000 - name: osd_hud_wp_disp - description: "Controls display of the next waypoints in the HUD." - default_value: "OFF" + description: "How many navigation waypoints are displayed, set to 0 (zero) to disable. As sample, if set to 2, and you just passed the 3rd waypoint of the mission, you'll see markers for the 4th waypoint (marked "1") and the 5th waypoint (marked "2")" + default_value: "0" field: hud_wp_disp + min: 0 max: 3 - name: osd_left_sidebar_scroll From e5c0d0d58aa13afcc582e001c606a7b4cde2d2c0 Mon Sep 17 00:00:00 2001 From: Olivier C Date: Tue, 7 Jul 2020 14:39:38 +0200 Subject: [PATCH 039/248] Removing quotes --- src/main/fc/settings.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 5ff8f441b38..5f2bcd596af 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2754,7 +2754,7 @@ groups: min: 0 max: 4000 - name: osd_hud_wp_disp - description: "How many navigation waypoints are displayed, set to 0 (zero) to disable. As sample, if set to 2, and you just passed the 3rd waypoint of the mission, you'll see markers for the 4th waypoint (marked "1") and the 5th waypoint (marked "2")" + description: "How many navigation waypoints are displayed, set to 0 (zero) to disable. As sample, if set to 2, and you just passed the 3rd waypoint of the mission, you'll see markers for the 4th waypoint (marked 1) and the 5th waypoint (marked 2)" default_value: "0" field: hud_wp_disp From 5a48f994c146d5c2c2f79cf5f020f4e34e7afc19 Mon Sep 17 00:00:00 2001 From: ShikOfTheRa Date: Tue, 7 Jul 2020 14:19:53 +0100 Subject: [PATCH 040/248] Update Building in Windows 10 with Linux Subsystem.md --- .../Building in Windows 10 with Linux Subsystem.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/development/Building in Windows 10 with Linux Subsystem.md b/docs/development/Building in Windows 10 with Linux Subsystem.md index 5ed64eb83fb..39ca71cf9b9 100644 --- a/docs/development/Building in Windows 10 with Linux Subsystem.md +++ b/docs/development/Building in Windows 10 with Linux Subsystem.md @@ -12,7 +12,7 @@ reboot Install Ubuntu: 1. Go to Microsoft store https://www.microsoft.com/en-gb/store/b/home -1. Search and install most recent Ubunto LTS version +1. Search and install most recent Ubuntu LTS version 1. When download completed, select `Launch Ubuntu` 1. When prompted enter a user name and password which you will need to remember 1. When complete, the linux command prompt will be displayed @@ -41,7 +41,7 @@ You now have a folder called inav in the root of C drive that you can edit in wi ## Building (example): Launch Ubuntu: -Click Windows Start button then scroll and lauch "Ubunto" +Click Windows Start button then scroll and lauch "Ubuntu" Building from Ubunto command line `cd /mnt/c/inav` From 7e3c0789e67e78f5bce2530511ed76a2799c446e Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Tue, 7 Jul 2020 18:13:08 +0100 Subject: [PATCH 041/248] [DOC] document log_level and log_topic --- src/main/fc/settings.yaml | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 5f2bcd596af..ce545ab777a 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2222,7 +2222,7 @@ groups: field: fw.cruise_speed min: 0 max: 65535 - - name: nav_fw_control_smoothness + - name: nav_fw_control_smoothness description: "How smoothly the autopilot controls the airplane to correct the navigation error" default_value: "0" field: fw.control_smoothness @@ -2679,25 +2679,25 @@ groups: max: 90 - name: osd_crosshairs_style description: "To set the visual type for the crosshair" - default_value: "DEFAULT" + default_value: "DEFAULT" field: crosshairs_style table: osd_crosshairs_style type: uint8_t - name: osd_horizon_offset description: "To vertically adjust the whole OSD and AHI and scrolling bars" - default_value: "0" + default_value: "0" field: horizon_offset min: -2 max: 2 - name: osd_camera_uptilt description: "Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal" - default_value: "0" + default_value: "0" field: camera_uptilt min: -40 max: 80 - name: osd_camera_fov_h description: "Horizontal field of view for the camera in degres" - default_value: "135" + default_value: "135" field: camera_fov_h min: 60 max: 150 @@ -2971,11 +2971,14 @@ groups: - name: log_level field: level table: log_level + description: "Defines serial debugging log level. See `docs/development/serial_printf_debugging.md` for usage." + default_value: "`ERROR`" - name: log_topics field: topics min: 0 max: UINT32_MAX - + description: "Defines serial debugging log topic. See `docs/development/serial_printf_debugging.md` for usage." + default_value: "0" - name: PG_ESC_SENSOR_CONFIG type: escSensorConfig_t headers: ["sensors/esc_sensor.h"] From 29c94d7284e01b8da1b1d91d8a13615685816dec Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Wed, 8 Jul 2020 15:03:23 +0200 Subject: [PATCH 042/248] [DPS310] Fix temperature readings --- src/main/drivers/barometer/barometer_dps310.c | 32 ++++++++++++++++--- src/main/sensors/barometer.c | 1 + src/main/sensors/temperature.c | 4 +-- 3 files changed, 31 insertions(+), 6 deletions(-) diff --git a/src/main/drivers/barometer/barometer_dps310.c b/src/main/drivers/barometer/barometer_dps310.c index dcedfc373c3..5fbe12fc69f 100644 --- a/src/main/drivers/barometer/barometer_dps310.c +++ b/src/main/drivers/barometer/barometer_dps310.c @@ -68,7 +68,11 @@ #define DPS310_MEAS_CFG_SENSOR_RDY (1 << 6) #define DPS310_MEAS_CFG_TMP_RDY (1 << 5) #define DPS310_MEAS_CFG_PRS_RDY (1 << 4) + +#define DPS310_MEAS_CFG_MEAS_CTRL_MASK (0x7) #define DPS310_MEAS_CFG_MEAS_CTRL_CONT (0x7) +#define DPS310_MEAS_CFG_MEAS_TEMP_SING (0x2) +#define DPS310_MEAS_CFG_MEAS_IDLE (0x0) #define DPS310_PRS_CFG_BIT_PM_RATE_32HZ (0x50) // 101 - 32 measurements pr. sec. #define DPS310_PRS_CFG_BIT_PM_PRC_16 (0x04) // 0100 - 16 times (Standard). @@ -116,16 +120,21 @@ static void registerWrite(busDevice_t * busDev, uint8_t reg, uint8_t value) busWrite(busDev, reg, value); } -static void registerSetBits(busDevice_t * busDev, uint8_t reg, uint8_t setbits) +static void registerWriteBits(busDevice_t * busDev, uint8_t reg, uint8_t mask, uint8_t bits) { uint8_t val = registerRead(busDev, reg); - if ((val & setbits) != setbits) { - val |= setbits; + if ((val & mask) != bits) { + val = (val & (~mask)) | bits; registerWrite(busDev, reg, val); } } +static void registerSetBits(busDevice_t * busDev, uint8_t reg, uint8_t setbits) +{ + registerWriteBits(busDev, reg, setbits, setbits); +} + static int32_t getTwosComplement(uint32_t raw, uint8_t length) { if (raw & ((int)1 << (length - 1))) { @@ -190,6 +199,21 @@ static bool deviceConfigure(busDevice_t * busDev) // 0x20 c30 [15:8] + 0x21 c30 [7:0] baroState.calib.c30 = getTwosComplement(((uint32_t)coef[16] << 8) | (uint32_t)coef[17], 16); + // MEAS_CFG: Make sure the device is in IDLE mode + registerWriteBits(busDev, DPS310_REG_MEAS_CFG, DPS310_MEAS_CFG_MEAS_CTRL_MASK, DPS310_MEAS_CFG_MEAS_IDLE); + + // Fix IC with a fuse bit problem, which lead to a wrong temperature + // Should not affect ICs without this problem + registerWrite(busDev, 0x0E, 0xA5); + registerWrite(busDev, 0x0F, 0x96); + registerWrite(busDev, 0x62, 0x02); + registerWrite(busDev, 0x0E, 0x00); + registerWrite(busDev, 0x0F, 0x00); + + // Make ONE temperature measurement and flush it + registerWriteBits(busDev, DPS310_REG_MEAS_CFG, DPS310_MEAS_CFG_MEAS_CTRL_MASK, DPS310_MEAS_CFG_MEAS_TEMP_SING); + delay(40); + // PRS_CFG: pressure measurement rate (32 Hz) and oversampling (16 time standard) registerSetBits(busDev, DPS310_REG_PRS_CFG, DPS310_PRS_CFG_BIT_PM_RATE_32HZ | DPS310_PRS_CFG_BIT_PM_PRC_16); @@ -201,7 +225,7 @@ static bool deviceConfigure(busDevice_t * busDev) registerSetBits(busDev, DPS310_REG_CFG_REG, DPS310_CFG_REG_BIT_T_SHIFT | DPS310_CFG_REG_BIT_P_SHIFT); // MEAS_CFG: Continuous pressure and temperature measurement - registerSetBits(busDev, DPS310_REG_MEAS_CFG, DPS310_MEAS_CFG_MEAS_CTRL_CONT); + registerWriteBits(busDev, DPS310_REG_MEAS_CFG, DPS310_MEAS_CFG_MEAS_CTRL_MASK, DPS310_MEAS_CFG_MEAS_CTRL_CONT); return true; } diff --git a/src/main/sensors/barometer.c b/src/main/sensors/barometer.c index 567264f783c..49d8d0cc591 100644 --- a/src/main/sensors/barometer.c +++ b/src/main/sensors/barometer.c @@ -20,6 +20,7 @@ #include #include "platform.h" +#include "build/debug.h" #include "common/calibration.h" #include "common/log.h" diff --git a/src/main/sensors/temperature.c b/src/main/sensors/temperature.c index 28cf60802d0..5cb146cf164 100644 --- a/src/main/sensors/temperature.c +++ b/src/main/sensors/temperature.c @@ -210,13 +210,13 @@ PROTOTHREAD(temperatureUpdate) } else mpuBaroTempValid &= ~(1 << MPU_TEMP_VALID_BIT); - #ifdef USE_BARO +#ifdef USE_BARO if (sensors(SENSOR_BARO)) { baroTemperature = baroGetTemperature(); mpuBaroTempValid |= (1 << BARO_TEMP_VALID_BIT); } else mpuBaroTempValid &= ~(1 << BARO_TEMP_VALID_BIT); - #endif +#endif #ifdef USE_TEMPERATURE_SENSOR From 47cd8f317de376511e650266545f84805c2077b4 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 8 Jul 2020 15:18:52 +0200 Subject: [PATCH 043/248] Refactor LC, GF and GVAR to use single scheduler task --- make/source.mk | 7 ++-- src/main/fc/cli.c | 24 ++++++------- src/main/fc/fc_core.c | 4 +-- src/main/fc/fc_init.c | 4 +-- src/main/fc/fc_msp.c | 16 ++++----- src/main/fc/fc_tasks.c | 26 ++++---------- src/main/flight/mixer.c | 6 ++-- src/main/flight/pid.c | 4 +-- src/main/flight/servos.c | 8 ++--- src/main/flight/servos.h | 4 +-- .../global_functions.c | 6 ++-- .../global_functions.h | 2 +- .../global_variables.c | 4 +-- .../global_variables.h | 0 .../{common => programming}/logic_condition.c | 6 ++-- .../{common => programming}/logic_condition.h | 0 src/main/programming/programming_task.c | 35 +++++++++++++++++++ src/main/programming/programming_task.h | 27 ++++++++++++++ src/main/scheduler/scheduler.h | 7 ++-- src/main/target/common.h | 3 +- 20 files changed, 120 insertions(+), 73 deletions(-) rename src/main/{common => programming}/global_functions.c (98%) rename src/main/{common => programming}/global_functions.h (98%) rename src/main/{common => programming}/global_variables.c (96%) rename src/main/{common => programming}/global_variables.h (100%) rename src/main/{common => programming}/logic_condition.c (99%) rename src/main/{common => programming}/logic_condition.h (100%) create mode 100644 src/main/programming/programming_task.c create mode 100644 src/main/programming/programming_task.h diff --git a/make/source.mk b/make/source.mk index 6c4800aa35a..e1b9aa12847 100644 --- a/make/source.mk +++ b/make/source.mk @@ -14,9 +14,6 @@ COMMON_SRC = \ common/filter.c \ common/gps_conversion.c \ common/log.c \ - common/logic_condition.c \ - common/global_functions.c \ - common/global_variables.c \ common/maths.c \ common/memory.c \ common/olc.c \ @@ -26,6 +23,10 @@ COMMON_SRC = \ common/time.c \ common/typeconversion.c \ common/uvarint.c \ + programming/logic_condition.c \ + programming/global_functions.c \ + programming/global_variables.c \ + programming/programming_task.c \ config/config_eeprom.c \ config/config_streamer.c \ config/feature.c \ diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index dc6f43f071f..a63a0946ff4 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -43,8 +43,8 @@ extern uint8_t __config_end; #include "common/memory.h" #include "common/time.h" #include "common/typeconversion.h" -#include "common/global_functions.h" -#include "common/global_variables.h" +#include "programming/global_functions.h" +#include "programming/global_variables.h" #include "config/config_eeprom.h" #include "config/feature.h" @@ -1682,7 +1682,7 @@ static void printServoMix(uint8_t dumpMask, const servoMixer_t *customServoMixer && customServoMixer.inputSource == customServoMixerDefault.inputSource && customServoMixer.rate == customServoMixerDefault.rate && customServoMixer.speed == customServoMixerDefault.speed - #ifdef USE_LOGIC_CONDITIONS + #ifdef USE_PROGRAMMING_FRAMEWORK && customServoMixer.conditionId == customServoMixerDefault.conditionId #endif ; @@ -1693,7 +1693,7 @@ static void printServoMix(uint8_t dumpMask, const servoMixer_t *customServoMixer customServoMixerDefault.inputSource, customServoMixerDefault.rate, customServoMixerDefault.speed, - #ifdef USE_LOGIC_CONDITIONS + #ifdef USE_PROGRAMMING_FRAMEWORK customServoMixer.conditionId #else 0 @@ -1706,7 +1706,7 @@ static void printServoMix(uint8_t dumpMask, const servoMixer_t *customServoMixer customServoMixer.inputSource, customServoMixer.rate, customServoMixer.speed, - #ifdef USE_LOGIC_CONDITIONS + #ifdef USE_PROGRAMMING_FRAMEWORK customServoMixer.conditionId #else 0 @@ -1753,7 +1753,7 @@ static void cliServoMix(char *cmdline) customServoMixersMutable(i)->inputSource = args[INPUT]; customServoMixersMutable(i)->rate = args[RATE]; customServoMixersMutable(i)->speed = args[SPEED]; - #ifdef USE_LOGIC_CONDITIONS + #ifdef USE_PROGRAMMING_FRAMEWORK customServoMixersMutable(i)->conditionId = args[CONDITION]; #endif cliServoMix(""); @@ -1763,7 +1763,7 @@ static void cliServoMix(char *cmdline) } } -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK static void printLogic(uint8_t dumpMask, const logicCondition_t *logicConditions, const logicCondition_t *defaultLogicConditions) { @@ -1950,7 +1950,7 @@ static void cliGvar(char *cmdline) { #endif -#ifdef USE_GLOBAL_FUNCTIONS +#ifdef USE_PROGRAMMING_FRAMEWORK static void printGlobalFunctions(uint8_t dumpMask, const globalFunction_t *globalFunctions, const globalFunction_t *defaultGlobalFunctions) { @@ -3321,7 +3321,7 @@ static void printConfig(const char *cmdline, bool doDiff) cliPrintHashLine("servo"); printServo(dumpMask, servoParams_CopyArray, servoParams(0)); -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK cliPrintHashLine("logic"); printLogic(dumpMask, logicConditions_CopyArray, logicConditions(0)); @@ -3329,7 +3329,7 @@ static void printConfig(const char *cmdline, bool doDiff) printGvar(dumpMask, globalVariableConfigs_CopyArray, globalVariableConfigs(0)); #endif -#ifdef USE_GLOBAL_FUNCTIONS +#ifdef USE_PROGRAMMING_FRAMEWORK cliPrintHashLine("gf"); printGlobalFunctions(dumpMask, globalFunctions_CopyArray, globalFunctions(0)); #endif @@ -3576,7 +3576,7 @@ const clicmd_t cmdTable[] = { CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port", " [baud] [mode] : passthrough to serial", cliSerialPassthrough), #endif CLI_COMMAND_DEF("servo", "configure servos", NULL, cliServo), -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK CLI_COMMAND_DEF("logic", "configure logic conditions", " \r\n" "\treset\r\n", cliLogic), @@ -3585,7 +3585,7 @@ const clicmd_t cmdTable[] = { " \r\n" "\treset\r\n", cliGvar), #endif -#ifdef USE_GLOBAL_FUNCTIONS +#ifdef USE_PROGRAMMING_FRAMEWORK CLI_COMMAND_DEF("gf", "configure global functions", " \r\n" "\treset\r\n", cliGlobalFunctions), diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index dc508179638..9aece7e69dd 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -32,7 +32,7 @@ FILE_COMPILE_FOR_SPEED #include "common/color.h" #include "common/utils.h" #include "common/filter.h" -#include "common/global_functions.h" +#include "programming/global_functions.h" #include "drivers/light_led.h" #include "drivers/serial.h" @@ -446,7 +446,7 @@ void releaseSharedTelemetryPorts(void) { void tryArm(void) { updateArmingStatus(); -#ifdef USE_GLOBAL_FUNCTIONS +#ifdef USE_PROGRAMMING_FRAMEWORK if ( !isArmingDisabled() || emergencyArmingIsEnabled() || diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index ac4656bcac3..1ee4dd016dd 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -35,7 +35,7 @@ #include "common/maths.h" #include "common/memory.h" #include "common/printf.h" -#include "common/global_variables.h" +#include "programming/global_variables.h" #include "config/config_eeprom.h" #include "config/feature.h" @@ -286,7 +286,7 @@ void init(void) logInit(); #endif -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK gvInit(); #endif diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 066e02dd5ff..f20e576d5e1 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -35,8 +35,8 @@ #include "common/bitarray.h" #include "common/time.h" #include "common/utils.h" -#include "common/global_functions.h" -#include "common/global_variables.h" +#include "programming/global_functions.h" +#include "programming/global_variables.h" #include "config/parameter_group_ids.h" @@ -520,14 +520,14 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU8(dst, customServoMixers(i)->inputSource); sbufWriteU16(dst, customServoMixers(i)->rate); sbufWriteU8(dst, customServoMixers(i)->speed); - #ifdef USE_LOGIC_CONDITIONS + #ifdef USE_PROGRAMMING_FRAMEWORK sbufWriteU8(dst, customServoMixers(i)->conditionId); #else sbufWriteU8(dst, -1); #endif } break; -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK case MSP2_INAV_LOGIC_CONDITIONS: for (int i = 0; i < MAX_LOGIC_CONDITIONS; i++) { sbufWriteU8(dst, logicConditions(i)->enabled); @@ -551,7 +551,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF } break; #endif -#ifdef USE_GLOBAL_FUNCTIONS +#ifdef USE_PROGRAMMING_FRAMEWORK case MSP2_INAV_GLOBAL_FUNCTIONS: for (int i = 0; i < MAX_GLOBAL_FUNCTIONS; i++) { sbufWriteU8(dst, globalFunctions(i)->enabled); @@ -1928,7 +1928,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) customServoMixersMutable(tmp_u8)->inputSource = sbufReadU8(src); customServoMixersMutable(tmp_u8)->rate = sbufReadU16(src); customServoMixersMutable(tmp_u8)->speed = sbufReadU8(src); - #ifdef USE_LOGIC_CONDITIONS + #ifdef USE_PROGRAMMING_FRAMEWORK customServoMixersMutable(tmp_u8)->conditionId = sbufReadU8(src); #else sbufReadU8(src); @@ -1937,7 +1937,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) } else return MSP_RESULT_ERROR; break; -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK case MSP2_INAV_SET_LOGIC_CONDITIONS: sbufReadU8Safe(&tmp_u8, src); if ((dataSize == 15) && (tmp_u8 < MAX_LOGIC_CONDITIONS)) { @@ -1953,7 +1953,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) return MSP_RESULT_ERROR; break; #endif -#ifdef USE_GLOBAL_FUNCTIONS +#ifdef USE_PROGRAMMING_FRAMEWORK case MSP2_INAV_SET_GLOBAL_FUNCTIONS: sbufReadU8Safe(&tmp_u8, src); if ((dataSize == 10) && (tmp_u8 < MAX_GLOBAL_FUNCTIONS)) { diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index 7a5c64b06db..f79c596b9f6 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -26,8 +26,7 @@ #include "common/axis.h" #include "common/color.h" #include "common/utils.h" -#include "common/logic_condition.h" -#include "common/global_functions.h" +#include "programming/programming_task.h" #include "drivers/accgyro/accgyro.h" #include "drivers/compass/compass.h" @@ -355,11 +354,8 @@ void fcTasksInit(void) #ifdef USE_RCDEVICE setTaskEnabled(TASK_RCDEVICE, rcdeviceIsEnabled()); #endif -#ifdef USE_LOGIC_CONDITIONS - setTaskEnabled(TASK_LOGIC_CONDITIONS, true); -#endif -#ifdef USE_GLOBAL_FUNCTIONS - setTaskEnabled(TASK_GLOBAL_FUNCTIONS, true); +#ifdef USE_PROGRAMMING_FRAMEWORK + setTaskEnabled(TASK_PROGRAMMING_FRAMEWORK, true); #endif #ifdef USE_IRLOCK setTaskEnabled(TASK_IRLOCK, irlockHasBeenDetected()); @@ -578,18 +574,10 @@ cfTask_t cfTasks[TASK_COUNT] = { .staticPriority = TASK_PRIORITY_IDLE, }, #endif -#ifdef USE_LOGIC_CONDITIONS - [TASK_LOGIC_CONDITIONS] = { - .taskName = "LOGIC", - .taskFunc = logicConditionUpdateTask, - .desiredPeriod = TASK_PERIOD_HZ(10), // 10Hz @100msec - .staticPriority = TASK_PRIORITY_IDLE, - }, -#endif -#ifdef USE_GLOBAL_FUNCTIONS - [TASK_GLOBAL_FUNCTIONS] = { - .taskName = "G_FNK", - .taskFunc = globalFunctionsUpdateTask, +#ifdef USE_PROGRAMMING_FRAMEWORK + [TASK_PROGRAMMING_FRAMEWORK] = { + .taskName = "PROGRAMMING", + .taskFunc = programmingFrameworkUpdateTask, .desiredPeriod = TASK_PERIOD_HZ(10), // 10Hz @100msec .staticPriority = TASK_PRIORITY_IDLE, }, diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 24aab18727e..b24b78c911d 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -29,7 +29,7 @@ FILE_COMPILE_FOR_SPEED #include "common/filter.h" #include "common/maths.h" #include "common/utils.h" -#include "common/global_functions.h" +#include "programming/global_functions.h" #include "config/feature.h" #include "config/parameter_group.h" @@ -479,7 +479,7 @@ void FAST_CODE mixTable(const float dT) int16_t throttleMin, throttleMax; // Find min and max throttle based on condition. -#ifdef USE_GLOBAL_FUNCTIONS +#ifdef USE_PROGRAMMING_FRAMEWORK if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE)) { throttleRangeMin = throttleIdleValue; throttleRangeMax = motorConfig()->maxthrottle; @@ -514,7 +514,7 @@ void FAST_CODE mixTable(const float dT) throttleRangeMax = motorConfig()->maxthrottle; // Throttle scaling to limit max throttle when battery is full - #ifdef USE_GLOBAL_FUNCTIONS + #ifdef USE_PROGRAMMING_FRAMEWORK mixerThrottleCommand = ((mixerThrottleCommand - throttleRangeMin) * getThrottleScale(motorConfig()->throttleScale)) + throttleRangeMin; #else mixerThrottleCommand = ((mixerThrottleCommand - throttleRangeMin) * motorConfig()->throttleScale) + throttleRangeMin; diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index a9e621285ed..2a48c719468 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -57,7 +57,7 @@ FILE_COMPILE_FOR_SPEED #include "sensors/acceleration.h" #include "sensors/compass.h" #include "sensors/pitotmeter.h" -#include "common/global_functions.h" +#include "programming/global_functions.h" typedef struct { float kP; // Proportional gain @@ -958,7 +958,7 @@ void FAST_CODE pidController(float dT) if (axis == FD_YAW && headingHoldState == HEADING_HOLD_ENABLED) { rateTarget = pidHeadingHold(dT); } else { -#ifdef USE_GLOBAL_FUNCTIONS +#ifdef USE_PROGRAMMING_FRAMEWORK rateTarget = pidRcCommandToRate(getRcCommandOverride(rcCommand, axis), currentControlRateProfile->stabilized.rates[axis]); #else rateTarget = pidRcCommandToRate(rcCommand[axis], currentControlRateProfile->stabilized.rates[axis]); diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index 375eacb2880..dbd910e2733 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -28,7 +28,7 @@ #include "common/axis.h" #include "common/filter.h" #include "common/maths.h" -#include "common/global_variables.h" +#include "programming/global_variables.h" #include "config/config_reset.h" #include "config/feature.h" @@ -75,7 +75,7 @@ void pgResetFn_customServoMixers(servoMixer_t *instance) .inputSource = 0, .rate = 0, .speed = 0 -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK ,.conditionId = -1 #endif ); @@ -266,7 +266,7 @@ void servoMixer(float dT) input[INPUT_FEATURE_FLAPS] = FLIGHT_MODE(FLAPERON) ? servoConfig()->flaperon_throw_offset : 0; input[INPUT_MAX] = 500; -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK input[INPUT_GVAR_0] = constrain(gvGet(0), -1000, 1000); input[INPUT_GVAR_1] = constrain(gvGet(1), -1000, 1000); input[INPUT_GVAR_2] = constrain(gvGet(2), -1000, 1000); @@ -318,7 +318,7 @@ void servoMixer(float dT) /* * Check if conditions for a rule are met, not all conditions apply all the time */ - #ifdef USE_LOGIC_CONDITIONS + #ifdef USE_PROGRAMMING_FRAMEWORK if (!logicConditionGetValue(currentServoMixer[i].conditionId)) { continue; } diff --git a/src/main/flight/servos.h b/src/main/flight/servos.h index f8ca7b51121..14df882289b 100644 --- a/src/main/flight/servos.h +++ b/src/main/flight/servos.h @@ -18,7 +18,7 @@ #pragma once #include "config/parameter_group.h" -#include "common/logic_condition.h" +#include "programming/logic_condition.h" #define MAX_SUPPORTED_SERVOS 16 @@ -105,7 +105,7 @@ typedef struct servoMixer_s { uint8_t inputSource; // input channel for this rule int16_t rate; // range [-1000;+1000] ; can be used to adjust a rate 0-1000% and a direction uint8_t speed; // reduces the speed of the rule, 0=unlimited speed -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK int8_t conditionId; #endif } servoMixer_t; diff --git a/src/main/common/global_functions.c b/src/main/programming/global_functions.c similarity index 98% rename from src/main/common/global_functions.c rename to src/main/programming/global_functions.c index 5e12bf9761d..a9929e6623d 100644 --- a/src/main/common/global_functions.c +++ b/src/main/programming/global_functions.c @@ -28,13 +28,13 @@ #include "common/utils.h" #include "common/maths.h" -#include "common/global_functions.h" -#include "common/logic_condition.h" +#include "programming/global_functions.h" +#include "programming/logic_condition.h" #include "io/vtx.h" #include "drivers/vtx_common.h" -#ifdef USE_GLOBAL_FUNCTIONS +#ifdef USE_PROGRAMMING_FRAMEWORK #include "common/axis.h" diff --git a/src/main/common/global_functions.h b/src/main/programming/global_functions.h similarity index 98% rename from src/main/common/global_functions.h rename to src/main/programming/global_functions.h index f8e0128eab2..adcaec001bd 100644 --- a/src/main/common/global_functions.h +++ b/src/main/programming/global_functions.h @@ -24,7 +24,7 @@ #pragma once #include "config/parameter_group.h" -#include "common/logic_condition.h" +#include "programming/logic_condition.h" #define MAX_GLOBAL_FUNCTIONS 8 diff --git a/src/main/common/global_variables.c b/src/main/programming/global_variables.c similarity index 96% rename from src/main/common/global_variables.c rename to src/main/programming/global_variables.c index 72230a97aeb..df2faace763 100644 --- a/src/main/common/global_variables.c +++ b/src/main/programming/global_variables.c @@ -26,13 +26,13 @@ FILE_COMPILE_FOR_SIZE -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK #include #include "config/config_reset.h" #include "config/parameter_group.h" #include "config/parameter_group_ids.h" -#include "common/global_variables.h" +#include "programming/global_variables.h" #include "common/maths.h" #include "build/build_config.h" diff --git a/src/main/common/global_variables.h b/src/main/programming/global_variables.h similarity index 100% rename from src/main/common/global_variables.h rename to src/main/programming/global_variables.h diff --git a/src/main/common/logic_condition.c b/src/main/programming/logic_condition.c similarity index 99% rename from src/main/common/logic_condition.c rename to src/main/programming/logic_condition.c index 7ba9dd2f1bb..d42d62fa71c 100644 --- a/src/main/common/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -28,11 +28,11 @@ #include "config/parameter_group.h" #include "config/parameter_group_ids.h" -#include "common/logic_condition.h" -#include "common/global_variables.h" +#include "programming/logic_condition.h" +#include "programming/global_variables.h" #include "common/utils.h" #include "rx/rx.h" -#include "maths.h" +#include "common/maths.h" #include "fc/fc_core.h" #include "fc/rc_controls.h" #include "fc/runtime_config.h" diff --git a/src/main/common/logic_condition.h b/src/main/programming/logic_condition.h similarity index 100% rename from src/main/common/logic_condition.h rename to src/main/programming/logic_condition.h diff --git a/src/main/programming/programming_task.c b/src/main/programming/programming_task.c new file mode 100644 index 00000000000..1447ffd231f --- /dev/null +++ b/src/main/programming/programming_task.c @@ -0,0 +1,35 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include "platform.h" + +FILE_COMPILE_FOR_SIZE + +#include "programming/logic_condition.h" +#include "programming/global_functions.h" + +void programmingFrameworkUpdateTask(timeUs_t currentTimeUs) { + logicConditionUpdateTask(currentTimeUs); + globalFunctionsUpdateTask(currentTimeUs); +} \ No newline at end of file diff --git a/src/main/programming/programming_task.h b/src/main/programming/programming_task.h new file mode 100644 index 00000000000..f19e3f184be --- /dev/null +++ b/src/main/programming/programming_task.h @@ -0,0 +1,27 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#pragma once + +void programmingFrameworkUpdateTask(timeUs_t currentTimeUs); \ No newline at end of file diff --git a/src/main/scheduler/scheduler.h b/src/main/scheduler/scheduler.h index a9d13ef5eff..99ebc681934 100755 --- a/src/main/scheduler/scheduler.h +++ b/src/main/scheduler/scheduler.h @@ -110,11 +110,8 @@ typedef enum { #ifdef USE_VTX_CONTROL TASK_VTXCTRL, #endif -#ifdef USE_LOGIC_CONDITIONS - TASK_LOGIC_CONDITIONS, -#endif -#ifdef USE_GLOBAL_FUNCTIONS - TASK_GLOBAL_FUNCTIONS, +#ifdef USE_PROGRAMMING_FRAMEWORK + TASK_PROGRAMMING_FRAMEWORK, #endif #ifdef USE_RPM_FILTER TASK_RPM_FILTER, diff --git a/src/main/target/common.h b/src/main/target/common.h index d79dad8a621..a6ff91b0384 100755 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -162,8 +162,7 @@ #define USE_VTX_FFPV #ifndef STM32F3 //F3 series does not have enoug RAM to support logic conditions -#define USE_LOGIC_CONDITIONS -#define USE_GLOBAL_FUNCTIONS +#define USE_PROGRAMMING_FRAMEWORK #define USE_CLI_BATCH #endif From 70054d59b0b1b066e8ee4735677a8971d501b6f8 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 8 Jul 2020 22:19:28 +0200 Subject: [PATCH 044/248] Move gyro EKF from gyro to PID --- src/main/flight/kalman.c | 10 ++-------- src/main/flight/kalman.h | 3 +-- src/main/flight/pid.c | 11 ++++++++++- src/main/sensors/gyro.c | 14 -------------- 4 files changed, 13 insertions(+), 25 deletions(-) diff --git a/src/main/flight/kalman.c b/src/main/flight/kalman.c index 9e672a4a6ac..2e88777d73a 100755 --- a/src/main/flight/kalman.c +++ b/src/main/flight/kalman.c @@ -29,7 +29,6 @@ FILE_COMPILE_FOR_SPEED #include "build/debug.h" kalman_t kalmanFilterStateRate[XYZ_AXIS_COUNT]; -float setPoint[XYZ_AXIS_COUNT]; static void gyroKalmanInitAxis(kalman_t *filter) { @@ -43,11 +42,6 @@ static void gyroKalmanInitAxis(kalman_t *filter) filter->inverseN = 1.0f / (float)(filter->w); } -void gyroKalmanSetSetpoint(uint8_t axis, float rate) -{ - setPoint[axis] = rate; -} - void gyroKalmanInitialize(void) { gyroKalmanInitAxis(&kalmanFilterStateRate[X]); @@ -114,13 +108,13 @@ static void updateAxisVariance(kalman_t *kalmanState, float rate) kalmanState->r = squirt * VARIANCE_SCALE; } -float gyroKalmanUpdate(uint8_t axis, float input) +float gyroKalmanUpdate(uint8_t axis, float input, float setpoint) { updateAxisVariance(&kalmanFilterStateRate[axis], input); DEBUG_SET(DEBUG_KALMAN, axis, kalmanFilterStateRate[axis].k * 1000.0f); //Kalman gain - return kalman_process(&kalmanFilterStateRate[axis], input, setPoint[axis]); + return kalman_process(&kalmanFilterStateRate[axis], input, setpoint); } #endif \ No newline at end of file diff --git a/src/main/flight/kalman.h b/src/main/flight/kalman.h index f493c1f628d..0a27ca2514c 100755 --- a/src/main/flight/kalman.h +++ b/src/main/flight/kalman.h @@ -50,5 +50,4 @@ typedef struct kalman } kalman_t; void gyroKalmanInitialize(void); -float gyroKalmanUpdate(uint8_t axis, float input); -void gyroKalmanSetSetpoint(uint8_t axis, float rate); +float gyroKalmanUpdate(uint8_t axis, float input, float setpoint); diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index a9e621285ed..791163627a9 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -967,8 +967,11 @@ void FAST_CODE pidController(float dT) // Limit desired rate to something gyro can measure reliably pidState[axis].rateTarget = constrainf(rateTarget, -GYRO_SATURATION_LIMIT, +GYRO_SATURATION_LIMIT); + #ifdef USE_GYRO_KALMAN - gyroKalmanSetSetpoint(axis, pidState[axis].rateTarget); + if (gyroConfig()->kalmanEnabled) { + pidState[axis].gyroRate = gyroKalmanUpdate(axis, pidState[axis].gyroRate, pidState[axis].rateTarget); + } #endif } @@ -1105,6 +1108,12 @@ void pidInit(void) } else { pidControllerApplyFn = nullRateController; } + +#ifdef USE_GYRO_KALMAN + if (gyroConfig()->kalmanEnabled) { + gyroKalmanInitialize(); + } +#endif } const pidBank_t * pidBank(void) { diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index e11b2f5d003..7db921eb73a 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -72,7 +72,6 @@ FILE_COMPILE_FOR_SPEED #include "flight/gyroanalyse.h" #include "flight/rpm_filter.h" #include "flight/dynamic_gyro_notch.h" -#include "flight/kalman.h" #ifdef USE_HARDWARE_REVISION_DETECTION #include "hardware_revision.h" @@ -312,11 +311,6 @@ bool gyroInit(void) } gyroInitFilters(); -#ifdef USE_GYRO_KALMAN - if (gyroConfig()->kalmanEnabled) { - gyroKalmanInitialize(); - } -#endif #ifdef USE_DYNAMIC_FILTERS dynamicGyroNotchFiltersInit(&dynamicGyroNotchState); gyroDataAnalyseStateInit( @@ -460,14 +454,6 @@ void FAST_CODE NOINLINE gyroUpdate() gyro.gyroADCf[axis] = gyroADCf; } -#ifdef USE_GYRO_KALMAN - if (gyroConfig()->kalmanEnabled) { - gyro.gyroADCf[X] = gyroKalmanUpdate(X, gyro.gyroADCf[X]); - gyro.gyroADCf[Y] = gyroKalmanUpdate(Y, gyro.gyroADCf[Y]); - gyro.gyroADCf[Z] = gyroKalmanUpdate(Z, gyro.gyroADCf[Z]); - } -#endif - #ifdef USE_DYNAMIC_FILTERS if (dynamicGyroNotchState.enabled) { gyroDataAnalyse(&gyroAnalyseState); From eebb5f644fd2591aa544c50ff05b64da1de08248 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 8 Jul 2020 22:27:17 +0200 Subject: [PATCH 045/248] Allow separate debug of PID measurement --- src/main/build/debug.h | 3 ++- src/main/fc/settings.yaml | 2 +- src/main/flight/kalman.c | 2 +- src/main/flight/pid.c | 1 + 4 files changed, 5 insertions(+), 3 deletions(-) diff --git a/src/main/build/debug.h b/src/main/build/debug.h index a5a5e90ea65..6fd91b473d9 100644 --- a/src/main/build/debug.h +++ b/src/main/build/debug.h @@ -72,6 +72,7 @@ typedef enum { DEBUG_DYNAMIC_FILTER_FREQUENCY, DEBUG_IRLOCK, DEBUG_CD, - DEBUG_KALMAN, + DEBUG_KALMAN_GAIN, + DEBUG_PID_MEASUREMENT, DEBUG_COUNT } debugType_e; diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index ce545ab777a..f01b915ccce 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -84,7 +84,7 @@ tables: "FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE", "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "ITERM_RELAX", "ERPM", "RPM_FILTER", "RPM_FREQ", "NAV_YAW", "DYNAMIC_FILTER", "DYNAMIC_FILTER_FREQUENCY", - "IRLOCK", "CD", "KALMAN"] + "IRLOCK", "CD", "KALMAN_GAIN", "PID_MEASUREMENT"] - name: async_mode values: ["NONE", "GYRO", "ALL"] - name: aux_operator diff --git a/src/main/flight/kalman.c b/src/main/flight/kalman.c index 2e88777d73a..70855b46b8f 100755 --- a/src/main/flight/kalman.c +++ b/src/main/flight/kalman.c @@ -112,7 +112,7 @@ float gyroKalmanUpdate(uint8_t axis, float input, float setpoint) { updateAxisVariance(&kalmanFilterStateRate[axis], input); - DEBUG_SET(DEBUG_KALMAN, axis, kalmanFilterStateRate[axis].k * 1000.0f); //Kalman gain + DEBUG_SET(DEBUG_KALMAN_GAIN, axis, kalmanFilterStateRate[axis].k * 1000.0f); //Kalman gain return kalman_process(&kalmanFilterStateRate[axis], input, setpoint); } diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 791163627a9..e04178dc196 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -973,6 +973,7 @@ void FAST_CODE pidController(float dT) pidState[axis].gyroRate = gyroKalmanUpdate(axis, pidState[axis].gyroRate, pidState[axis].rateTarget); } #endif + DEBUG_SET(DEBUG_PID_MEASUREMENT, axis, pidState[axis].gyroRate); } // Step 3: Run control for ANGLE_MODE, HORIZON_MODE, and HEADING_LOCK From 206aef3197907a07ff8916c86ac2a6f36a3c5c51 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Thu, 9 Jul 2020 09:39:51 +0100 Subject: [PATCH 046/248] [DOC] add additional descriptions to settings.yaml --- src/main/fc/settings.yaml | 18 +++++++++++++++++- 1 file changed, 17 insertions(+), 1 deletion(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index ce545ab777a..e73844ccabc 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -357,6 +357,8 @@ groups: members: - name: rangefinder_hardware table: rangefinder_hardware + description: "Selection of rangefinder hardware." + default_value: "NONE" - name: rangefinder_median_filter description: "3-point median filtering for rangefinder readouts" default_value: "OFF" @@ -369,6 +371,8 @@ groups: condition: USE_OPFLOW members: - name: opflow_hardware + description: "Selection of OPFLOW hardware." + default: "NONE" table: opflow_hardware - name: opflow_scale min: 0 @@ -475,6 +479,8 @@ groups: condition: USE_PITOT members: - name: pitot_hardware + description: "Selection of pitot hardware." + default_value: "NONE" table: pitot_hardware - name: pitot_lpf_milli_hz min: 0 @@ -488,6 +494,8 @@ groups: headers: ["rx/rx.h", "rx/spektrum.h"] members: - name: receiver_type + description: "Selection of receiver (RX) type. Additional configuration of a `serialrx_provider` and a UART will be needed for `SERIAL`" + default_value: "`TARGET dependent`" field: receiverType table: receiver_type - name: min_check @@ -576,6 +584,8 @@ groups: field: halfDuplex type: bool - name: msp_override_channels + description: "Mask of RX channels that may be overridden by MSP `SET_RAW_RC`. Note that this requires custom firmware with `USE_RX_MSP` and `USE_MSP_RC_OVERRIDE` compile options and the `MSP RC Override` flight mode." + default_value: "0" field: mspOverrideChannels condition: USE_MSP_RC_OVERRIDE min: 0 @@ -1177,6 +1187,8 @@ groups: type: generalSettings_t members: - name: applied_defaults + description: "Internal (configurator) hint. Should not be changed manually" + default_value: "0" field: appliedDefaults type: uint8_t min: 0 @@ -1827,6 +1839,8 @@ groups: field: use_gps_velned type: bool - name: inav_allow_dead_reckoning + description: "Defines if inav will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation" + default_value: "OFF" field: allow_dead_reckoning type: bool - name: inav_reset_altitude @@ -2093,7 +2107,7 @@ groups: min: 1000 max: 2000 - name: nav_mc_auto_disarm_delay - description: "" + description: "Delay before multi-rotor disarms when `nav_disarm_on_landing` is set (m/s)" default_value: "2000" field: mc.auto_disarm_delay min: 100 @@ -2820,6 +2834,8 @@ groups: condition: USE_UNDERCLOCK type: bool - name: debug_mode + description: "Defines debug values exposed in debug variables (developer / debugging setting)" + default_value: "NONE" table: debug_modes - name: throttle_tilt_comp_str description: "Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled." From 4673eb435e74816e9853a79b8786a81ac2f3e734 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Thu, 9 Jul 2020 09:45:42 +0100 Subject: [PATCH 047/248] [DOC] add `vtx_max_power_override` description --- src/main/fc/settings.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index e73844ccabc..5ab9066e3d0 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2949,6 +2949,8 @@ groups: min: VTX_SETTINGS_MIN_CHANNEL max: VTX_SETTINGS_MAX_CHANNEL - name: vtx_max_power_override + description: "Some VTXes may report max power incorrectly (i.e. 200mW for a 600mW VTX). Use this to override max supported power. 0 to disable and use whatever VTX reports as its capabilities" + default_value: "0" field: maxPowerOverride min: 0 max: 10000 From 514f89dad9d86b76a22e0abb7aa4abd1049222c3 Mon Sep 17 00:00:00 2001 From: kernel-machine Date: Fri, 10 Jul 2020 11:59:55 +0200 Subject: [PATCH 048/248] gf_set_osd_layout --- docs/Global Functions.md | 5 +++-- src/main/io/osd.c | 6 ++++++ src/main/programming/global_functions.c | 6 ++++++ src/main/programming/global_functions.h | 2 ++ 4 files changed, 17 insertions(+), 2 deletions(-) diff --git a/docs/Global Functions.md b/docs/Global Functions.md index f74d772b655..81f350cff2b 100644 --- a/docs/Global Functions.md +++ b/docs/Global Functions.md @@ -26,8 +26,9 @@ _Global Functions_ (abbr. GF) are a mechanism allowing to override certain fligh | 5 | INVERT_PITCH | Inverts PITCH axis input for PID/PIFF controller | | 6 | INVERT_YAW | Inverts YAW axis input for PID/PIFF controller | | 7 | OVERRIDE_THROTTLE | Override throttle value that is fed to the motors by mixer. Operand is scaled in us. `1000` means throttle cut, `1500` means half throttle | -| 8 | SET_VTX_BAND | Sets VTX band. Accepted values are `1-5` | -| 8 | SET_VTX_CHANNEL | Sets VTX channel. Accepted values are `1-8` | +| 8 | SET_VTX_BAND | Sets VTX band. Accepted values are `1-5` | +| 9 | SET_VTX_CHANNEL | Sets VTX channel. Accepted values are `1-8` | +| 10 | SET_OSD_LAYOUT | Sets OSD layout. Accepted values are `0-3` | ## Flags diff --git a/src/main/io/osd.c b/src/main/io/osd.c index dda74ae3e79..2c4db39b58e 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -52,6 +52,7 @@ FILE_COMPILE_FOR_SPEED #include "common/time.h" #include "common/typeconversion.h" #include "common/utils.h" +#include "programming/global_functions.h" #include "config/feature.h" #include "config/parameter_group.h" @@ -3241,6 +3242,11 @@ void osdUpdate(timeUs_t currentTimeUs) if (IS_RC_MODE_ACTIVE(BOXOSDALT1)) activeLayout = 1; else +#ifdef USE_PROGRAMMING_FRAMEWORK + if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_OSD_LAYOUT)) + activeLayout = constrain(globalFunctionValues[GLOBAL_FUNCTION_ACTION_SET_OSD_LAYOUT], 0, OSD_ALTERNATE_LAYOUT_COUNT); + else +#endif activeLayout = 0; } if (currentLayout != activeLayout) { diff --git a/src/main/programming/global_functions.c b/src/main/programming/global_functions.c index a9929e6623d..675da332157 100644 --- a/src/main/programming/global_functions.c +++ b/src/main/programming/global_functions.c @@ -135,6 +135,12 @@ void globalFunctionsProcess(int8_t functionId) { GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE); } break; + case GLOBAL_FUNCTION_ACTION_SET_OSD_LAYOUT: + if(conditionValue){ + globalFunctionValues[GLOBAL_FUNCTION_ACTION_SET_OSD_LAYOUT] = globalFunctionsStates[functionId].value; + GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_OSD_LAYOUT); + } + break; } } } diff --git a/src/main/programming/global_functions.h b/src/main/programming/global_functions.h index adcaec001bd..e6221ef8e32 100644 --- a/src/main/programming/global_functions.h +++ b/src/main/programming/global_functions.h @@ -39,6 +39,7 @@ typedef enum { GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE, // 7 GLOBAL_FUNCTION_ACTION_SET_VTX_BAND, // 8 GLOBAL_FUNCTION_ACTION_SET_VTX_CHANNEL, // 9 + GLOBAL_FUNCTION_ACTION_SET_OSD_LAYOUT, // 10 GLOBAL_FUNCTION_ACTION_LAST } globalFunctionActions_e; @@ -50,6 +51,7 @@ typedef enum { GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_PITCH = (1 << 4), GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_YAW = (1 << 5), GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE = (1 << 6), + GLOBAL_FUNCTION_FLAG_OVERRIDE_OSD_LAYOUT = (1 << 7), } globalFunctionFlags_t; typedef struct globalFunction_s { From abafe9b258ad1594e27d29972c37b559dc3ecdbd Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 12 Jul 2020 22:37:54 +0200 Subject: [PATCH 049/248] Refactor attenuation factor computation --- src/main/fc/settings.yaml | 6 +++ src/main/flight/pid.c | 4 +- src/main/navigation/navigation_multicopter.c | 53 ++++++++++++-------- 3 files changed, 41 insertions(+), 22 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 52150607253..8c2ddc4639f 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1651,14 +1651,20 @@ groups: min: 0 max: 100 - name: nav_mc_vel_xy_dterm_attenuation + description: "Maximum D-term attenution percentage for horizontal velocity PID controller (Multirotor). It allows to smooth the PosHold CRUISE, WP and RTH when Multirotor is traveling at full speed. Dterm is not attenuated at low speeds, breaking and accelerating." + default_value: "90" field: navVelXyDtermAttenuation min: 0 max: 100 - name: nav_mc_vel_xy_dterm_attenuation_start + description: "A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation begins" + default_value: 10" field: navVelXyDtermAttenuationStart min: 0 max: 100 - name: nav_mc_vel_xy_dterm_attenuation_end + description: "A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation reaches maximum" + default_value: "60" field: navVelXyDtermAttenuationEnd min: 0 max: 100 diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 4687ce4e4c5..d48118bd375 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -258,8 +258,8 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .loiter_direction = NAV_LOITER_RIGHT, .navVelXyDTermLpfHz = NAV_ACCEL_CUTOFF_FREQUENCY_HZ, - .navVelXyDtermAttenuation = 80, - .navVelXyDtermAttenuationStart = 20, + .navVelXyDtermAttenuation = 90, + .navVelXyDtermAttenuationStart = 10, .navVelXyDtermAttenuationEnd = 60, .iterm_relax_type = ITERM_RELAX_SETPOINT, .iterm_relax_cutoff = MC_ITERM_RELAX_CUTOFF_DEFAULT, diff --git a/src/main/navigation/navigation_multicopter.c b/src/main/navigation/navigation_multicopter.c index b7bfa2e2d74..964cb980fef 100755 --- a/src/main/navigation/navigation_multicopter.c +++ b/src/main/navigation/navigation_multicopter.c @@ -469,6 +469,25 @@ static void updatePositionVelocityController_MC(const float maxSpeed) #endif } +static float computeNormalizedVelocity(const float value, const float maxValue) +{ + return constrainf(scaleRangef(fabsf(value), 0, maxValue, 0.0f, 1.0f), 0.0f, 1.0f); +} + +static float computeVelocityScale( + const float value, + const float maxValue, + const float attenuationFactor, + const float attenuationStart, + const float attenuationEnd +) +{ + const float normalized = computeNormalizedVelocity(value, maxValue); + + float scale = scaleRangef(normalized, attenuationStart, attenuationEnd, 0, attenuationFactor); + return constrainf(scale, 0, attenuationFactor); +} + static void updatePositionAccelController_MC(timeDelta_t deltaMicros, float maxAccelLimit, const float maxSpeed) { const float measurementX = navGetCurrentActualPositionAndVelocity()->vel.x; @@ -517,29 +536,23 @@ static void updatePositionAccelController_MC(timeDelta_t deltaMicros, float maxA * acceleration and deceleration * Scale down dTerm with 2D speed */ - - //Normalize the setpoint and measurement between 0.0f and 1.0f where 1.0f is currently used max speed - const float setpointNormalized = constrainf(scaleRangef(fabsf(setpointXY), 0, maxSpeed, 0.0f, 1.0f), 0.0f, 1.0f); - const float measurementNormalized = constrainf(scaleRangef(fabsf(posControl.actualState.velXY), 0, maxSpeed, 0.0f, 1.0f), 0.0f, 1.0f); - - DEBUG_SET(DEBUG_ALWAYS, 0, setpointNormalized * 100); - DEBUG_SET(DEBUG_ALWAYS, 1, measurementNormalized * 100); - - /* - * Dterm can be attenuated when both setpoint and measurement is high - UAV is moving close to desired velocity - */ - float setpointScale = scaleRangef(setpointNormalized, multicopterPosXyCoefficients.dTermAttenuationStart, multicopterPosXyCoefficients.dTermAttenuationEnd, 0, multicopterPosXyCoefficients.dTermAttenuation); - setpointScale = constrainf(setpointScale, 0, multicopterPosXyCoefficients.dTermAttenuation); - - float measurementScale = scaleRangef(measurementNormalized, multicopterPosXyCoefficients.dTermAttenuationStart, multicopterPosXyCoefficients.dTermAttenuationEnd, 0, multicopterPosXyCoefficients.dTermAttenuation); - measurementScale = constrainf(measurementScale, 0, multicopterPosXyCoefficients.dTermAttenuation); - - DEBUG_SET(DEBUG_ALWAYS, 2, setpointScale * 100); - DEBUG_SET(DEBUG_ALWAYS, 3, measurementScale * 100); + const float setpointScale = computeVelocityScale( + setpointXY, + maxSpeed, + multicopterPosXyCoefficients.dTermAttenuation, + multicopterPosXyCoefficients.dTermAttenuationStart, + multicopterPosXyCoefficients.dTermAttenuationEnd + ); + const float measurementScale = computeVelocityScale( + posControl.actualState.velXY, + maxSpeed, + multicopterPosXyCoefficients.dTermAttenuation, + multicopterPosXyCoefficients.dTermAttenuationStart, + multicopterPosXyCoefficients.dTermAttenuationEnd + ); //Choose smaller attenuation factor and convert from attenuation to scale const float dtermScale = 1.0f - MIN(setpointScale, measurementScale); - DEBUG_SET(DEBUG_ALWAYS, 4, dtermScale * 100); // Apply PID with output limiting and I-term anti-windup // Pre-calculated accelLimit and the logic of navPidApply2 function guarantee that our newAccel won't exceed maxAccelLimit From b09eba7aabb4341b156661c277b36b57943d5ead Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 13 Jul 2020 13:22:18 +0200 Subject: [PATCH 050/248] Docs improvements --- src/main/fc/settings.yaml | 6 ++++++ src/main/sensors/compass.c | 2 +- 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 2046e7d0149..780070e75fc 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -419,14 +419,20 @@ groups: min: INT16_MIN max: INT16_MAX - name: maggain_x + description: "Magnetometer calibration X gain. If 0, no calibration or calibration failed" + default_value: "0" field: magGain[X] min: INT16_MIN max: INT16_MAX - name: maggain_y + description: "Magnetometer calibration Y gain. If 0, no calibration or calibration failed" + default_value: "0" field: magGain[Y] min: INT16_MIN max: INT16_MAX - name: maggain_z + description: "Magnetometer calibration Z gain. If 0, no calibration or calibration failed" + default_value: "0" field: magGain[Z] min: INT16_MIN max: INT16_MAX diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index eda1fab967a..90fb2c5ac0c 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -380,7 +380,7 @@ void compassUpdate(timeUs_t currentTimeUs) diffMag += (mag.magADC[axis] - magPrev[axis]) * (mag.magADC[axis] - magPrev[axis]); avgMag += (mag.magADC[axis] + magPrev[axis]) * (mag.magADC[axis] + magPrev[axis]) / 4.0f; - int32_t sample = ABS(mag.magADC[axis]); + const int32_t sample = ABS(mag.magADC[axis]); if (sample > magGain[axis]) { magGain[axis] = sample; } From cecaddd8ef2df16ed654573bbd83608cf105c94f Mon Sep 17 00:00:00 2001 From: Felipe Machado Date: Wed, 15 Jul 2020 16:36:33 +0100 Subject: [PATCH 051/248] [MAVLINK] Update flight modes map to match Arduplane/Arducopter --- src/main/telemetry/mavlink.c | 100 +++++++++++++++++++++++++++++++++-- 1 file changed, 95 insertions(+), 5 deletions(-) diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index e6194797d27..2a6f4f8b5a5 100755 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -82,6 +82,60 @@ #define TELEMETRY_MAVLINK_MAXRATE 50 #define TELEMETRY_MAVLINK_DELAY ((1000 * 1000) / TELEMETRY_MAVLINK_MAXRATE) + +/** @brief A mapping of plane flight modes for custom_mode field of heartbeat. */ +typedef enum APM_PLANE_MODE +{ + PLANE_MODE_MANUAL=0, + PLANE_MODE_CIRCLE=1, + PLANE_MODE_STABILIZE=2, + PLANE_MODE_TRAINING=3, + PLANE_MODE_ACRO=4, + PLANE_MODE_FLY_BY_WIRE_A=5, + PLANE_MODE_FLY_BY_WIRE_B=6, + PLANE_MODE_CRUISE=7, + PLANE_MODE_AUTOTUNE=8, + PLANE_MODE_AUTO=10, + PLANE_MODE_RTL=11, + PLANE_MODE_LOITER=12, + PLANE_MODE_TAKEOFF=13, + PLANE_MODE_AVOID_ADSB=14, + PLANE_MODE_GUIDED=15, + PLANE_MODE_INITIALIZING=16, + PLANE_MODE_QSTABILIZE=17, + PLANE_MODE_QHOVER=18, + PLANE_MODE_QLOITER=19, + PLANE_MODE_QLAND=20, + PLANE_MODE_QRTL=21, + PLANE_MODE_QAUTOTUNE=22, + PLANE_MODE_ENUM_END=23, +} APM_PLANE_MODE; + +/** @brief A mapping of copter flight modes for custom_mode field of heartbeat. */ +typedef enum APM_COPTER_MODE +{ + COPTER_MODE_STABILIZE=0, + COPTER_MODE_ACRO=1, + COPTER_MODE_ALT_HOLD=2, + COPTER_MODE_AUTO=3, + COPTER_MODE_GUIDED=4, + COPTER_MODE_LOITER=5, + COPTER_MODE_RTL=6, + COPTER_MODE_CIRCLE=7, + COPTER_MODE_LAND=9, + COPTER_MODE_DRIFT=11, + COPTER_MODE_SPORT=13, + COPTER_MODE_FLIP=14, + COPTER_MODE_AUTOTUNE=15, + COPTER_MODE_POSHOLD=16, + COPTER_MODE_BRAKE=17, + COPTER_MODE_THROW=18, + COPTER_MODE_AVOID_ADSB=19, + COPTER_MODE_GUIDED_NOGPS=20, + COPTER_MODE_SMART_RTL=21, + COPTER_MODE_ENUM_END=22, +} APM_COPTER_MODE; + static serialPort_t *mavlinkPort = NULL; static serialPortConfig_t *portConfig; @@ -108,9 +162,45 @@ static mavlink_status_t mavRecvStatus; static uint8_t mavSystemId = 1; static uint8_t mavComponentId = MAV_COMP_ID_SYSTEM_CONTROL; -// MANUAL, ACRO, ANGLE, HRZN, ALTHOLD, POSHOLD, RTH, WP, LAUNCH, FAILSAFE -static uint8_t inavToArduCopterMap[FLM_COUNT] = { 1, 1, 0, 0, 2, 16, 6, 3, 18, 0 }; -static uint8_t inavToArduPlaneMap[FLM_COUNT] = { 0, 4, 2, 2, 5, 1, 11, 10, 15, 2 }; +APM_COPTER_MODE inavToArduCopterMap(flightModeForTelemetry_e flightMode) +{ + switch (flightMode) + { + case FLM_ACRO: return COPTER_MODE_ACRO; + case FLM_ACRO_AIR: return COPTER_MODE_ACRO; + case FLM_ANGLE: return COPTER_MODE_STABILIZE; + case FLM_HORIZON: return COPTER_MODE_STABILIZE; + case FLM_ALTITUDE_HOLD: return COPTER_MODE_ALT_HOLD; + case FLM_POSITION_HOLD: return COPTER_MODE_POSHOLD; + case FLM_RTH: return COPTER_MODE_RTL; + case FLM_MISSION: return COPTER_MODE_AUTO; + case FLM_LAUNCH: return COPTER_MODE_THROW; + case FLM_FAILSAFE: return COPTER_MODE_RTL; + default: return COPTER_MODE_ENUM_END; + } +} + +APM_PLANE_MODE inavToArduPlaneMap(flightModeForTelemetry_e flightMode) +{ + switch (flightMode) + { + case FLM_MANUAL: return PLANE_MODE_MANUAL; + case FLM_ACRO: return PLANE_MODE_ACRO; + case FLM_ACRO_AIR: return PLANE_MODE_ACRO; + case FLM_ANGLE: return PLANE_MODE_FLY_BY_WIRE_A; + case FLM_HORIZON: return PLANE_MODE_STABILIZE; + case FLM_ALTITUDE_HOLD: return PLANE_MODE_FLY_BY_WIRE_B; + case FLM_POSITION_HOLD: return PLANE_MODE_LOITER; + case FLM_RTH: return PLANE_MODE_RTL; + case FLM_MISSION: return PLANE_MODE_AUTO; + case FLM_CRUISE: return PLANE_MODE_CRUISE; + case FLM_LAUNCH: return PLANE_MODE_TAKEOFF; + case FLM_FAILSAFE: return PLANE_MODE_RTL; + default: return PLANE_MODE_ENUM_END; + } +} + + static int mavlinkStreamTrigger(enum MAV_DATA_STREAM streamNum) { @@ -468,10 +558,10 @@ void mavlinkSendHUDAndHeartbeat(void) uint8_t mavCustomMode; if (STATE(FIXED_WING_LEGACY)) { - mavCustomMode = inavToArduPlaneMap[flm]; + mavCustomMode = (uint8_t)inavToArduPlaneMap(flm); } else { - mavCustomMode = inavToArduCopterMap[flm]; + mavCustomMode = (uint8_t)inavToArduCopterMap(flm); } if (flm != FLM_MANUAL) { From 8dda60b6c1895c8b17128a2bd2d888e61cd3e1e5 Mon Sep 17 00:00:00 2001 From: Cullen Jennings Date: Thu, 16 Jul 2020 18:20:21 -0700 Subject: [PATCH 052/248] fix formatting for MD to dsiplay correctly in github --- docs/development/Building Manual.md | 6 +++--- docs/development/Building in Windows light.md | 10 +++++----- docs/development/Travis.md | 2 +- 3 files changed, 9 insertions(+), 9 deletions(-) diff --git a/docs/development/Building Manual.md b/docs/development/Building Manual.md index eb4960ff0a3..97431dedf7b 100755 --- a/docs/development/Building Manual.md +++ b/docs/development/Building Manual.md @@ -1,15 +1,15 @@ -#Building Manual. +# Building Manual. The manual PDF file is generated by concatenating relevant markdown files and by transforming the result using Gimli to obtain the final PDF file. This steps are handled automatically by the ```build_docs.sh``` script located in the root of the repository next to the Makefile. -##Requirements & Installation +## Requirements & Installation The PDF manual generation uses the Gimli for the conversion. It can be installed via ruby gems. On Debian based systems the installation steps are: ```bash sudo apt-get install ruby1.9.1 ruby1.9.1-dev rubygems zlib1g-dev wkhtmltopdf libxml2-dev libxslt-dev sudo gem1.9.1 install gimli ``` -##Configuration +## Configuration All markdown files need to be registered in the ```build_manual.sh``` file individually by modifying the ```doc_files``` variable / array: ```bash doc_files=( 'Configuration.md' diff --git a/docs/development/Building in Windows light.md b/docs/development/Building in Windows light.md index 147a1909671..6cc0c48c79f 100644 --- a/docs/development/Building in Windows light.md +++ b/docs/development/Building in Windows light.md @@ -1,7 +1,7 @@ # Building in windows light no cygwin and no path changes -##Install Git for windows +## Install Git for windows download https://github.com/git-for-windows/git/releases/download/v2.10.1.windows.1/Git-2.10.1-32-bit.exe Recommended install location is C:\Git (no spaces or special characters in path) @@ -28,21 +28,21 @@ Follow images as not all are at default settings. ![Git Installation](assets/010.gitwin.png) -##Install toolset scripts +## Install toolset scripts download https://www.dropbox.com/s/hhlr16h657y4l5u/devtools.zip?dl=0 extract it into C:\ it creates devtools folder -##Install latest arm toolchain +## Install latest arm toolchain download https://gcc.gnu.org/mirrors.html extract it into C:\devtools\gcc-arm-none-eabi-... (folder already there) -##Install Ruby +## Install Ruby Install the latest Ruby version using [Ruby Installer](https://rubyinstaller.org). -##Test +## Test Run C:\devtools\shF4.cmd If everything went according the manual you should be in mingw console window. (if not we need to update this manual) diff --git a/docs/development/Travis.md b/docs/development/Travis.md index 169d0693060..9bbe02cfe95 100644 --- a/docs/development/Travis.md +++ b/docs/development/Travis.md @@ -1,4 +1,4 @@ -#Travis +# Travis INAV provides Travis build and config files in the repository root. From edd0f358f7d5da4fad1fdafac9c32500f981d7f4 Mon Sep 17 00:00:00 2001 From: Cullen Jennings Date: Thu, 16 Jul 2020 18:26:39 -0700 Subject: [PATCH 053/248] fix formatting for MD to dsiplay correctly in github --- docs/Board - DALRCF405.md | 2 +- docs/Board - DALRCF722DUAL.md | 2 +- docs/Board - FOXEERF722DUAL.md | 4 ++-- docs/LedStrip.md | 2 +- docs/Navigation.md | 2 +- 5 files changed, 6 insertions(+), 6 deletions(-) diff --git a/docs/Board - DALRCF405.md b/docs/Board - DALRCF405.md index 08e65492e76..5dd2e1f95fb 100644 --- a/docs/Board - DALRCF405.md +++ b/docs/Board - DALRCF405.md @@ -97,7 +97,7 @@ This board use the STM32F405RGT6 microcontroller and have the following features | 3 | SWDIO | PAD | | 4 | 3V3 | PAD | -###Designers +### Designers * ZhengNyway(nyway@vip.qq.com) FROM DALRC diff --git a/docs/Board - DALRCF722DUAL.md b/docs/Board - DALRCF722DUAL.md index 20287ee5210..08905ded674 100644 --- a/docs/Board - DALRCF722DUAL.md +++ b/docs/Board - DALRCF722DUAL.md @@ -102,7 +102,7 @@ This board use the STM32F722RET6 microcontroller and have the following features | 4 | 3V3 | PAD | -###Designers +### Designers * ZhengNyway(nyway@vip.qq.com) FROM DALRC diff --git a/docs/Board - FOXEERF722DUAL.md b/docs/Board - FOXEERF722DUAL.md index 6e168aaac49..1a548febda4 100644 --- a/docs/Board - FOXEERF722DUAL.md +++ b/docs/Board - FOXEERF722DUAL.md @@ -99,5 +99,5 @@ This board use the STM32F722RET6 microcontroller and have the following features | 4 | 3V3 | PAD | -###Designers -* NywayZheng(nyway@vip.qq.com) \ No newline at end of file +### Designers +* NywayZheng(nyway@vip.qq.com) diff --git a/docs/LedStrip.md b/docs/LedStrip.md index 3e2a9b11d98..2220ce26cd4 100644 --- a/docs/LedStrip.md +++ b/docs/LedStrip.md @@ -536,7 +536,7 @@ LEDs 14-15 should be placed facing up, in the middle ### Exmple 28 LED config ``` -#right rear cluster +# right rear cluster led 0 9,9:S:FWT:0 led 1 10,10:S:FWT:0 led 2 11,11:S:IA:0 diff --git a/docs/Navigation.md b/docs/Navigation.md index 66970585a49..0dc2513b308 100755 --- a/docs/Navigation.md +++ b/docs/Navigation.md @@ -92,7 +92,7 @@ Parameters: # wp load # wp -#wp 11 valid +# wp 11 valid wp 0 1 543533193 -45179273 3500 0 0 0 0 wp 1 1 543535723 -45193913 3500 0 0 0 0 wp 2 1 543544541 -45196617 5000 0 0 0 0 From 3fa9b893eb961690b36c320978fa2e0670bd6bc7 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sat, 18 Jul 2020 18:13:58 +0200 Subject: [PATCH 054/248] First cut of HAKRC Zeus F722 --- make/release.mk | 2 +- src/main/target/HGLRCF722/config.c | 33 +++++ src/main/target/HGLRCF722/target.c | 53 ++++++++ src/main/target/HGLRCF722/target.h | 180 ++++++++++++++++++++++++++++ src/main/target/HGLRCF722/target.mk | 19 +++ 5 files changed, 286 insertions(+), 1 deletion(-) create mode 100644 src/main/target/HGLRCF722/config.c create mode 100644 src/main/target/HGLRCF722/target.c create mode 100644 src/main/target/HGLRCF722/target.h create mode 100644 src/main/target/HGLRCF722/target.mk diff --git a/make/release.mk b/make/release.mk index 0edda29c66f..1ca0439bdab 100644 --- a/make/release.mk +++ b/make/release.mk @@ -34,4 +34,4 @@ RELEASE_TARGETS += IFLIGHTF7_TWING IFLIGHTF4_TWING IFLIGHTF4_SUCCEXD RELEASE_TARGETS += AIKONF4 -RELEASE_TARGETS += ZEEZF7 +RELEASE_TARGETS += ZEEZF7 HGLRCF722 diff --git a/src/main/target/HGLRCF722/config.c b/src/main/target/HGLRCF722/config.c new file mode 100644 index 00000000000..17131889016 --- /dev/null +++ b/src/main/target/HGLRCF722/config.c @@ -0,0 +1,33 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include "platform.h" +#include "io/piniobox.h" + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = 47; + pinioBoxConfigMutable()->permanentId[1] = 48; +} diff --git a/src/main/target/HGLRCF722/target.c b/src/main/target/HGLRCF722/target.c new file mode 100644 index 00000000000..ebabbd28a12 --- /dev/null +++ b/src/main/target/HGLRCF722/target.c @@ -0,0 +1,53 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/pinio.h" +#include "drivers/sensor.h" + +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); + +const timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S1 UP1-2 D(1, 4, 5) + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S2 UP1-2 D(1, 5, 5) + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 UP1-2 D(1, 7, 5) + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 UP1-2 D(1, 2, 5) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 UP1-7 D(1, 5, 3) - clash with S2 + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 UP1-7 D(1, 6, 3) + DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S7 UP1-6 D(1, 0, 2) + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), // S8 UP1-6 D(1, 3, 2) + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // LED D(2, 6, 0) + DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM, RX2 + DEF_TIM(TIM5, CH3, PA2, TIM_USE_PWM, 0, 0), // TX2 & softserial1 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/HGLRCF722/target.h b/src/main/target/HGLRCF722/target.h new file mode 100644 index 00000000000..c745a853be5 --- /dev/null +++ b/src/main/target/HGLRCF722/target.h @@ -0,0 +1,180 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "HGF7" +#define USBD_PRODUCT_STRING "HGLRCF722" + +#define LED0 PA14 +#define LED1 PA13 + +#define BEEPER PC13 +#define BEEPER_INVERTED + +// *************** SPI1 Gyro & ACC ******************* +#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_DUAL_GYRO + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW180_DEG_FLIP +#define MPU6000_CS_PIN PB2 +#define MPU6000_SPI_BUS BUS_SPI1 +#define MPU6000_EXTI_PIN PC4 + +#define USE_EXTI +#define USE_MPU_DATA_READY_SIGNAL + +// *************** I2C /Baro/Mag ********************* +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_SPI_BMP280 +#define BMP280_SPI_BUS BUS_SPI1 +#define BMP280_CS_PIN PA4 +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_MS5611 +#define USE_BARO_DPS310 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_AK8975 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +#define TEMPERATURE_I2C_BUS BUS_I2C1 + +#define PITOT_I2C_BUS BUS_I2C1 + +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS BUS_I2C1 + +// *************** SPI2 OSD *********************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_OSD +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +// *************** SPI3 SD BLACKBOX******************* +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 + +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI3 +#define M25P16_CS_PIN PD2 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + + +// *************** UART ***************************** +#define USE_VCP +#define USB_DETECT_PIN PC14 +#define USE_USB_DETECT + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define USE_UART3 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define SERIAL_PORT_COUNT 6 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART1 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 + +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC1 +#define ADC_CHANNEL_3_PIN PC0 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 + +// *************** PINIO *************************** +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PC8 // VTX power switcher +#define PINIO2_PIN PC9 // 2xCamera switcher + +// *************** LEDSTRIP ************************ +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) +#define CURRENT_METER_SCALE 179 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff + +#define MAX_PWM_OUTPUT_PORTS 8 +#define USE_DSHOT +#define USE_SERIALSHOT +#define USE_ESC_SENSOR \ No newline at end of file diff --git a/src/main/target/HGLRCF722/target.mk b/src/main/target/HGLRCF722/target.mk new file mode 100644 index 00000000000..ee06f7a49ce --- /dev/null +++ b/src/main/target/HGLRCF722/target.mk @@ -0,0 +1,19 @@ +F7X2RE_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH MSC + +TARGET_SRC = \ + drivers/accgyro/accgyro_mpu6000.c \ + drivers/barometer/barometer_bmp085.c \ + drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_ms56xx.c \ + drivers/barometer/barometer_dps310.c \ + drivers/compass/compass_ak8975.c \ + drivers/compass/compass_hmc5883l.c \ + drivers/compass/compass_qmc5883l.c \ + drivers/compass/compass_ist8310.c \ + drivers/compass/compass_ist8308.c \ + drivers/compass/compass_mag3110.c \ + drivers/compass/compass_lis3mdl.c \ + drivers/light_ws2811strip.c \ + drivers/max7456.c \ + drivers/pitotmeter_adc.c \ From d85693cd98678cbf09c3d9ddb8df575e852ad9e7 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 20 Jul 2020 18:05:38 +0200 Subject: [PATCH 055/248] PCF8574 Basic Driver --- make/source.mk | 1 + src/main/build/debug.h | 1 + src/main/drivers/bus.h | 1 + src/main/drivers/io_pcf8574.c | 90 +++++++++++++++++++++++++++++++ src/main/drivers/io_pcf8574.h | 29 ++++++++++ src/main/fc/fc_init.c | 6 +++ src/main/fc/settings.yaml | 2 +- src/main/target/common.h | 3 ++ src/main/target/common_hardware.c | 17 ++++++ 9 files changed, 149 insertions(+), 1 deletion(-) create mode 100644 src/main/drivers/io_pcf8574.c create mode 100644 src/main/drivers/io_pcf8574.h diff --git a/make/source.mk b/make/source.mk index e1b9aa12847..d1b0b3e065d 100644 --- a/make/source.mk +++ b/make/source.mk @@ -45,6 +45,7 @@ COMMON_SRC = \ drivers/exti.c \ drivers/io.c \ drivers/io_pca9685.c \ + drivers/io_pcf8574.c \ drivers/irlock.c \ drivers/light_led.c \ drivers/osd.c \ diff --git a/src/main/build/debug.h b/src/main/build/debug.h index a5a5e90ea65..3ae2e3109c1 100644 --- a/src/main/build/debug.h +++ b/src/main/build/debug.h @@ -73,5 +73,6 @@ typedef enum { DEBUG_IRLOCK, DEBUG_CD, DEBUG_KALMAN, + DEBUG_PCF8574, DEBUG_COUNT } debugType_e; diff --git a/src/main/drivers/bus.h b/src/main/drivers/bus.h index d5a877f7d6b..6e7dc2f48b2 100755 --- a/src/main/drivers/bus.h +++ b/src/main/drivers/bus.h @@ -145,6 +145,7 @@ typedef enum { DEVHW_UG2864, // I2C OLED display DEVHW_SDCARD, // Generic SD-Card DEVHW_IRLOCK, // IR-Lock visual positioning hardware + DEVHW_PCF8574, // 8-bit I/O expander } devHardwareType_e; typedef enum { diff --git a/src/main/drivers/io_pcf8574.c b/src/main/drivers/io_pcf8574.c new file mode 100644 index 00000000000..dded542209f --- /dev/null +++ b/src/main/drivers/io_pcf8574.c @@ -0,0 +1,90 @@ +/* + * This file is part of INAV. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include +#include "drivers/bus.h" +#include "drivers/io_pcf8574.h" +#include "drivers/time.h" +#include "build/debug.h" + +#ifdef USE_PCF8574 + +#define PCF8574_WRITE_ADDRESS 0x40 +#define PCF8574_READ_ADDRESS 0x41 + +static busDevice_t *busDev; + +static bool deviceDetect(busDevice_t *busDev) +{ + for (int retry = 0; retry < 5; retry++) + { + uint8_t sig; + + delay(150); + + bool ack = busRead(busDev, 0x00, &sig); + if (ack) + { + return true; + } + }; + + return false; +} + +bool pcf8574Init(void) +{ + busDev = busDeviceInit(BUSTYPE_I2C, DEVHW_PCF8574, 0, 0); + if (busDev == NULL) + { + DEBUG_SET(DEBUG_PCF8574, 0, 1); + return false; + } + + if (!deviceDetect(busDev)) + { + DEBUG_SET(DEBUG_PCF8574, 0, 2); + busDeviceDeInit(busDev); + return false; + } + + pcf8574Write(0x00); //Set all ports to OFF + delay(25); + return true; +} + +void pcf8574Write(uint8_t data) +{ + busWrite(busDev, PCF8574_WRITE_ADDRESS, data); +} + +uint8_t pcf8574Read(void) +{ + uint8_t data; + busRead(busDev, PCF8574_READ_ADDRESS, &data); + return data; +} + +#endif \ No newline at end of file diff --git a/src/main/drivers/io_pcf8574.h b/src/main/drivers/io_pcf8574.h new file mode 100644 index 00000000000..dc87f69449a --- /dev/null +++ b/src/main/drivers/io_pcf8574.h @@ -0,0 +1,29 @@ +/* + * This file is part of INAV. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#pragma once + +bool pcf8574Init(void); +void pcf8574Write(uint8_t data); +uint8_t pcf8574Read(void); \ No newline at end of file diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index 1ee4dd016dd..dbc91f46818 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -83,6 +83,7 @@ #include "msc/emfat_file.h" #endif #include "drivers/sdcard/sdcard.h" +#include "drivers/io_pcf8574.h" #include "fc/cli.h" #include "fc/config.h" @@ -674,6 +675,11 @@ void init(void) } #endif +#ifdef USE_PCF8574 + bool pcfActive = pcf8574Init(); + DEBUG_SET(DEBUG_PCF8574, 1, pcfActive); +#endif + // Considering that the persistent reset reason is only used during init persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_NONE); diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 5ab9066e3d0..9493f039152 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -84,7 +84,7 @@ tables: "FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE", "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "ITERM_RELAX", "ERPM", "RPM_FILTER", "RPM_FREQ", "NAV_YAW", "DYNAMIC_FILTER", "DYNAMIC_FILTER_FREQUENCY", - "IRLOCK", "CD", "KALMAN"] + "IRLOCK", "CD", "KALMAN", "PCF8574"] - name: async_mode values: ["NONE", "GYRO", "ALL"] - name: aux_operator diff --git a/src/main/target/common.h b/src/main/target/common.h index a6ff91b0384..95bd52a71e6 100755 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -121,6 +121,9 @@ #define USE_D_BOOST #define USE_ANTIGRAVITY +#define USE_I2C_IO_EXPANDER +#define USE_PCF8574 + #else // FLASH_SIZE < 256 #define LOG_LEVEL_MAXIMUM LOG_LEVEL_ERROR #endif diff --git a/src/main/target/common_hardware.c b/src/main/target/common_hardware.c index b372e9c8f74..0818d119733 100755 --- a/src/main/target/common_hardware.c +++ b/src/main/target/common_hardware.c @@ -353,4 +353,21 @@ BUSDEV_REGISTER_I2C(busdev_irlock, DEVHW_IRLOCK, IRLOCK_I2C_BUS, 0x54, NONE, DEVFLAGS_USE_RAW_REGISTERS); #endif +#if defined(USE_I2C) && defined(USE_PCF8574) + + #if !defined(PCF8574_I2C_BUS) && defined(EXTERNAL_I2C_BUS) + #define PCF8574_I2C_BUS EXTERNAL_I2C_BUS + #endif + + #if !defined(PCF8574_I2C_BUS) && defined(DEFAULT_I2C_BUS) + #define PCF8574_I2C_BUS DEFAULT_I2C_BUS + #endif + + #if !defined(PCF8574_I2C_BUS) + #define PCF8574_I2C_BUS BUS_I2C1 + #endif + + BUSDEV_REGISTER_I2C(busdev_pcf8574, DEVHW_PCF8574, PCF8574_I2C_BUS, 0x20, NONE, DEVFLAGS_NONE, 0); +#endif + #endif // USE_TARGET_HARDWARE_DESCRIPTORS From 2e3f67f635ddd5b6169f82f57e9944126a5d53b5 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 20 Jul 2020 20:11:50 +0200 Subject: [PATCH 056/248] Logic Conditions integration --- make/source.mk | 1 + src/main/drivers/io_pcf8574.c | 8 +-- src/main/drivers/io_port_expander.c | 67 ++++++++++++++++++++++++++ src/main/drivers/io_port_expander.h | 37 ++++++++++++++ src/main/fc/fc_init.c | 7 ++- src/main/programming/logic_condition.c | 11 ++++- src/main/programming/logic_condition.h | 43 +++++++++-------- src/main/target/common.h | 1 - src/main/target/common_hardware.c | 2 +- 9 files changed, 142 insertions(+), 35 deletions(-) create mode 100644 src/main/drivers/io_port_expander.c create mode 100644 src/main/drivers/io_port_expander.h diff --git a/make/source.mk b/make/source.mk index d1b0b3e065d..37e70f9ee25 100644 --- a/make/source.mk +++ b/make/source.mk @@ -46,6 +46,7 @@ COMMON_SRC = \ drivers/io.c \ drivers/io_pca9685.c \ drivers/io_pcf8574.c \ + drivers/io_port_expander.c \ drivers/irlock.c \ drivers/light_led.c \ drivers/osd.c \ diff --git a/src/main/drivers/io_pcf8574.c b/src/main/drivers/io_pcf8574.c index dded542209f..b42386cf9b3 100644 --- a/src/main/drivers/io_pcf8574.c +++ b/src/main/drivers/io_pcf8574.c @@ -29,8 +29,6 @@ #include "drivers/time.h" #include "build/debug.h" -#ifdef USE_PCF8574 - #define PCF8574_WRITE_ADDRESS 0x40 #define PCF8574_READ_ADDRESS 0x41 @@ -70,8 +68,6 @@ bool pcf8574Init(void) return false; } - pcf8574Write(0x00); //Set all ports to OFF - delay(25); return true; } @@ -85,6 +81,4 @@ uint8_t pcf8574Read(void) uint8_t data; busRead(busDev, PCF8574_READ_ADDRESS, &data); return data; -} - -#endif \ No newline at end of file +} \ No newline at end of file diff --git a/src/main/drivers/io_port_expander.c b/src/main/drivers/io_port_expander.c new file mode 100644 index 00000000000..5125fe2260c --- /dev/null +++ b/src/main/drivers/io_port_expander.c @@ -0,0 +1,67 @@ +/* + * This file is part of INAV. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include +#include "platform.h" +#include "drivers/io_port_expander.h" +#include "drivers/io_pcf8574.h" + +#ifdef USE_I2C_IO_EXPANDER + +static ioPortExpanderState_t ioPortExpanderState; + +void ioPortExpanderInit(void) +{ + + ioPortExpanderState.active = pcf8574Init(); + + if (ioPortExpanderState.active) { + ioPortExpanderState.state = 0x00; + pcf8574Write(ioPortExpanderState.state); //Set all ports to OFF + } + +} + +void ioPortExpanderSet(uint8_t pin, uint8_t value) +{ + if (pin > 7) { + return; + } + + //Cast to 0/1 + value = (bool) value; + + ioPortExpanderState.state ^= (-value ^ ioPortExpanderState.state) & (1UL << pin); + ioPortExpanderState.shouldSync = true; +} + +void ioPortExpanderSync(void) +{ + if (ioPortExpanderState.active && ioPortExpanderState.shouldSync) { + pcf8574Write(ioPortExpanderState.state); + ioPortExpanderState.shouldSync = false;; + } +} + +#endif \ No newline at end of file diff --git a/src/main/drivers/io_port_expander.h b/src/main/drivers/io_port_expander.h new file mode 100644 index 00000000000..5a78b9b3c33 --- /dev/null +++ b/src/main/drivers/io_port_expander.h @@ -0,0 +1,37 @@ +/* + * This file is part of INAV. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#pragma once + +#include "stdint.h" + +typedef struct ioPortExpanderState_s { + uint8_t active; + uint8_t state; + uint8_t shouldSync; +} ioPortExpanderState_t; + +void ioPortExpanderInit(void); +void ioPortExpanderSync(void); +void ioPortExpanderSet(uint8_t pin, uint8_t value); \ No newline at end of file diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index dbc91f46818..d5b1d071d45 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -83,7 +83,7 @@ #include "msc/emfat_file.h" #endif #include "drivers/sdcard/sdcard.h" -#include "drivers/io_pcf8574.h" +#include "drivers/io_port_expander.h" #include "fc/cli.h" #include "fc/config.h" @@ -675,9 +675,8 @@ void init(void) } #endif -#ifdef USE_PCF8574 - bool pcfActive = pcf8574Init(); - DEBUG_SET(DEBUG_PCF8574, 1, pcfActive); +#ifdef USE_I2C_IO_EXPANDER + ioPortExpanderInit(); #endif // Considering that the persistent reset reason is only used during init diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index d42d62fa71c..a63196b3fec 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -41,6 +41,7 @@ #include "sensors/pitotmeter.h" #include "flight/imu.h" #include "flight/pid.h" +#include "drivers/io_port_expander.h" #include "navigation/navigation.h" #include "navigation/navigation_private.h" @@ -180,7 +181,12 @@ static int logicConditionCompute( return operandA; } break; - +#ifdef USE_I2C_IO_EXPANDER + case LOGIC_CONDITION_PORT_SET: + ioPortExpanderSet((uint8_t)operandA, (uint8_t)operandB); + return operandB; + break; +#endif default: return false; break; @@ -456,6 +462,9 @@ void logicConditionUpdateTask(timeUs_t currentTimeUs) { for (uint8_t i = 0; i < MAX_LOGIC_CONDITIONS; i++) { logicConditionProcess(i); } +#ifdef USE_I2C_IO_EXPANDER + ioPortExpanderSync(); +#endif } void logicConditionReset(void) { diff --git a/src/main/programming/logic_condition.h b/src/main/programming/logic_condition.h index f48383870ab..2ae2db83110 100644 --- a/src/main/programming/logic_condition.h +++ b/src/main/programming/logic_condition.h @@ -29,27 +29,28 @@ #define MAX_LOGIC_CONDITIONS 16 typedef enum { - LOGIC_CONDITION_TRUE = 0, // 0 - LOGIC_CONDITION_EQUAL, // 1 - LOGIC_CONDITION_GREATER_THAN, // 2 - LOGIC_CONDITION_LOWER_THAN, // 3 - LOGIC_CONDITION_LOW, // 4 - LOGIC_CONDITION_MID, // 5 - LOGIC_CONDITION_HIGH, // 6 - LOGIC_CONDITION_AND, // 7 - LOGIC_CONDITION_OR, // 8 - LOGIC_CONDITION_XOR, // 9 - LOGIC_CONDITION_NAND, // 10 - LOGIC_CONDITION_NOR, // 11 - LOGIC_CONDITION_NOT, // 12 - LOGIC_CONDITION_STICKY, // 13 - LOGIC_CONDITION_ADD, // 14 - LOGIC_CONDITION_SUB, // 15 - LOGIC_CONDITION_MUL, // 16 - LOGIC_CONDITION_DIV, // 17 - LOGIC_CONDITION_GVAR_SET, // 18 - LOGIC_CONDITION_GVAR_INC, // 19 - LOGIC_CONDITION_GVAR_DEC, // 20 + LOGIC_CONDITION_TRUE = 0, + LOGIC_CONDITION_EQUAL = 1, + LOGIC_CONDITION_GREATER_THAN = 2, + LOGIC_CONDITION_LOWER_THAN = 3, + LOGIC_CONDITION_LOW = 4, + LOGIC_CONDITION_MID = 5, + LOGIC_CONDITION_HIGH = 6, + LOGIC_CONDITION_AND = 7, + LOGIC_CONDITION_OR = 8, + LOGIC_CONDITION_XOR = 9, + LOGIC_CONDITION_NAND = 10, + LOGIC_CONDITION_NOR = 11, + LOGIC_CONDITION_NOT = 12, + LOGIC_CONDITION_STICKY = 13, + LOGIC_CONDITION_ADD = 14, + LOGIC_CONDITION_SUB = 15, + LOGIC_CONDITION_MUL = 16, + LOGIC_CONDITION_DIV = 17, + LOGIC_CONDITION_GVAR_SET = 18, + LOGIC_CONDITION_GVAR_INC = 19, + LOGIC_CONDITION_GVAR_DEC = 20, + LOGIC_CONDITION_PORT_SET = 128, LOGIC_CONDITION_LAST } logicOperation_e; diff --git a/src/main/target/common.h b/src/main/target/common.h index 95bd52a71e6..95d55be5360 100755 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -122,7 +122,6 @@ #define USE_ANTIGRAVITY #define USE_I2C_IO_EXPANDER -#define USE_PCF8574 #else // FLASH_SIZE < 256 #define LOG_LEVEL_MAXIMUM LOG_LEVEL_ERROR diff --git a/src/main/target/common_hardware.c b/src/main/target/common_hardware.c index 0818d119733..ad8736d0db6 100755 --- a/src/main/target/common_hardware.c +++ b/src/main/target/common_hardware.c @@ -353,7 +353,7 @@ BUSDEV_REGISTER_I2C(busdev_irlock, DEVHW_IRLOCK, IRLOCK_I2C_BUS, 0x54, NONE, DEVFLAGS_USE_RAW_REGISTERS); #endif -#if defined(USE_I2C) && defined(USE_PCF8574) +#if defined(USE_I2C) && defined(USE_I2C_IO_EXPANDER) #if !defined(PCF8574_I2C_BUS) && defined(EXTERNAL_I2C_BUS) #define PCF8574_I2C_BUS EXTERNAL_I2C_BUS From 37d35b505d9781148ec30b29928a53ce36bb2fca Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 20 Jul 2020 20:42:31 +0200 Subject: [PATCH 057/248] Docs update --- docs/Logic Conditions.md | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/docs/Logic Conditions.md b/docs/Logic Conditions.md index 97f24933bb4..10ffc058d41 100644 --- a/docs/Logic Conditions.md +++ b/docs/Logic Conditions.md @@ -39,6 +39,14 @@ Logic conditions can be edited using INAV Configurator user interface, of via CL | 11 | NOR | | | 12 | NOT | | | 13 | STICKY | `Operand A` is activation operator, `Operand B` is deactivation operator. After activation, operator will return `true` until Operand B is evaluated as `true`| +| 14 | ADD | Add `Operand A` to `Operand B` and returns the result | +| 15 | SUB | Substract `Operand B` from `Operand A` and returns the result | +| 16 | MUL | Multiply `Operand A` by `Operand B` and returns the result | +| 17 | DIV | Divide `Operand A` by `Operand B` and returns the result | +| 18 | GVAR SET | Store value from `Operand B` into the Global Variable addressed by `Operand B`. Bear in mind, that operand `Global Variable` means: Value stored in Global Variable of an index! To store in GVAR 1 use `Value 1` not `Global Variable 1` | +| 19 | GVAR INC | Increase the GVAR indexed by `Operand A` with value from `Operand B` | +| 20 | GVAR DEC | Decrease the GVAR indexed by `Operand A` with value from `Operand B` | +| 128 | IO PORT SET | Set I2C IO Expander pin `Operand A` to value of `Operand B`. `Operand A` accepts values `0-7` and `Operand B` accepts `0` and `1` | ### Operands @@ -49,6 +57,7 @@ Logic conditions can be edited using INAV Configurator user interface, of via CL | 2 | FLIGHT | `value` points to flight parameter table | | 3 | FLIGHT_MODE | `value` points to flight modes table | | 4 | LC | `value` points to other logic condition ID | +| 5 | GVAR | Value stored in Global Variable indexed by `value`. `GVAR 1` means: value in GVAR 1 | #### FLIGHT From 707133c4db1c59338746add1da31fd029fac090b Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Mon, 20 Jul 2020 21:13:35 +0200 Subject: [PATCH 058/248] Add Smartport Master (#5724) --- make/source.mk | 1 + src/main/build/debug.h | 3 + src/main/common/utils.h | 3 + src/main/config/parameter_group_ids.h | 3 +- src/main/fc/fc_init.c | 5 + src/main/fc/fc_tasks.c | 20 + src/main/fc/settings.yaml | 16 +- src/main/io/serial.h | 49 +-- src/main/io/smartport_master.c | 591 ++++++++++++++++++++++++++ src/main/io/smartport_master.h | 87 ++++ src/main/scheduler/scheduler.h | 3 + 11 files changed, 754 insertions(+), 27 deletions(-) create mode 100644 src/main/io/smartport_master.c create mode 100644 src/main/io/smartport_master.h diff --git a/make/source.mk b/make/source.mk index e1b9aa12847..57909d6ec2d 100644 --- a/make/source.mk +++ b/make/source.mk @@ -202,6 +202,7 @@ COMMON_SRC = \ io/osd_common.c \ io/osd_grid.c \ io/osd_hud.c \ + io/smartport_master.c \ navigation/navigation.c \ navigation/navigation_fixedwing.c \ navigation/navigation_fw_launch.c \ diff --git a/src/main/build/debug.h b/src/main/build/debug.h index a5a5e90ea65..cb05965d31e 100644 --- a/src/main/build/debug.h +++ b/src/main/build/debug.h @@ -73,5 +73,8 @@ typedef enum { DEBUG_IRLOCK, DEBUG_CD, DEBUG_KALMAN, + DEBUG_SPM_CELLS, // Smartport master FLVSS + DEBUG_SPM_VS600, // Smartport master VS600 VTX + DEBUG_SPM_VARIO, // Smartport master variometer DEBUG_COUNT } debugType_e; diff --git a/src/main/common/utils.h b/src/main/common/utils.h index 3ed062a198f..d1f42515b61 100644 --- a/src/main/common/utils.h +++ b/src/main/common/utils.h @@ -52,6 +52,7 @@ #define BUILD_BUG_ON(condition) ((void)sizeof(char[1 - 2*!!(condition)])) #define BIT(x) (1 << (x)) +#define GET_BIT(value, bit) ((value >> bit) & 1) #define STATIC_ASSERT(condition, name) \ typedef char assert_failed_ ## name [(condition) ? 1 : -1 ] __attribute__((unused)) @@ -112,3 +113,5 @@ void * memcpy_fn ( void * destination, const void * source, size_t num ) asm("me #define UNREACHABLE() __builtin_unreachable() #define ALIGNED(x) __attribute__ ((aligned(x))) + +#define PACKED __attribute__((packed)) diff --git a/src/main/config/parameter_group_ids.h b/src/main/config/parameter_group_ids.h index 104a3e46278..c07afcb82fb 100644 --- a/src/main/config/parameter_group_ids.h +++ b/src/main/config/parameter_group_ids.h @@ -111,7 +111,8 @@ #define PG_ESC_SENSOR_CONFIG 1021 #define PG_RPM_FILTER_CONFIG 1022 #define PG_GLOBAL_VARIABLE_CONFIG 1023 -#define PG_INAV_END 1023 +#define PG_SMARTPORT_MASTER_CONFIG 1024 +#define PG_INAV_END 1024 // OSD configuration (subject to change) //#define PG_OSD_FONT_CONFIG 2047 diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index 1ee4dd016dd..de5b2e7c9ac 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -114,6 +114,7 @@ #include "io/rcdevice_cam.h" #include "io/serial.h" #include "io/displayport_msp.h" +#include "io/smartport_master.h" #include "io/vtx.h" #include "io/vtx_control.h" #include "io/vtx_smartaudio.h" @@ -280,6 +281,10 @@ void init(void) djiOsdSerialInit(); #endif +#if defined(USE_SMARTPORT_MASTER) + smartportMasterInit(); +#endif + #if defined(USE_LOG) // LOG might use serial output, so we only can init it after serial port is ready // From this point on we can use LOG_*() to produce real-time debugging information diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index f79c596b9f6..3207509ea3b 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -61,6 +61,7 @@ #include "io/pwmdriver_i2c.h" #include "io/serial.h" #include "io/rcdevice_cam.h" +#include "io/smartport_master.h" #include "io/vtx.h" #include "io/osd_dji_hd.h" #include "io/servo_sbus.h" @@ -251,6 +252,13 @@ void taskTelemetry(timeUs_t currentTimeUs) } #endif +#if defined(USE_SMARTPORT_MASTER) +void taskSmartportMaster(timeUs_t currentTimeUs) +{ + smartportMasterHandle(currentTimeUs); +} +#endif + #ifdef USE_LED_STRIP void taskLedStrip(timeUs_t currentTimeUs) { @@ -360,6 +368,9 @@ void fcTasksInit(void) #ifdef USE_IRLOCK setTaskEnabled(TASK_IRLOCK, irlockHasBeenDetected()); #endif +#if defined(USE_SMARTPORT_MASTER) + setTaskEnabled(TASK_SMARTPORT_MASTER, true); +#endif } cfTask_t cfTasks[TASK_COUNT] = { @@ -494,6 +505,15 @@ cfTask_t cfTasks[TASK_COUNT] = { }, #endif +#if defined(USE_SMARTPORT_MASTER) + [TASK_SMARTPORT_MASTER] = { + .taskName = "SPORT MASTER", + .taskFunc = taskSmartportMaster, + .desiredPeriod = TASK_PERIOD_HZ(500), // 500 Hz + .staticPriority = TASK_PRIORITY_IDLE, + }, +#endif + #ifdef USE_LED_STRIP [TASK_LEDSTRIP] = { .taskName = "LEDSTRIP", diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 5ab9066e3d0..d0ab6d67ee2 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -25,7 +25,7 @@ tables: values: ["NONE", "PPM", "SERIAL", "MSP", "SPI", "UIB"] enum: rxReceiverType_e - name: serial_rx - values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "SUMH", "XB-B", "XB-B-RJ01", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "SBUS_FAST"] + values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "SUMH", "XB-B", "XB-B-RJ01", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "FPORT2", "SBUS_FAST"] - name: rx_spi_protocol values: ["V202_250K", "V202_1M", "SYMA_X", "SYMA_X5C", "CX10", "CX10A", "H8_3D", "INAV", "ELERES"] enum: rx_spi_protocol_e @@ -84,7 +84,7 @@ tables: "FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE", "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "ITERM_RELAX", "ERPM", "RPM_FILTER", "RPM_FREQ", "NAV_YAW", "DYNAMIC_FILTER", "DYNAMIC_FILTER_FREQUENCY", - "IRLOCK", "CD", "KALMAN"] + "IRLOCK", "CD", "KALMAN", "SPM_CELLS", "SPM_VS600", "SPM_VARIO"] - name: async_mode values: ["NONE", "GYRO", "ALL"] - name: aux_operator @@ -3005,3 +3005,15 @@ groups: - name: esc_sensor_listen_only field: listenOnly type: bool + + - name: PG_SMARTPORT_MASTER_CONFIG + type: smartportMasterConfig_t + headers: ["io/smartport_master.h"] + condition: USE_SMARTPORT_MASTER + members: + - name: smartport_master_halfduplex + field: halfDuplex + type: bool + - name: smartport_master_inverted + field: inverted + type: bool diff --git a/src/main/io/serial.h b/src/main/io/serial.h index 6f77480f730..76e57b36388 100644 --- a/src/main/io/serial.h +++ b/src/main/io/serial.h @@ -30,30 +30,31 @@ typedef enum { } portSharing_e; typedef enum { - FUNCTION_NONE = 0, - FUNCTION_MSP = (1 << 0), // 1 - FUNCTION_GPS = (1 << 1), // 2 - FUNCTION_TELEMETRY_FRSKY = (1 << 2), // 4 - FUNCTION_TELEMETRY_HOTT = (1 << 3), // 8 - FUNCTION_TELEMETRY_LTM = (1 << 4), // 16 - FUNCTION_TELEMETRY_SMARTPORT = (1 << 5), // 32 - FUNCTION_RX_SERIAL = (1 << 6), // 64 - FUNCTION_BLACKBOX = (1 << 7), // 128 - FUNCTION_TELEMETRY_MAVLINK = (1 << 8), // 256 - FUNCTION_TELEMETRY_IBUS = (1 << 9), // 512 - FUNCTION_RCDEVICE = (1 << 10), // 1024 - FUNCTION_VTX_SMARTAUDIO = (1 << 11), // 2048 - FUNCTION_VTX_TRAMP = (1 << 12), // 4096 - FUNCTION_UAV_INTERCONNECT = (1 << 13), // 8192 - FUNCTION_OPTICAL_FLOW = (1 << 14), // 16384 - FUNCTION_LOG = (1 << 15), // 32768 - FUNCTION_RANGEFINDER = (1 << 16), // 65536 - FUNCTION_VTX_FFPV = (1 << 17), // 131072 - FUNCTION_ESCSERIAL = (1 << 18), // 262144: this is used for both SERIALSHOT and ESC_SENSOR telemetry - FUNCTION_TELEMETRY_SIM = (1 << 19), // 524288 - FUNCTION_FRSKY_OSD = (1 << 20), // 1048576 - FUNCTION_DJI_HD_OSD = (1 << 21), // 2097152 - FUNCTION_SERVO_SERIAL = (1 << 22), // 4194304 + FUNCTION_NONE = 0, + FUNCTION_MSP = (1 << 0), // 1 + FUNCTION_GPS = (1 << 1), // 2 + FUNCTION_TELEMETRY_FRSKY = (1 << 2), // 4 + FUNCTION_TELEMETRY_HOTT = (1 << 3), // 8 + FUNCTION_TELEMETRY_LTM = (1 << 4), // 16 + FUNCTION_TELEMETRY_SMARTPORT = (1 << 5), // 32 + FUNCTION_RX_SERIAL = (1 << 6), // 64 + FUNCTION_BLACKBOX = (1 << 7), // 128 + FUNCTION_TELEMETRY_MAVLINK = (1 << 8), // 256 + FUNCTION_TELEMETRY_IBUS = (1 << 9), // 512 + FUNCTION_RCDEVICE = (1 << 10), // 1024 + FUNCTION_VTX_SMARTAUDIO = (1 << 11), // 2048 + FUNCTION_VTX_TRAMP = (1 << 12), // 4096 + FUNCTION_UAV_INTERCONNECT = (1 << 13), // 8192 + FUNCTION_OPTICAL_FLOW = (1 << 14), // 16384 + FUNCTION_LOG = (1 << 15), // 32768 + FUNCTION_RANGEFINDER = (1 << 16), // 65536 + FUNCTION_VTX_FFPV = (1 << 17), // 131072 + FUNCTION_ESCSERIAL = (1 << 18), // 262144: this is used for both SERIALSHOT and ESC_SENSOR telemetry + FUNCTION_TELEMETRY_SIM = (1 << 19), // 524288 + FUNCTION_FRSKY_OSD = (1 << 20), // 1048576 + FUNCTION_DJI_HD_OSD = (1 << 21), // 2097152 + FUNCTION_SERVO_SERIAL = (1 << 22), // 4194304 + FUNCTION_TELEMETRY_SMARTPORT_MASTER = (1 << 23), // 8388608 } serialPortFunction_e; typedef enum { diff --git a/src/main/io/smartport_master.c b/src/main/io/smartport_master.c new file mode 100644 index 00000000000..cc51b4235dd --- /dev/null +++ b/src/main/io/smartport_master.c @@ -0,0 +1,591 @@ +/* + * This file is part of iNav. + * + * iNav is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * iNav is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with iNav. If not, see . + */ + +#include +#include +#include + +#include "platform.h" +FILE_COMPILE_FOR_SPEED + +#if defined(USE_SMARTPORT_MASTER) + +#include "build/debug.h" + +#include "common/utils.h" + +#include "config/parameter_group.h" +#include "config/parameter_group_ids.h" + +#include "drivers/serial.h" +#include "drivers/time.h" + +#include "io/serial.h" +#include "io/smartport_master.h" + +#include "rx/frsky_crc.h" + +enum { + PRIM_DISCARD_FRAME = 0x00, + PRIM_DATA_FRAME = 0x10, + PRIM_WORKING_STATE = 0x20, + PRIM_IDLE_STATE = 0x21, + PRIM_CONFIG_READ = 0x30, + PRIM_CONFIG_WRITE = 0x31, + PRIM_CONFIG_RESPONSE = 0x32, + PRIM_DIAG_READ = 0X40, + PRIM_DIAG_WRITE = 0X41, + PRIM_ENABLE_APP_NODE = 0x70, + PRIM_DISABLE_APP_NODE = 0x71, +}; + +enum +{ + DATAID_SPEED = 0x0830, + DATAID_VFAS = 0x0210, + DATAID_CURRENT = 0x0200, + DATAID_RPM = 0x050F, + DATAID_ALTITUDE = 0x0100, + DATAID_FUEL = 0x0600, + DATAID_ADC1 = 0xF102, + DATAID_ADC2 = 0xF103, + DATAID_LATLONG = 0x0800, + DATAID_CAP_USED = 0x0600, + DATAID_VARIO = 0x0110, + DATAID_CELLS = 0x0300, + DATAID_CELLS_LAST = 0x030F, + DATAID_HEADING = 0x0840, + DATAID_FPV = 0x0450, + DATAID_PITCH = 0x0430, + DATAID_ROLL = 0x0440, + DATAID_ACCX = 0x0700, + DATAID_ACCY = 0x0710, + DATAID_ACCZ = 0x0720, + DATAID_T1 = 0x0400, + DATAID_T2 = 0x0410, + DATAID_HOME_DIST = 0x0420, + DATAID_GPS_ALT = 0x0820, + DATAID_ASPD = 0x0A00, + DATAID_A3 = 0x0900, + DATAID_A4 = 0x0910, + DATAID_VS600 = 0x0E10 +}; + +#define SMARTPORT_BAUD 57600 +#define SMARTPORT_UART_MODE MODE_RXTX + +#define SMARTPORT_PHYID_MAX 0x1B +#define SMARTPORT_PHYID_COUNT (SMARTPORT_PHYID_MAX + 1) + +#define SMARTPORT_POLLING_INTERVAL 12 // ms + +#define SMARTPORT_FRAME_START 0x7E +#define SMARTPORT_BYTESTUFFING_MARKER 0x7D +#define SMARTPORT_BYTESTUFFING_XOR_VALUE 0x20 + +#define SMARTPORT_SENSOR_DATA_TIMEOUT 500 // ms + +#define SMARTPORT_FORWARD_REQUESTS_MAX 10 + +typedef enum { + PT_ACTIVE_ID, + PT_INACTIVE_ID +} pollType_e; + +typedef struct smartPortMasterFrame_s { + uint8_t magic; + uint8_t phyID; + smartPortPayload_t payload; + uint8_t crc; +} PACKED smartportFrame_t; + +typedef union { + smartportFrame_t frame; + uint8_t bytes[sizeof(smartportFrame_t)]; +} smartportFrameBuffer_u; + +typedef struct { + cellsData_t cells; + timeUs_t cellsTimestamp; + vs600Data_t vs600; + timeUs_t vs600Timestamp; + int32_t altitude; + timeUs_t altitudeTimestamp; + int16_t vario; + timeUs_t varioTimestamp; +} smartportSensorsData_t; + +typedef struct { + uint8_t phyID; + smartPortPayload_t payload; +} smartportForwardData_t; + +PG_REGISTER_WITH_RESET_TEMPLATE(smartportMasterConfig_t, smartportMasterConfig, PG_SMARTPORT_MASTER_CONFIG, 0); + +PG_RESET_TEMPLATE(smartportMasterConfig_t, smartportMasterConfig, + .halfDuplex = true, + .inverted = false +); + +static serialPort_t *smartportMasterSerialPort = NULL; +static serialPortConfig_t *portConfig; +static int8_t currentPolledPhyID = -1; +static int8_t forcedPolledPhyID = -1; +static uint8_t rxBufferLen = 0; + +static uint32_t activePhyIDs = 0; +static smartPortPayload_t sensorPayloadCache[SMARTPORT_PHYID_COUNT]; + +static uint8_t forwardRequestsStart = 0; +static uint8_t forwardRequestsEnd = 0; +static smartportForwardData_t forwardRequests[SMARTPORT_FORWARD_REQUESTS_MAX]; // Forward requests' circular buffer + +static uint8_t forwardResponsesCount = 0; +static smartportForwardData_t forwardResponses[SMARTPORT_FORWARD_REQUESTS_MAX]; // Forward responses' buffer + +static smartportSensorsData_t sensorsData; + + +bool smartportMasterInit(void) +{ + portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_SMARTPORT_MASTER); + if (!portConfig) { + return false; + } + + portOptions_t portOptions = (smartportMasterConfig()->halfDuplex ? SERIAL_BIDIR : SERIAL_UNIDIR) | (smartportMasterConfig()->inverted ? SERIAL_NOT_INVERTED : SERIAL_INVERTED); + smartportMasterSerialPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_SMARTPORT_MASTER, NULL, NULL, SMARTPORT_BAUD, SMARTPORT_UART_MODE, portOptions); + + memset(&sensorsData, 0, sizeof(sensorsData)); + + return true; +} + +static void phyIDSetActive(uint8_t phyID, bool active) +{ + uint32_t mask = 1 << phyID; + if (active) { + activePhyIDs |= mask; + } else { + activePhyIDs &= ~mask; + } +} + +static uint32_t phyIDAllActiveMask(void) +{ + uint32_t mask = 0; + for (uint8_t i = 0; i < SMARTPORT_PHYID_COUNT; ++i) { + mask |= 1 << i; + } + return mask; +} + +static int8_t phyIDNext(uint8_t start, bool active, bool loop) +{ + for (uint8_t i = start; i < ((loop ? start : 0) + SMARTPORT_PHYID_COUNT); ++i) { + uint8_t phyID = i % SMARTPORT_PHYID_COUNT; + uint32_t mask = 1 << phyID; + uint32_t phyIDMasked = activePhyIDs & mask; + if ((active && phyIDMasked) || !(active || phyIDMasked)) { + return phyID; + } + } + return -1; +} + +static bool phyIDIsActive(uint8_t id) +{ + return !!(activePhyIDs & (1 << id)); +} + +static bool phyIDNoneActive(void) +{ + return activePhyIDs == 0; +} + +static bool phyIDAllActive(void) +{ + static uint32_t allActiveMask = 0; + + if (!allActiveMask) { + allActiveMask = phyIDAllActiveMask(); + } + + return !!((activePhyIDs & allActiveMask) == allActiveMask); +} + +static bool phyIDAnyActive(void) +{ + return !!activePhyIDs; +} + +static void smartportMasterSendByte(uint8_t byte) +{ + serialWrite(smartportMasterSerialPort, byte); +} + +static void smartportMasterPhyIDFillCheckBits(uint8_t *phyIDByte) +{ + *phyIDByte |= (GET_BIT(*phyIDByte, 0) ^ GET_BIT(*phyIDByte, 1) ^ GET_BIT(*phyIDByte, 2)) << 5; + *phyIDByte |= (GET_BIT(*phyIDByte, 2) ^ GET_BIT(*phyIDByte, 3) ^ GET_BIT(*phyIDByte, 4)) << 6; + *phyIDByte |= (GET_BIT(*phyIDByte, 0) ^ GET_BIT(*phyIDByte, 2) ^ GET_BIT(*phyIDByte, 4)) << 7; +} + +static void smartportMasterPoll(void) +{ + static pollType_e nextPollType = PT_INACTIVE_ID; + static uint8_t nextActivePhyID = 0, nextInactivePhyID = 0; + uint8_t phyIDToPoll; + + if (currentPolledPhyID != -1) { + // currentPolledPhyID hasn't been reset by smartportMasterReceive so we didn't get valid data for this PhyID (inactive) + phyIDSetActive(currentPolledPhyID, false); + } + + if (forcedPolledPhyID != -1) { + + phyIDToPoll = forcedPolledPhyID; + forcedPolledPhyID = -1; + + } else { + + if (phyIDNoneActive()) { + nextPollType = PT_INACTIVE_ID; + } else if (phyIDAllActive()) { + nextPollType = PT_ACTIVE_ID; + } + + switch (nextPollType) { + + case PT_ACTIVE_ID: { + int8_t activePhyIDToPoll = phyIDNext(nextActivePhyID, true, false); + if (activePhyIDToPoll == -1) { + nextActivePhyID = 0; + nextPollType = PT_INACTIVE_ID; + } else { + phyIDToPoll = activePhyIDToPoll; + if (phyIDToPoll == SMARTPORT_PHYID_MAX) { + nextActivePhyID = 0; + if (!phyIDAllActive()) { + nextPollType = PT_INACTIVE_ID; + } + } else { + nextActivePhyID = phyIDToPoll + 1; + } + break; + } + FALLTHROUGH; + } + + case PT_INACTIVE_ID: { + phyIDToPoll = phyIDNext(nextInactivePhyID, false, true); + nextInactivePhyID = (phyIDToPoll == SMARTPORT_PHYID_MAX ? 0 : phyIDToPoll + 1); + if (phyIDAnyActive()) { + nextPollType = PT_ACTIVE_ID; + } + break; + } + + } + + } + + currentPolledPhyID = phyIDToPoll; + smartportMasterPhyIDFillCheckBits(&phyIDToPoll); + + // poll + smartportMasterSendByte(SMARTPORT_FRAME_START); + smartportMasterSendByte(phyIDToPoll); + + rxBufferLen = 0; // discard incomplete frames received during previous poll +} + +static void smartportMasterForwardNextPayload(void) +{ + smartportForwardData_t *request = forwardRequests + forwardRequestsStart; + + /*forcedPolledPhyID = request->phyID; // force next poll to the request's phyID XXX disabled, doesn't seem necessary */ + + smartportMasterPhyIDFillCheckBits(&request->phyID); + smartportMasterSendByte(SMARTPORT_FRAME_START); + smartportMasterSendByte(request->phyID); + + uint16_t checksum = 0; + uint8_t *payloadPtr = (uint8_t *)&request->payload; + for (uint8_t i = 0; i < sizeof(request->payload); ++i) { + uint8_t c = *payloadPtr++; + if ((c == SMARTPORT_FRAME_START) || (c == SMARTPORT_BYTESTUFFING_MARKER)) { + smartportMasterSendByte(SMARTPORT_BYTESTUFFING_MARKER); + smartportMasterSendByte(c ^ SMARTPORT_BYTESTUFFING_XOR_VALUE); + } else { + smartportMasterSendByte(c); + } + checksum += c; + } + checksum = 0xff - ((checksum & 0xff) + (checksum >> 8)); + smartportMasterSendByte(checksum); + + forwardRequestsStart = (forwardRequestsStart + 1) % SMARTPORT_FORWARD_REQUESTS_MAX; +} + +static void decodeCellsData(uint32_t sdata) +{ + uint8_t voltageStartIndex = sdata & 0xF; + uint8_t count = sdata >> 4 & 0xF; + uint16_t voltage1 = (sdata >> 8 & 0xFFF) * 2; + uint16_t voltage2 = (sdata >> 20 & 0xFFF) * 2; + if ((voltageStartIndex <= 4) && (count <= 6)) { // sanity check + cellsData_t *cd = &sensorsData.cells; + cd->count = count; + cd->voltage[voltageStartIndex] = voltage1; + cd->voltage[voltageStartIndex+1] = voltage2; + + DEBUG_SET(DEBUG_SPM_CELLS, 0, cd->count); + for (uint8_t i = 0; i < 6; ++i) { + DEBUG_SET(DEBUG_SPM_CELLS, i+1, cd->voltage[i]); + } + } +} + +static void decodeVS600Data(uint32_t sdata) +{ + vs600Data_t *vs600 = &sensorsData.vs600; + vs600->power = (sdata >> 8) & 0xFF; + vs600->band = (sdata >> 16) & 0xFF; + vs600->channel = (sdata >> 24) & 0xFF; + DEBUG_SET(DEBUG_SPM_VS600, 0, sdata); + DEBUG_SET(DEBUG_SPM_VS600, 1, vs600->channel); + DEBUG_SET(DEBUG_SPM_VS600, 2, vs600->band); + DEBUG_SET(DEBUG_SPM_VS600, 3, vs600->power); +} + +static void decodeAltitudeData(uint32_t sdata) +{ + sensorsData.altitude = sdata * 5; // cm + DEBUG_SET(DEBUG_SPM_VARIO, 0, sensorsData.altitude); +} + +static void decodeVarioData(uint32_t sdata) +{ + sensorsData.vario = sdata * 2; // mm/s + DEBUG_SET(DEBUG_SPM_VARIO, 1, sensorsData.vario); +} + +static void processSensorPayload(smartPortPayload_t *payload, timeUs_t currentTimeUs) +{ + switch (payload->valueId) { + case DATAID_CELLS: + decodeCellsData(payload->data); + sensorsData.cellsTimestamp = currentTimeUs; + break; + + case DATAID_VS600: + decodeVS600Data(payload->data); + sensorsData.vs600Timestamp = currentTimeUs; + break; + + case DATAID_ALTITUDE: + decodeAltitudeData(payload->data); + sensorsData.altitudeTimestamp = currentTimeUs; + break; + + case DATAID_VARIO: + decodeVarioData(payload->data); + sensorsData.varioTimestamp = currentTimeUs; + break; + } + sensorPayloadCache[currentPolledPhyID] = *payload; +} + +static void processPayload(smartPortPayload_t *payload, timeUs_t currentTimeUs) +{ + switch (payload->frameId) { + + case PRIM_DISCARD_FRAME: + break; + + case PRIM_DATA_FRAME: + processSensorPayload(payload, currentTimeUs); + break; + + default: + if (forwardResponsesCount < SMARTPORT_FORWARD_REQUESTS_MAX) { + smartportForwardData_t *response = forwardResponses + forwardResponsesCount; + response->phyID = currentPolledPhyID; + response->payload = *payload; + forwardResponsesCount += 1; + } + break; + } +} + +static void smartportMasterReceive(timeUs_t currentTimeUs) +{ + static smartportFrameBuffer_u buffer; + static bool processByteStuffing = false; + + if (!rxBufferLen) { + processByteStuffing = false; + } + + while (serialRxBytesWaiting(smartportMasterSerialPort)) { + + uint8_t c = serialRead(smartportMasterSerialPort); + + if (currentPolledPhyID == -1) { // We did not poll a sensor or a packet has already been received and processed + continue; + } + + if (processByteStuffing) { + c ^= SMARTPORT_BYTESTUFFING_XOR_VALUE; + processByteStuffing = false; + } else if (c == SMARTPORT_BYTESTUFFING_MARKER) { + processByteStuffing = true; + continue; + } + + buffer.bytes[rxBufferLen] = c; + rxBufferLen += 1; + + if (rxBufferLen == sizeof(buffer)) { // frame complete + + uint8_t calcCRC = frskyCheckSum((uint8_t *)&buffer.frame.payload, sizeof(buffer.frame.payload)); + + if (buffer.frame.crc == calcCRC) { + phyIDSetActive(currentPolledPhyID, true); + processPayload(&buffer.frame.payload, currentTimeUs); + } + + currentPolledPhyID = -1; // previously polled PhyID has answered, not expecting more data until next poll + rxBufferLen = 0; // reset buffer + + } + + } +} + +bool smartportMasterGetSensorPayload(uint8_t phyID, smartPortPayload_t *payload) +{ + if ((phyID > SMARTPORT_PHYID_MAX) || !phyIDIsActive(phyID)) { + return false; + } + + *payload = sensorPayloadCache[phyID]; + return true; +} + +bool smartportMasterHasForwardResponse(uint8_t phyID) +{ + for (uint8_t i = 0; i < forwardResponsesCount; ++i) { + smartportForwardData_t *response = forwardResponses + i; + if (response->phyID == phyID) { + return true; + } + } + + return false; +} + +bool smartportMasterNextForwardResponse(uint8_t phyID, smartPortPayload_t *payload) +{ + for (uint8_t i = 0; i < forwardResponsesCount; ++i) { + smartportForwardData_t *response = forwardResponses + i; + if (response->phyID == phyID) { + *payload = response->payload; + forwardResponsesCount -= 1; + memmove(response, response + 1, (forwardResponsesCount - i) * sizeof(*response)); + return true; + } + } + + return false; +} + +static uint8_t forwardRequestCount(void) +{ + if (forwardRequestsStart > forwardRequestsEnd) { + return SMARTPORT_FORWARD_REQUESTS_MAX - forwardRequestsStart + forwardRequestsEnd; + } else { + return forwardRequestsEnd - forwardRequestsStart; + } +} + +bool smartportMasterForward(uint8_t phyID, smartPortPayload_t *payload) +{ + if (forwardRequestCount() == SMARTPORT_FORWARD_REQUESTS_MAX) { + return false; + } + + smartportForwardData_t *request = forwardRequests + forwardRequestsEnd; + request->phyID = phyID; + request->payload = *payload; + forwardRequestsEnd = (forwardRequestsEnd + 1) % SMARTPORT_FORWARD_REQUESTS_MAX; + return true; +} + +void smartportMasterHandle(timeUs_t currentTimeUs) +{ + static timeUs_t pollTimestamp = 0; + + if (!smartportMasterSerialPort) { + return; + } + + if (!pollTimestamp || (cmpTimeUs(currentTimeUs, pollTimestamp) > SMARTPORT_POLLING_INTERVAL * 1000)) { + if (forwardRequestCount() && (forcedPolledPhyID == -1)) { // forward next payload if there is one in queue and we are not waiting from the response of the previous one + smartportMasterForwardNextPayload(); + } else { + smartportMasterPoll(); + } + pollTimestamp = currentTimeUs; + } else { + smartportMasterReceive(currentTimeUs); + } +} + +cellsData_t *smartportMasterGetCellsData(void) +{ + if (micros() - sensorsData.cellsTimestamp > SMARTPORT_SENSOR_DATA_TIMEOUT) { + return NULL; + } + + return &sensorsData.cells; +} + +vs600Data_t *smartportMasterGetVS600Data(void) +{ + if (micros() - sensorsData.vs600Timestamp > SMARTPORT_SENSOR_DATA_TIMEOUT) { + return NULL; + } + + return &sensorsData.vs600; +} + +bool smartportMasterPhyIDIsActive(uint8_t phyID) +{ + return phyIDIsActive(phyID); +} + +int8_t smartportMasterStripPhyIDCheckBits(uint8_t phyID) +{ + uint8_t smartportPhyID = phyID & 0x1F; + uint8_t phyIDCheck = smartportPhyID; + smartportMasterPhyIDFillCheckBits(&phyIDCheck); + return phyID == phyIDCheck ? smartportPhyID : -1; +} + +#endif diff --git a/src/main/io/smartport_master.h b/src/main/io/smartport_master.h new file mode 100644 index 00000000000..c499b490e5f --- /dev/null +++ b/src/main/io/smartport_master.h @@ -0,0 +1,87 @@ +/* + * This file is part of iNav + * + * iNav free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * iNav distributed in the hope that it + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +#include +#include + +#include + +#include "config/parameter_group.h" + +#include + +#if defined(USE_SMARTPORT_MASTER) + +typedef struct { + bool halfDuplex; + bool inverted; +} smartportMasterConfig_t; + +PG_DECLARE(smartportMasterConfig_t, smartportMasterConfig); + +typedef struct { + int8_t count; + int16_t voltage[6]; +} cellsData_t; + +typedef enum { + VS600_BAND_A, + VS600_BAND_B, + VS600_BAND_C, + VS600_BAND_D, + VS600_BAND_E, + VS600_BAND_F, +} vs600Band_e; + +typedef enum { + VS600_POWER_PIT, + VS600_POWER_25MW, + VS600_POWER_200MW, + VS600_POWER_600MW, +} vs600Power_e; + +typedef struct { + vs600Band_e band; + uint8_t channel; + vs600Power_e power; +} vs600Data_t; + + +bool smartportMasterInit(void); +void smartportMasterHandle(timeUs_t currentTimeUs); + +bool smartportMasterPhyIDIsActive(uint8_t phyID); +int8_t smartportMasterStripPhyIDCheckBits(uint8_t phyID); + +// Returns latest received SmartPort payload for phyID +bool smartportMasterGetSensorPayload(uint8_t phyID, smartPortPayload_t *payload); + +// Forwarding +bool smartportMasterForward(uint8_t phyID, smartPortPayload_t *payload); +bool smartportMasterHasForwardResponse(uint8_t phyID); +bool smartportMasterNextForwardResponse(uint8_t phyID, smartPortPayload_t *payload); + +// Returns latest Cells data or NULL if the data is too old +cellsData_t *smartportMasterGetCellsData(void); +vs600Data_t *smartportMasterGetVS600Data(void); + +#endif /* USE_SMARTPORT_MASTER */ diff --git a/src/main/scheduler/scheduler.h b/src/main/scheduler/scheduler.h index 99ebc681934..3a8666f2d33 100755 --- a/src/main/scheduler/scheduler.h +++ b/src/main/scheduler/scheduler.h @@ -116,6 +116,9 @@ typedef enum { #ifdef USE_RPM_FILTER TASK_RPM_FILTER, #endif +#if defined(USE_SMARTPORT_MASTER) + TASK_SMARTPORT_MASTER, +#endif #ifdef USE_IRLOCK TASK_IRLOCK, #endif From 6f76bd5ad995661a28c64980e4af4619b794a5e8 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Mon, 20 Jul 2020 22:46:15 +0200 Subject: [PATCH 059/248] Add bootloader and firmware update API (#5728) * Add F765XG MCU support * Add bootloader and update system * Fix linker files --- Makefile | 114 +++- make/gdb.mk | 3 + make/mcu/STM32F3.mk | 8 +- make/mcu/STM32F4.mk | 27 +- make/mcu/STM32F7.mk | 23 +- make/source.mk | 52 +- make/targets.mk | 33 +- src/bl/bl_main.c | 489 ++++++++++++++++++ src/main/drivers/flash.c | 6 +- src/main/drivers/flash.h | 4 +- src/main/drivers/persistent.h | 6 +- src/main/drivers/system.c | 9 +- src/main/drivers/system.h | 1 + src/main/drivers/system_stm32f4xx.c | 3 +- src/main/fc/cli.c | 6 +- src/main/fc/fc_init.c | 3 + src/main/fc/fc_msp.c | 32 +- src/main/fc/firmware_update.c | 318 ++++++++++++ src/main/fc/firmware_update.h | 29 ++ src/main/fc/firmware_update_common.c | 87 ++++ src/main/fc/firmware_update_common.h | 55 ++ src/main/io/asyncfatfs/asyncfatfs.c | 108 ++++ src/main/io/asyncfatfs/asyncfatfs.h | 5 + src/main/msp/msp_protocol_v2_inav.h | 6 + src/main/target/ANYFCF7/target.mk | 2 +- src/main/target/KAKUTEF7/target.mk | 2 +- src/main/target/MATEKF765/target.mk | 2 +- src/main/target/OMNIBUSF7/target.mk | 2 +- ..._f303_128k.ld => stm32_flash_F303_128k.ld} | 0 ..._f303_256k.ld => stm32_flash_F303_256k.ld} | 0 ...tm32_flash_f405.ld => stm32_flash_F405.ld} | 0 src/main/target/link/stm32_flash_F405_bl.ld | 43 ++ .../target/link/stm32_flash_F405_for_bl.ld | 42 ++ ..._f405_opbl.ld => stm32_flash_F405_opbl.ld} | 0 ...tm32_flash_f411.ld => stm32_flash_F411.ld} | 0 ..._f411_opbl.ld => stm32_flash_F411_opbl.ld} | 0 ...tm32_flash_f427.ld => stm32_flash_F427.ld} | 0 ...tm32_flash_f446.ld => stm32_flash_F446.ld} | 0 src/main/target/link/stm32_flash_F7.ld | 184 +++++++ ...tm32_flash_f746.ld => stm32_flash_F746.ld} | 22 +- ...32_flash_f765.ld => stm32_flash_F765xI.ld} | 2 +- src/main/target/link/stm32_flash_F765xI_bl.ld | 56 ++ .../target/link/stm32_flash_F765xI_for_bl.ld | 57 ++ ...sh_f7_split.ld => stm32_flash_F7_split.ld} | 0 ...tm32_flash_f722.ld => stm32_flash_F7x2.ld} | 2 +- src/main/target/link/stm32_flash_F7x2_bl.ld | 50 ++ .../target/link/stm32_flash_F7x2_for_bl.ld | 50 ++ ...32_flash_f745.ld => stm32_flash_F7x5xG.ld} | 2 +- src/main/target/link/stm32_flash_F7x5xG_bl.ld | 50 ++ .../target/link/stm32_flash_F7x5xG_for_bl.ld | 50 ++ src/main/target/system.h | 21 + src/main/target/system_stm32f4xx.c | 3 +- src/main/target/system_stm32f7xx.c | 3 +- src/utils/combine_tool | 29 ++ src/utils/intelhex.rb | 100 ++++ 55 files changed, 2103 insertions(+), 98 deletions(-) create mode 100644 src/bl/bl_main.c create mode 100644 src/main/fc/firmware_update.c create mode 100644 src/main/fc/firmware_update.h create mode 100644 src/main/fc/firmware_update_common.c create mode 100644 src/main/fc/firmware_update_common.h rename src/main/target/link/{stm32_flash_f303_128k.ld => stm32_flash_F303_128k.ld} (100%) rename src/main/target/link/{stm32_flash_f303_256k.ld => stm32_flash_F303_256k.ld} (100%) rename src/main/target/link/{stm32_flash_f405.ld => stm32_flash_F405.ld} (100%) create mode 100644 src/main/target/link/stm32_flash_F405_bl.ld create mode 100644 src/main/target/link/stm32_flash_F405_for_bl.ld rename src/main/target/link/{stm32_flash_f405_opbl.ld => stm32_flash_F405_opbl.ld} (100%) rename src/main/target/link/{stm32_flash_f411.ld => stm32_flash_F411.ld} (100%) rename src/main/target/link/{stm32_flash_f411_opbl.ld => stm32_flash_F411_opbl.ld} (100%) rename src/main/target/link/{stm32_flash_f427.ld => stm32_flash_F427.ld} (100%) rename src/main/target/link/{stm32_flash_f446.ld => stm32_flash_F446.ld} (100%) create mode 100644 src/main/target/link/stm32_flash_F7.ld rename src/main/target/link/{stm32_flash_f746.ld => stm32_flash_F746.ld} (55%) rename src/main/target/link/{stm32_flash_f765.ld => stm32_flash_F765xI.ld} (97%) create mode 100644 src/main/target/link/stm32_flash_F765xI_bl.ld create mode 100644 src/main/target/link/stm32_flash_F765xI_for_bl.ld rename src/main/target/link/{stm32_flash_f7_split.ld => stm32_flash_F7_split.ld} (100%) rename src/main/target/link/{stm32_flash_f722.ld => stm32_flash_F7x2.ld} (97%) create mode 100644 src/main/target/link/stm32_flash_F7x2_bl.ld create mode 100644 src/main/target/link/stm32_flash_F7x2_for_bl.ld rename src/main/target/link/{stm32_flash_f745.ld => stm32_flash_F7x5xG.ld} (97%) create mode 100644 src/main/target/link/stm32_flash_F7x5xG_bl.ld create mode 100644 src/main/target/link/stm32_flash_F7x5xG_for_bl.ld create mode 100644 src/main/target/system.h create mode 100755 src/utils/combine_tool create mode 100644 src/utils/intelhex.rb diff --git a/Makefile b/Makefile index aa20153ccaf..7ea9a13b6a0 100644 --- a/Makefile +++ b/Makefile @@ -66,7 +66,9 @@ endif # Working directories SRC_DIR := $(ROOT)/src/main +BL_SRC_DIR := $(ROOT)/src/bl OBJECT_DIR := $(ROOT)/obj/main +BL_OBJECT_DIR := $(ROOT)/obj/bl BIN_DIR := $(ROOT)/obj CMSIS_DIR := $(ROOT)/lib/main/CMSIS INCLUDE_DIRS := $(SRC_DIR) \ @@ -93,8 +95,9 @@ FATFS_DIR = $(ROOT)/lib/main/FatFS FATFS_SRC = $(notdir $(wildcard $(FATFS_DIR)/*.c)) VPATH := $(SRC_DIR):$(SRC_DIR)/startup -VPATH := $(VPATH):$(ROOT)/make/mcu -VPATH := $(VPATH):$(ROOT)/make +VPATH := $(VPATH):$(ROOT)/make/mcu +VPATH := $(VPATH):$(ROOT)/make +VPATH := $(VPATH):$(BL_SRC_DIR) CSOURCES := $(shell find $(SRC_DIR) -name '*.c') @@ -102,6 +105,12 @@ CSOURCES := $(shell find $(SRC_DIR) -name '*.c') include $(ROOT)/make/mcu/STM32.mk include $(ROOT)/make/mcu/$(TARGET_MCU_GROUP).mk +BL_LD_SCRIPT := $(basename $(LD_SCRIPT))_bl.ld + +ifneq ($(FOR_BL),) + LD_SCRIPT := $(basename $(LD_SCRIPT))_for_bl.ld +endif + # Configure default flash sizes for the targets (largest size specified gets hit first) if flash not specified already. ifeq ($(FLASH_SIZE),) ifneq ($(TARGET_FLASH),) @@ -159,6 +168,7 @@ include $(ROOT)/make/tools.mk CROSS_CC = $(ARM_SDK_PREFIX)gcc OBJCOPY = $(ARM_SDK_PREFIX)objcopy SIZE = $(ARM_SDK_PREFIX)size +COMBINE_TOOL := src/utils/combine_tool # # Tool options. @@ -209,6 +219,12 @@ CFLAGS += $(ARCH_FLAGS) \ -save-temps=obj \ -MMD -MP +BL_CFLAGS = -DMSP_FIRMWARE_UPDATE -DBOOTLOADER + +ifneq ($(FOR_BL),) + CFLAGS += -DMSP_FIRMWARE_UPDATE +endif + ASFLAGS = $(ARCH_FLAGS) \ -x assembler-with-cpp \ $(addprefix -I,$(INCLUDE_DIRS)) \ @@ -232,6 +248,23 @@ LDFLAGS = -lm \ -Wl,--print-memory-usage \ -T$(LD_SCRIPT) +BL_LDFLAGS = -lm \ + -nostartfiles \ + --specs=nano.specs \ + -lc \ + $(SYSLIB) \ + $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(DEBUG_FLAGS) \ + $(SEMIHOSTING_LDFLAGS) \ + -static \ + -Wl,-gc-sections,-Map,$(TARGET_BL_MAP) \ + -Wl,-L$(LINKER_DIR) \ + -Wl,--cref \ + -Wl,--no-wchar-size-warning \ + -Wl,--print-memory-usage \ + -T$(BL_LD_SCRIPT) + ############################################################################### # No user-serviceable parts below ############################################################################### @@ -246,30 +279,41 @@ CPPCHECK = cppcheck $(CSOURCES) --enable=all --platform=unix64 \ # TARGET_BIN := $(BIN_DIR)/$(FORKNAME)_$(FC_VER) TARGET_BIN := $(TARGET_BIN)_$(TARGET) +TARGET_BL_BIN := $(TARGET_BIN)_bl ifneq ($(BUILD_SUFFIX),) TARGET_BIN := $(TARGET_BIN)_$(BUILD_SUFFIX) + TARGET_BL_BIN := $(TARGET_BL_BIN)_$(BUILD_SUFFIX) endif TARGET_BIN := $(TARGET_BIN).bin +TARGET_BL_BIN := $(TARGET_BL_BIN).bin TARGET_HEX = $(TARGET_BIN:.bin=.hex) +TARGET_BL_HEX = $(TARGET_BL_BIN:.bin=.hex) +TARGET_COMBINED_HEX = $(basename $(TARGET_HEX))_combined.hex TARGET_OBJ_DIR = $(OBJECT_DIR)/$(TARGET) +TARGET_BL_OBJ_DIR = $(BL_OBJECT_DIR)/$(TARGET) TARGET_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).elf +TARGET_BL_ELF = $(BL_OBJECT_DIR)/$(FORKNAME)_$(TARGET).elf TARGET_OBJS = $(addsuffix .o,$(addprefix $(TARGET_OBJ_DIR)/,$(basename $(TARGET_SRC)))) +TARGET_BL_OBJS = $(addsuffix .o,$(addprefix $(TARGET_BL_OBJ_DIR)/,$(basename $(TARGET_BL_SRC)))) TARGET_DEPS = $(addsuffix .d,$(addprefix $(TARGET_OBJ_DIR)/,$(basename $(TARGET_SRC)))) +TARGET_BL_DEPS = $(addsuffix .d,$(addprefix $(TARGET_BL_OBJ_DIR)/,$(basename $(TARGET_BL_SRC)))) TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map +TARGET_BL_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET)_bl.map CLEAN_ARTIFACTS := $(TARGET_BIN) CLEAN_ARTIFACTS += $(TARGET_HEX) CLEAN_ARTIFACTS += $(TARGET_ELF) CLEAN_ARTIFACTS += $(TARGET_OBJS) $(TARGET_MAP) +CLEAN_ARTIFACTS += $(TARGET_BL_BIN) $(TARGET_BL_HEX) $(TARGET_BL_ELF) $(TARGET_BL_OBJS) $(TARGET_BL_MAP) include $(ROOT)/make/stamp.mk include $(ROOT)/make/settings.mk include $(ROOT)/make/svd.mk # Make sure build date and revision is updated on every incremental build -$(TARGET_OBJ_DIR)/build/version.o : $(TARGET_SRC) +$(TARGET_OBJ_DIR)/build/version.o $(TARGET_BL_OBJ_DIR)/build/version.o: $(TARGET_SRC) # CFLAGS used for ASM generation. These can't include the LTO related options # since they prevent proper ASM generation. Since $(LTO_FLAGS) includes the @@ -291,6 +335,17 @@ $(TARGET_ELF): $(TARGET_OBJS) $(V1) $(CROSS_CC) -o $@ $(filter %.o, $^) $(LDFLAGS) $(V0) $(SIZE) $(TARGET_ELF) +$(TARGET_BL_HEX): $(TARGET_BL_ELF) + $(V0) $(OBJCOPY) -O ihex --set-start $(FLASH_ORIGIN) $< $@ + +$(TARGET_BL_BIN): $(TARGET_BL_ELF) + $(V0) $(OBJCOPY) -O binary $< $@ + +$(TARGET_BL_ELF): $(TARGET_BL_OBJS) + $(V1) echo Linking $(TARGET) bl + $(V1) $(CROSS_CC) -o $@ $(filter %.o, $^) $(BL_LDFLAGS) + $(V0) $(SIZE) $(TARGET_BL_ELF) + OPTIMIZE_FLAG_SPEED := "-Os" OPTIMIZE_FLAG_SIZE := "-Os" OPTIMIZE_FLAG_NORMAL := "-Os" @@ -306,6 +361,11 @@ define compile_file $(CROSS_CC) -c -o $@ $(CFLAGS) $(2) $< endef +define compile_bl_file + echo "%% $(1) $(2) $<" "$(STDOUT)" && \ + $(CROSS_CC) -c -o $@ $(CFLAGS) $(BL_CFLAGS) $(2) $< +endef + # Compile $(TARGET_OBJ_DIR)/%.o: %.c $(V1) mkdir -p $(dir $@) @@ -323,13 +383,29 @@ ifeq ($(GENERATE_ASM), 1) $(V1) $(CROSS_CC) -S -fverbose-asm -Wa,-aslh -o $(patsubst %.o,%.txt.S,$@) -g $(ASM_CFLAGS) $< endif +$(TARGET_BL_OBJ_DIR)/%.o: %.c + $(V1) mkdir -p $(dir $@) + + $(V1) $(if $(findstring $<,$(SIZE_OPTIMISED_SRC)), \ + $(call compile_bl_file,(size),$(OPTIMIZE_FLAG_SIZE)) \ + , \ + $(if $(findstring $<,$(SPEED_OPTIMISED_SRC)), \ + $(call compile_bl_file,(speed),$(OPTIMIZE_FLAG_SPEED)) \ + , \ + $(call compile_bl_file,(normal),$(OPTIMIZE_FLAG_NORMAL)) \ + ) \ + ) +ifeq ($(GENERATE_ASM), 1) + $(V1) $(CROSS_CC) -S -fverbose-asm -Wa,-aslh -o $(patsubst %.o,%.txt.S,$@) -g $(ASM_CFLAGS) $(BL_CFLAGS) $< +endif + # Assemble -$(TARGET_OBJ_DIR)/%.o: %.s +$(TARGET_OBJ_DIR)/%.o $(TARGET_BL_OBJ_DIR)/%.o: %.s $(V1) mkdir -p $(dir $@) $(V1) echo %% $(notdir $<) "$(STDOUT)" $(V1) $(CROSS_CC) -c -o $@ $(ASFLAGS) $< -$(TARGET_OBJ_DIR)/%.o: %.S +$(TARGET_OBJ_DIR)/%.o $(TARGET_BL_OBJ_DIR)/%.o: %.S $(V1) mkdir -p $(dir $@) $(V1) echo %% $(notdir $<) "$(STDOUT)" $(V1) $(CROSS_CC) -c -o $@ $(ASFLAGS) $< @@ -355,6 +431,31 @@ $(VALID_TARGETS): CFLAGS=$(SAVED_CFLAGS) $(MAKE) -j 8 TARGET=$@ && \ echo "Building $@ succeeded." +$(VALID_BL_TARGETS): + $(V0) echo "" && \ + echo "Building $@" && \ + CFLAGS=$(SAVED_CFLAGS) $(MAKE) -j 8 TARGET=$(@:%_bl=%) bl_binary bl_hex && \ + echo "Building $(@:%_bl=%) bl succeeded." + +$(VALID_TARGETS_FOR_BL): + $(V0) echo "" && \ + echo "Building $@" && \ + CFLAGS=$(SAVED_CFLAGS) $(MAKE) -j 8 TARGET=$(@:%_for_bl=%) FOR_BL=1 binary hex && \ + echo "Building $(@:%_for_bl=%) for bl succeeded." + +$(VALID_TARGETS_WITH_BL): + $(V0) echo "" && \ + echo "Building $@ with bl" && \ + CFLAGS=$(SAVED_CFLAGS) $(MAKE) TARGET=$(@:%_with_bl=%) combined_hex && \ + echo "Building $(@:%_with_bl=%) with bl succeeded." + +combined_hex: + $(V1) echo "Building combined BL+MAIN hex" && \ + CFLAGS=$(SAVED_CFLAGS) $(MAKE) -j 8 TARGET=$(TARGET) bl_binary && \ + CFLAGS=$(SAVED_CFLAGS) $(MAKE) -j 8 TARGET=$(TARGET) binary FOR_BL=1 && \ + echo "Combining MAIN+BL in $(TARGET_COMBINED_HEX)" && \ + $(COMBINE_TOOL) $(TARGET_BL_BIN) $(TARGET_BIN) $(TARGET_COMBINED_HEX) + ## clean : clean up all temporary / machine-generated files clean: $(V0) echo "Cleaning $(TARGET)" @@ -398,6 +499,9 @@ st-flash: $(TARGET_BIN) elf: $(TARGET_ELF) binary: $(TARGET_BIN) hex: $(TARGET_HEX) +bl_elf: $(TARGET_BL_ELF) +bl_binary: $(TARGET_BL_BIN) +bl_hex: $(TARGET_BL_HEX) unbrick_$(TARGET): $(TARGET_HEX) $(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon diff --git a/make/gdb.mk b/make/gdb.mk index 9e6c059d7f5..aeb29b38daa 100644 --- a/make/gdb.mk +++ b/make/gdb.mk @@ -12,3 +12,6 @@ endif gdb-openocd: $(TARGET_ELF) $(GDB) $< -ex "target remote $(GDB_REMOTE)" $(GDB_OPENOCD_INIT_CMDS) + +gdb-openocd-bl: $(TARGET_BL_ELF) + $(GDB) $< -ex "target remote $(GDB_REMOTE)" $(GDB_OPENOCD_INIT_CMDS) diff --git a/make/mcu/STM32F3.mk b/make/mcu/STM32F3.mk index 232ce7fe042..b7b05eff3b3 100644 --- a/make/mcu/STM32F3.mk +++ b/make/mcu/STM32F3.mk @@ -3,7 +3,7 @@ # ifeq ($(OPBL),yes) -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k_opbl.ld +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F303_$(FLASH_SIZE)k_opbl.ld endif TARGET_FLASH := 256 @@ -47,7 +47,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \ VPATH := $(VPATH):$(FATFS_DIR) endif -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k.ld +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F303_$(FLASH_SIZE)k.ld ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion DEVICE_FLAGS = -DSTM32F303xC -DSTM32F303 @@ -74,7 +74,9 @@ MCU_COMMON_SRC = \ drivers/serial_uart_stm32f30x.c \ drivers/system_stm32f30x.c \ drivers/timer_impl_stdperiph.c \ - drivers/timer_stm32f30x.c + drivers/timer_stm32f30x.c \ + src/main/drivers/bus_spi.c + DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM4 diff --git a/make/mcu/STM32F4.mk b/make/mcu/STM32F4.mk index 3c740a564b4..2216605fee4 100644 --- a/make/mcu/STM32F4.mk +++ b/make/mcu/STM32F4.mk @@ -141,23 +141,23 @@ endif ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion ifeq ($(TARGET),$(filter $(TARGET),$(F411_TARGETS))) -DEVICE_FLAGS = -DSTM32F411xE -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411.ld -STARTUP_SRC = startup_stm32f411xe.s + DEVICE_FLAGS := -DSTM32F411xE + LD_SCRIPT := $(LINKER_DIR)/stm32_flash_F411.ld + STARTUP_SRC := startup_stm32f411xe.s else ifeq ($(TARGET),$(filter $(TARGET),$(F405_TARGETS))) -DEVICE_FLAGS = -DSTM32F40_41xxx -DSTM32F405xx -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405.ld -STARTUP_SRC = startup_stm32f40xx.s + DEVICE_FLAGS := -DSTM32F40_41xxx -DSTM32F405xx + LD_SCRIPT := $(LINKER_DIR)/stm32_flash_F405.ld + STARTUP_SRC := startup_stm32f40xx.s else ifeq ($(TARGET),$(filter $(TARGET),$(F446_TARGETS))) -DEVICE_FLAGS = -DSTM32F446xx -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f446.ld -STARTUP_SRC = startup_stm32f446xx.s + DEVICE_FLAGS := -DSTM32F446xx + LD_SCRIPT := $(LINKER_DIR)/stm32_flash_F446.ld + STARTUP_SRC := startup_stm32f446xx.s else ifeq ($(TARGET),$(filter $(TARGET),$(F427_TARGETS))) -DEVICE_FLAGS = -DSTM32F427_437xx -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f427.ld -STARTUP_SRC = startup_stm32f427xx.s + DEVICE_FLAGS := -DSTM32F427_437xx + LD_SCRIPT := $(LINKER_DIR)/stm32_flash_F427.ld + STARTUP_SRC := startup_stm32f427xx.s else -$(error Unknown MCU for F4 target) + $(error Unknown MCU for F4 target) endif DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) @@ -169,6 +169,7 @@ MCU_COMMON_SRC = \ drivers/adc_stm32f4xx.c \ drivers/adc_stm32f4xx.c \ drivers/bus_i2c_stm32f40x.c \ + drivers/bus_spi.c \ drivers/serial_softserial.c \ drivers/serial_uart_stm32f4xx.c \ drivers/system_stm32f4xx.c \ diff --git a/make/mcu/STM32F7.mk b/make/mcu/STM32F7.mk index 342a8cbf958..28da7c4df92 100644 --- a/make/mcu/STM32F7.mk +++ b/make/mcu/STM32F7.mk @@ -121,25 +121,30 @@ endif ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant -Wdouble-promotion DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER -ifeq ($(TARGET),$(filter $(TARGET),$(F7X5XI_TARGETS))) -DEVICE_FLAGS += -DSTM32F765xx -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f765.ld +ifeq ($(TARGET),$(filter $(TARGET),$(F765XI_TARGETS))) +DEVICE_FLAGS += -DSTM32F765xx -DSTM32F765xI +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F765xI.ld STARTUP_SRC = startup_stm32f765xx.s TARGET_FLASH := 2048 -else ifeq ($(TARGET),$(filter $(TARGET),$(F7X5XG_TARGETS))) -DEVICE_FLAGS += -DSTM32F745xx -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f745.ld +else ifeq ($(TARGET),$(filter $(TARGET),$(F765XG_TARGETS))) +DEVICE_FLAGS += -DSTM32F765xx -DSTM32F765xG +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F7x5xG.ld +STARTUP_SRC = startup_stm32f765xx.s +TARGET_FLASH := 1024 +else ifeq ($(TARGET),$(filter $(TARGET),$(F745XG_TARGETS))) +DEVICE_FLAGS += -DSTM32F745xx -DSTM32F745xG +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F7x5xG.ld STARTUP_SRC = startup_stm32f745xx.s -TARGET_FLASH := 2048 +TARGET_FLASH := 1024 else ifeq ($(TARGET),$(filter $(TARGET),$(F7X6XG_TARGETS))) DEVICE_FLAGS += -DSTM32F746xx -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f746.ld +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F746.ld STARTUP_SRC = startup_stm32f746xx.s TARGET_FLASH := 2048 else ifeq ($(TARGET),$(filter $(TARGET),$(F7X2RE_TARGETS))) DEVICE_FLAGS += -DSTM32F722xx ifndef LD_SCRIPT -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f722.ld +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F7x2.ld endif STARTUP_SRC = startup_stm32f722xx.s TARGET_FLASH := 512 diff --git a/make/source.mk b/make/source.mk index 57909d6ec2d..9c17d064a5d 100644 --- a/make/source.mk +++ b/make/source.mk @@ -1,7 +1,25 @@ COMMON_SRC = \ + common/log.c \ + common/printf.c \ + common/string_light.c \ + common/typeconversion.c \ + drivers/bus.c \ + drivers/bus_busdev_i2c.c \ + drivers/bus_busdev_spi.c \ + drivers/bus_i2c_soft.c \ + drivers/io.c \ + drivers/persistent.c \ + drivers/light_led.c \ + drivers/rcc.c \ + drivers/serial.c \ + drivers/system.c \ + drivers/time.c \ + fc/firmware_update_common.c \ + target/common_hardware.c + +MAIN_SRC = \ $(TARGET_DIR_SRC) \ main.c \ - target/common_hardware.c \ build/assert.c \ build/build_config.c \ build/debug.c \ @@ -13,15 +31,11 @@ COMMON_SRC = \ common/encoding.c \ common/filter.c \ common/gps_conversion.c \ - common/log.c \ common/maths.c \ common/memory.c \ common/olc.c \ - common/printf.c \ common/streambuf.c \ - common/string_light.c \ common/time.c \ - common/typeconversion.c \ common/uvarint.c \ programming/logic_condition.c \ programming/global_functions.c \ @@ -34,21 +48,12 @@ COMMON_SRC = \ config/general_settings.c \ drivers/adc.c \ drivers/buf_writer.c \ - drivers/bus.c \ - drivers/bus_busdev_i2c.c \ - drivers/bus_busdev_spi.c \ - drivers/bus_i2c_soft.c \ - drivers/bus_spi.c \ drivers/display.c \ drivers/display_canvas.c \ drivers/display_font_metadata.c \ drivers/exti.c \ - drivers/io.c \ drivers/io_pca9685.c \ - drivers/irlock.c \ - drivers/light_led.c \ drivers/osd.c \ - drivers/persistent.c \ drivers/resource.c \ drivers/rx_nrf24l01.c \ drivers/rx_spi.c \ @@ -59,14 +64,10 @@ COMMON_SRC = \ drivers/pwm_mapping.c \ drivers/pwm_output.c \ drivers/pinio.c \ - drivers/rcc.c \ drivers/rx_pwm.c \ - drivers/serial.c \ drivers/serial_uart.c \ drivers/sound_beeper.c \ drivers/stack_check.c \ - drivers/system.c \ - drivers/time.c \ drivers/timer.c \ drivers/usb_msc.c \ drivers/lights_io.c \ @@ -85,6 +86,7 @@ COMMON_SRC = \ fc/fc_hardfaults.c \ fc/fc_msp.c \ fc/fc_msp_box.c \ + fc/firmware_update.c \ fc/rc_smoothing.c \ fc/rc_adjustments.c \ fc/rc_controls.c \ @@ -235,25 +237,31 @@ COMMON_SRC = \ io/vtx_ffpv24g.c \ io/vtx_control.c +BL_SRC = \ + bl_main.c + COMMON_DEVICE_SRC = \ $(CMSIS_SRC) \ $(DEVICE_STDPERIPH_SRC) -TARGET_SRC := $(STARTUP_SRC) $(COMMON_DEVICE_SRC) $(COMMON_SRC) $(MCU_COMMON_SRC) $(TARGET_SRC) +TARGET_SRC := $(STARTUP_SRC) $(COMMON_DEVICE_SRC) $(MAIN_SRC) $(COMMON_SRC) $(MCU_COMMON_SRC) $(TARGET_SRC) +TARGET_BL_SRC := $(STARTUP_SRC) $(COMMON_DEVICE_SRC) $(BL_SRC) $(COMMON_SRC) $(MCU_COMMON_SRC) #excludes TARGET_SRC := $(filter-out $(MCU_EXCLUDES), $(TARGET_SRC)) ifneq ($(filter ONBOARDFLASH,$(FEATURES)),) -TARGET_SRC += \ +FLASH_SRC += \ drivers/flash.c \ drivers/flash_m25p16.c \ io/flashfs.c \ $(MSC_SRC) +TARGET_SRC += $(FLASH_SRC) +TARGET_BL_SRC += $(FLASH_SRC) endif ifneq ($(filter SDCARD,$(FEATURES)),) -TARGET_SRC += \ +SDCARD_SRC += \ drivers/sdcard/sdcard.c \ drivers/sdcard/sdcard_spi.c \ drivers/sdcard/sdcard_sdio.c \ @@ -261,6 +269,8 @@ TARGET_SRC += \ io/asyncfatfs/asyncfatfs.c \ io/asyncfatfs/fat_standard.c \ $(MSC_SRC) +TARGET_SRC += $(SDCARD_SRC) +TARGET_BL_SRC += $(SDCARD_SRC) endif ifneq ($(filter VCP,$(FEATURES)),) diff --git a/make/targets.mk b/make/targets.mk index aa0544bffdf..c111ddb75c0 100644 --- a/make/targets.mk +++ b/make/targets.mk @@ -5,6 +5,10 @@ VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS))) VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS) VALID_TARGETS := $(sort $(VALID_TARGETS)) +VALID_BL_TARGETS := $(addsuffix _bl,$(VALID_TARGETS)) +VALID_TARGETS_FOR_BL := $(addsuffix _for_bl,$(VALID_TARGETS)) +VALID_TARGETS_WITH_BL := $(addsuffix _with_bl,$(VALID_TARGETS)) + CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) ) TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) ) STFLASH_TARGETS = $(addprefix st-flash_,$(VALID_TARGETS) ) @@ -20,7 +24,7 @@ endif -include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) $(F427_TARGETS) $(F446_TARGETS) -F7_TARGETS = $(F7X2RE_TARGETS) $(F7X5XE_TARGETS) $(F7X5XG_TARGETS) $(F7X5XI_TARGETS) $(F7X6XG_TARGETS) +F7_TARGETS = $(F7X2RE_TARGETS) $(F7X5XE_TARGETS) $(F745XG_TARGETS) $(F765XG_TARGETS) $(F765XI_TARGETS) $(F7X6XG_TARGETS) ifeq ($(filter $(TARGET),$(VALID_TARGETS)),) $(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?) @@ -31,34 +35,37 @@ $(error Target '$(TARGET)' has not specified a valid STM group, must be one of F endif ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) -TARGET_MCU := STM32F303 +TARGET_MCU := STM32F303 TARGET_MCU_GROUP := STM32F3 else ifeq ($(TARGET),$(filter $(TARGET), $(F405_TARGETS))) -TARGET_MCU := STM32F405 +TARGET_MCU := STM32F405 TARGET_MCU_GROUP := STM32F4 else ifeq ($(TARGET),$(filter $(TARGET), $(F411_TARGETS))) -TARGET_MCU := STM32F411 +TARGET_MCU := STM32F411 TARGET_MCU_GROUP := STM32F4 else ifeq ($(TARGET),$(filter $(TARGET), $(F427_TARGETS))) -TARGET_MCU := STM32F427 +TARGET_MCU := STM32F427 TARGET_MCU_GROUP := STM32F4 else ifeq ($(TARGET),$(filter $(TARGET), $(F446_TARGETS))) -TARGET_MCU := STM32F446 +TARGET_MCU := STM32F446 TARGET_MCU_GROUP := STM32F4 else ifeq ($(TARGET),$(filter $(TARGET), $(F7X2RE_TARGETS))) -TARGET_MCU := STM32F7X2RE +TARGET_MCU := STM32F7X2RE TARGET_MCU_GROUP := STM32F7 else ifeq ($(TARGET),$(filter $(TARGET), $(F7X5XE_TARGETS))) -TARGET_MCU := STM32F7X5XE +TARGET_MCU := STM32F7X5XE +TARGET_MCU_GROUP := STM32F7 +else ifeq ($(TARGET),$(filter $(TARGET), $(F745XG_TARGETS))) +TARGET_MCU := STM32F745XG TARGET_MCU_GROUP := STM32F7 -else ifeq ($(TARGET),$(filter $(TARGET), $(F7X5XG_TARGETS))) -TARGET_MCU := STM32F7X5XG +else ifeq ($(TARGET),$(filter $(TARGET), $(F765XG_TARGETS))) +TARGET_MCU := STM32F765XG TARGET_MCU_GROUP := STM32F7 -else ifeq ($(TARGET),$(filter $(TARGET), $(F7X5XI_TARGETS))) -TARGET_MCU := STM32F7X5XI +else ifeq ($(TARGET),$(filter $(TARGET), $(F765XI_TARGETS))) +TARGET_MCU := STM32F765XI TARGET_MCU_GROUP := STM32F7 else ifeq ($(TARGET),$(filter $(TARGET), $(F7X6XG_TARGETS))) -TARGET_MCU := STM32F7X6XG +TARGET_MCU := STM32F7X6XG TARGET_MCU_GROUP := STM32F7 else $(error Unknown target MCU specified.) diff --git a/src/bl/bl_main.c b/src/bl/bl_main.c new file mode 100644 index 00000000000..b1a75170afc --- /dev/null +++ b/src/bl/bl_main.c @@ -0,0 +1,489 @@ +/* + * This file is part of iNav. + * + * iNav is free software. You can redistribute this software + * and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * iNav is distributed in the hope that they will be + * useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include +#include +#include + +#include "platform.h" + +/*#include "common/log.h"*/ +#include "common/maths.h" +/*#include "common/printf.h"*/ + +#include "drivers/bus.h" +#include "drivers/flash.h" +#include "drivers/persistent.h" +#include "drivers/io.h" +#include "drivers/light_led.h" +#include "drivers/sdcard/sdcard.h" +#include "drivers/system.h" +#include "drivers/time.h" + +#include "fc/firmware_update_common.h" + +#include "io/asyncfatfs/asyncfatfs.h" + + +#if !(defined(STM32F405xx) || defined(STM32F722xx) || defined(STM32F765XG) || defined(STM32F7X5XI)) +#error Unsupported MCU +#endif + +#if !(defined(USE_FLASHFS) || defined(USE_SDCARD)) +#error No storage backend available +#endif + + +typedef struct { + uint16_t size; + uint8_t count; +} flashSectorDef_t; + +#if defined(STM32F405xx) +#define SECTOR_COUNT 12 +flashSectorDef_t flashSectors[] = { { 16, 4 }, { 64, 1 }, { 128, 7 }, { 0, 0 } }; + +#elif defined(STM32F722xx) +#define SECTOR_COUNT 8 +flashSectorDef_t flashSectors[] = { { 16, 4 }, { 64, 1 }, { 128, 3 }, { 0, 0 } }; + +#elif defined(STM32F765XG) +#define SECTOR_COUNT 8 +flashSectorDef_t flashSectors[] = { { 32, 4 }, { 128, 1 }, { 256, 3 }, { 0, 0 } }; + +#elif defined(STM32F7X5XI) +#define SECTOR_COUNT 8 +flashSectorDef_t flashSectors[] = { { 32, 4 }, { 128, 1 }, { 256, 7 }, { 0, 0 } }; + +#endif + +#if defined(STM32F4) + #define flashLock() FLASH_Lock() + #define flashUnlock() FLASH_Unlock() +#elif defined(STM32F7) + #define flashLock() HAL_FLASH_Lock() + #define flashUnlock() HAL_FLASH_Unlock() +#endif + +static bool dataBackEndInitialized = false; + +#ifdef USE_SDCARD +static afatfsFilePtr_t flashDataFile = NULL; + +static void flashDataFileOpenCallback(afatfsFilePtr_t file) +{ + flashDataFile = file; +} +#endif + +static void init(void) +{ +#ifdef USE_HAL_DRIVER + HAL_Init(); +#endif + + /*printfSupportInit();*/ + + systemInit(); + + __enable_irq(); + + // initialize IO (needed for all IO operations) + IOInitGlobal(); + + ledInit(false); + + LED0_OFF; + LED1_OFF; + + for(int x = 0; x < 10; ++x) { + LED0_TOGGLE; + LED1_TOGGLE; + delay(200); + } + +} + +static bool dataBackendInit(void) +{ + if (dataBackEndInitialized) return true; + + busInit(); + +#if defined(USE_SDCARD) + sdcardInsertionDetectInit(); + sdcard_init(); + afatfs_init(); + + afatfsError_e sdError = afatfs_getLastError(); + while ((afatfs_getFilesystemState() != AFATFS_FILESYSTEM_STATE_READY) && ((sdError = afatfs_getLastError()) == AFATFS_ERROR_NONE)) { + afatfs_poll(); + } + + if (sdError != AFATFS_ERROR_NONE) { + return false; + } + +#elif defined(USE_FLASHFS) && defined(USE_FLASH_M25P16) + if (!flashInit()) { + return false; + } + +#endif + + dataBackEndInitialized = true; + return true; +} + +typedef void resetHandler_t(void); + +typedef struct isrVector_s { + uint32_t stackEnd; + resetHandler_t *resetHandler; +} isrVector_t; + +static void do_jump(uint32_t address) +{ +#ifdef STM32F7 + __DSB(); + __DMB(); + __ISB(); +#endif + + volatile isrVector_t *bootloaderVector = (isrVector_t *)address; + __set_MSP(bootloaderVector->stackEnd); + bootloaderVector->resetHandler(); +} + +void bootloader_jump_to_app(void) +{ + FLASH->ACR &= (~FLASH_ACR_PRFTEN); + +#if defined(STM32F4) + RCC_APB1PeriphResetCmd(~0, DISABLE); + RCC_APB2PeriphResetCmd(~0, DISABLE); +#elif defined(STM32F7) + RCC->APB1ENR = 0; + RCC->APB1LPENR = 0; + RCC->APB2ENR = 0; + RCC->APB2LPENR = 0; +#endif + + __disable_irq(); + + do_jump(FIRMWARE_START_ADDRESS); +} + +// find sector specified address is in (assume than the config section doesn't span more than 1 sector) +// returns -1 if not found +int8_t mcuFlashAddressSectorIndex(uint32_t address) +{ + uint32_t sectorStartAddress = FLASH_START_ADDRESS; + uint8_t sector = 0; + flashSectorDef_t *sectorDef = flashSectors; + + do { + for (unsigned j = 0; j < sectorDef->count; ++j) { + uint32_t sectorEndAddress = sectorStartAddress + sectorDef->size * 1024; + /*if ((CONFIG_START_ADDRESS >= sectorStartAddress) && (CONFIG_START_ADDRESS < sectorEndAddress) && (CONFIG_END_ADDRESS <= sectorEndAddress)) {*/ + if ((address >= sectorStartAddress) && (address < sectorEndAddress)) { + return sector; + } + sectorStartAddress = sectorEndAddress; + sector += 1; + } + sectorDef += 1; + } while (sectorDef->count); + + return -1; +} + +uint32_t mcuFlashSectorID(uint8_t sectorIndex) +{ +#if defined(STM32F4) + if (sectorIndex < 12) { + return sectorIndex * 8; + } else { + return 0x80 + (sectorIndex - 12) * 8; + } +#elif defined(STM32F7) + return sectorIndex; +#endif +} + +bool mcuFlashSectorErase(uint8_t sectorIndex) +{ +#if defined(STM32F4) + return (FLASH_EraseSector(mcuFlashSectorID(sectorIndex), VoltageRange_3) == FLASH_COMPLETE); +#elif defined(STM32F7) + FLASH_EraseInitTypeDef EraseInitStruct = { + .TypeErase = FLASH_TYPEERASE_SECTORS, + .VoltageRange = FLASH_VOLTAGE_RANGE_3, // 2.7-3.6V + .NbSectors = 1 + }; + EraseInitStruct.Sector = mcuFlashSectorID(sectorIndex); + uint32_t SECTORError; + const HAL_StatusTypeDef status = HAL_FLASHEx_Erase(&EraseInitStruct, &SECTORError); + return (status == HAL_OK); +#else +#error Unsupported MCU +#endif +} + +bool mcuFirmwareFlashErase(bool includeConfig) +{ + int8_t firmwareSectorIndex = mcuFlashAddressSectorIndex(FIRMWARE_START_ADDRESS); + int8_t configSectorIndex = mcuFlashAddressSectorIndex(CONFIG_START_ADDRESS); + + if ((firmwareSectorIndex == -1) || (configSectorIndex == -1)) { + return false; + } + + LED0_OFF; + LED1_ON; + for (unsigned i = firmwareSectorIndex; i < SECTOR_COUNT; ++i) { + if (includeConfig || (!includeConfig && (i != (uint8_t)configSectorIndex))) { + if (!mcuFlashSectorErase(i)) { + LED1_OFF; + return false; + } + LED0_TOGGLE; + } + } + + LED1_OFF; + return true; +} + +bool mcuFlashWriteWord(uint32_t address, uint32_t data) +{ +#if defined(STM32F4) + const FLASH_Status status = FLASH_ProgramWord(address, data); + return (status == FLASH_COMPLETE); +#elif defined(STM32F7) + const HAL_StatusTypeDef status = HAL_FLASH_Program(FLASH_TYPEPROGRAM_WORD, address, (uint64_t)data); + return (status == HAL_OK); +#else +#error Unsupported MCU +#endif +} + +typedef enum { + FLASH_OPERATION_UPDATE, + FLASH_OPERATION_ROLLBACK +} flashOperation_e; + +#if defined(USE_SDCARD) +bool afatfs_fseekWorkAround(afatfsFilePtr_t file, uint32_t forward) +{ + uint8_t buffer[256]; + while (forward > 0) { + uint32_t bytesRead = afatfs_freadSync(file, buffer, MIN(forward, (uint16_t)256)); + if (bytesRead < 256) { + return false; + } + forward -= bytesRead; + } + return true; +} +#endif + +bool flash(flashOperation_e flashOperation) +{ + if (!dataBackendInit()) { + return false; + } + + uint32_t buffer; + uint32_t flashDstAddress = FIRMWARE_START_ADDRESS + sizeof(buffer); // Write the first bytes last so that we can check that the firmware has been written fully + +#if defined(USE_SDCARD) + const char * const flashDataFileName = (flashOperation == FLASH_OPERATION_UPDATE ? FIRMWARE_UPDATE_FIRMWARE_FILENAME : FIRMWARE_UPDATE_BACKUP_FILENAME); + if ((afatfs_getFilesystemState() != AFATFS_FILESYSTEM_STATE_READY) + || !afatfs_fopen(flashDataFileName, "r", flashDataFileOpenCallback) + || (afatfs_fileSize(flashDataFile) > AVAILABLE_FIRMWARE_SPACE)) { + return false; + } + +#elif defined(USE_FLASHFS) + flashPartitionType_e srcFlashPartitionType = (flashOperation == FLASH_OPERATION_UPDATE ? FLASH_PARTITION_TYPE_UPDATE_FIRMWARE : FLASH_PARTITION_TYPE_FULL_BACKUP); + flashPartition_t *flashDataPartition = flashPartitionFindByType(srcFlashPartitionType); + const flashGeometry_t *flashGeometry = flashGetGeometry(); + uint32_t flashDataPartitionSize = (flashDataPartition->endSector - flashDataPartition->startSector + 1) * (flashGeometry->sectorSize * flashGeometry->pageSize); + firmwareUpdateMetadata_t updateMetadata; + + if (!flashDataPartition || !firmwareUpdateMetadataRead(&updateMetadata) + || (updateMetadata.firmwareSize > flashDataPartitionSize) + || (updateMetadata.firmwareSize > AVAILABLE_FIRMWARE_SPACE)) { + return false; + } + +#endif + + flashUnlock(); + bool flashSucceeded = false; + + if (!mcuFirmwareFlashErase(flashOperation != FLASH_OPERATION_UPDATE)) goto flashFailed; + + LED0_OFF; + LED1_OFF; + + uint32_t counter = 0; + +#if defined(USE_SDCARD) + + if (afatfs_fseekSync(flashDataFile, sizeof(buffer), AFATFS_SEEK_SET) == AFATFS_OPERATION_FAILURE) { + goto flashFailed; + } + + while (!afatfs_feof(flashDataFile)) { + + if ((flashOperation == FLASH_OPERATION_UPDATE) && (flashDstAddress == CONFIG_START_ADDRESS)) { + // skip config region + const uint32_t configSize = CONFIG_END_ADDRESS - CONFIG_START_ADDRESS; + /*if (afatfs_fseekSync(flashDataFile, configSize, AFATFS_SEEK_CUR) == AFATFS_OPERATION_FAILURE) {*/ + if (!afatfs_fseekWorkAround(flashDataFile, configSize)) { // workaround fseek bug, should be ^^^^^^^^^ + goto flashFailed; + } + flashDstAddress += configSize; + } + + afatfs_freadSync(flashDataFile, (uint8_t *)&buffer, sizeof(buffer)); + + if (!mcuFlashWriteWord(flashDstAddress, buffer)) { + goto flashFailed; + } + + flashDstAddress += sizeof(buffer); + + if (++counter % (10*1024/4) == 0) { + LED0_TOGGLE; + LED1_TOGGLE; + } + + } + + if ((afatfs_fseekSync(flashDataFile, 0, AFATFS_SEEK_SET) == AFATFS_OPERATION_FAILURE) + || (afatfs_freadSync(flashDataFile, (uint8_t *)&buffer, sizeof(buffer)) != sizeof(buffer))) { + goto flashFailed; + } + +#elif defined(USE_FLASHFS) + const uint32_t flashSrcStartAddress = flashDataPartition->startSector * flashGeometry->sectorSize; + uint32_t flashSrcAddress = flashSrcStartAddress + sizeof(buffer); + const uint32_t flashDstEndAddress = (flashOperation == FLASH_OPERATION_UPDATE ? FIRMWARE_START_ADDRESS + updateMetadata.firmwareSize : FLASH_END); + + while (flashDstAddress < flashDstEndAddress) { + + if ((flashOperation == FLASH_OPERATION_UPDATE) && (flashDstAddress == CONFIG_START_ADDRESS)) { + // skip config region + const uint32_t configSize = CONFIG_END_ADDRESS - CONFIG_START_ADDRESS; + flashSrcAddress += configSize; + flashDstAddress += configSize; + + if (flashDstAddress >= flashDstEndAddress) { + goto flashFailed; + } + } + + flashReadBytes(flashSrcAddress, (uint8_t*)&buffer, sizeof(buffer)); + if (!mcuFlashWriteWord(flashDstAddress, buffer)) { + goto flashFailed; + } + + flashSrcAddress += sizeof(buffer); + flashDstAddress += sizeof(buffer); + + if (++counter % (10*1024/4) == 0) { + LED0_TOGGLE; + LED1_TOGGLE; + } + + } + + flashReadBytes(flashSrcStartAddress, (uint8_t*)&buffer, sizeof(buffer)); + +#endif + + if (!mcuFlashWriteWord(FIRMWARE_START_ADDRESS, buffer)) { + goto flashFailed; + } + + flashSucceeded = true; + +flashFailed: + + flashLock(); + + LED0_OFF; + LED1_OFF; + + return flashSucceeded; +} + +#if defined(USE_FLASHFS) +bool dataflashChipEraseUpdatePartition(void) +{ + flashPartition_t *flashDataPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_UPDATE_FIRMWARE); + if (!flashDataPartition) return false; + + const flashGeometry_t *flashGeometry = flashGetGeometry(); + + LED0_OFF; + + for (unsigned i = flashDataPartition->startSector; i <= flashDataPartition->endSector; i++) { + uint32_t flashAddress = flashGeometry->sectorSize * i; + flashEraseSector(flashAddress); + flashWaitForReady(1000); + LED0_TOGGLE; + } + + LED0_OFF; + + return true; +} +#endif + +int main(void) +{ + init(); + + uint32_t bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON); + if ((bootloaderRequest == RESET_BOOTLOADER_FIRMWARE_UPDATE) || (bootloaderRequest == RESET_BOOTLOADER_FIRMWARE_ROLLBACK)) { + flashOperation_e flashOperation = (bootloaderRequest == RESET_BOOTLOADER_FIRMWARE_UPDATE ? FLASH_OPERATION_UPDATE : FLASH_OPERATION_ROLLBACK); + const bool success = flash(flashOperation); + persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, success ? RESET_BOOTLOADER_FIRMWARE_UPDATE_SUCCESS : RESET_BOOTLOADER_FIRMWARE_UPDATE_FAILED); + } else if (*(uint32_t*)FIRMWARE_START_ADDRESS == 0xFFFFFFFF) { + if (!flash(FLASH_OPERATION_ROLLBACK)) { + LED0_OFF; + LED1_OFF; + + while (true) { + LED0_TOGGLE; + LED1_TOGGLE; + delay(2000); + } + } + } + + bootloader_jump_to_app(); + + return 0; +} diff --git a/src/main/drivers/flash.c b/src/main/drivers/flash.c index 67669ade065..0f2f9aca74e 100644 --- a/src/main/drivers/flash.c +++ b/src/main/drivers/flash.c @@ -30,6 +30,9 @@ #include "flash.h" #include "flash_m25p16.h" + +#include "common/time.h" + #include "drivers/bus_spi.h" #include "drivers/io.h" #include "drivers/time.h" @@ -37,6 +40,7 @@ static flashPartitionTable_t flashPartitionTable; static int flashPartitions = 0; + #ifdef USE_SPI static bool flashSpiInit(void) { @@ -64,7 +68,7 @@ bool flashIsReady(void) return false; } -bool flashWaitForReady(uint32_t timeoutMillis) +bool flashWaitForReady(timeMs_t timeoutMillis) { #ifdef USE_FLASH_M25P16 return m25p16_waitForReady(timeoutMillis); diff --git a/src/main/drivers/flash.h b/src/main/drivers/flash.h index 2a608fcb4dc..9548a8e1ed5 100644 --- a/src/main/drivers/flash.h +++ b/src/main/drivers/flash.h @@ -22,7 +22,7 @@ #include -//#include "drivers/io.h" +#include "common/time.h" //#ifdef USE_FLASHFS @@ -39,7 +39,7 @@ typedef struct flashGeometry_s { bool flashInit(void); bool flashIsReady(void); -bool flashWaitForReady(uint32_t timeoutMillis); +bool flashWaitForReady(timeMs_t timeoutMillis); void flashEraseSector(uint32_t address); void flashEraseCompletely(void); #if 0 diff --git a/src/main/drivers/persistent.h b/src/main/drivers/persistent.h index ff268027880..34faa14536d 100644 --- a/src/main/drivers/persistent.h +++ b/src/main/drivers/persistent.h @@ -35,8 +35,12 @@ typedef enum { // Values for PERSISTENT_OBJECT_RESET_REASON #define RESET_NONE 0 -#define RESET_BOOTLOADER_REQUEST_ROM 1 +#define RESET_BOOTLOADER_REQUEST_ROM 1 // DFU request #define RESET_MSC_REQUEST 2 // MSC invocation was requested +#define RESET_BOOTLOADER_FIRMWARE_UPDATE 3 // Bootloader request to flash stored firmware update +#define RESET_BOOTLOADER_FIRMWARE_ROLLBACK 4 // Bootloader request to rollback to stored firmware and config backup +#define RESET_BOOTLOADER_FIRMWARE_UPDATE_SUCCESS 5 +#define RESET_BOOTLOADER_FIRMWARE_UPDATE_FAILED 6 void persistentObjectInit(void); uint32_t persistentObjectRead(persistentObjectId_e id); diff --git a/src/main/drivers/system.c b/src/main/drivers/system.c index 55691bb291e..1ac0824c747 100644 --- a/src/main/drivers/system.c +++ b/src/main/drivers/system.c @@ -85,12 +85,17 @@ void systemReset(void) NVIC_SystemReset(); } -void systemResetToBootloader(void) +void systemResetRequest(uint32_t requestId) { - persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_BOOTLOADER_REQUEST_ROM); + persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, requestId); systemReset(); } +void systemResetToBootloader(void) +{ + systemResetRequest(RESET_BOOTLOADER_REQUEST_ROM); +} + typedef void resetHandler_t(void); typedef struct isrVector_s { diff --git a/src/main/drivers/system.h b/src/main/drivers/system.h index 87cc1406901..878d9d94a8b 100644 --- a/src/main/drivers/system.h +++ b/src/main/drivers/system.h @@ -38,6 +38,7 @@ void failureMode(failureMode_e mode); // bootloader/IAP void systemReset(void); +void systemResetRequest(uint32_t requestId); void systemResetToBootloader(void); uint32_t systemBootloaderAddress(void); bool isMPUSoftReset(void); diff --git a/src/main/drivers/system_stm32f4xx.c b/src/main/drivers/system_stm32f4xx.c index aa981834845..dfb97c3e686 100644 --- a/src/main/drivers/system_stm32f4xx.c +++ b/src/main/drivers/system_stm32f4xx.c @@ -28,6 +28,8 @@ #include "drivers/exti.h" +#include "target/system.h" + void SetSysClock(void); @@ -160,7 +162,6 @@ void systemInit(void) cachedRccCsrValue = RCC->CSR; /* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */ - extern void *isr_vector_table_base; NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0); RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, DISABLE); diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index a63a0946ff4..f9233eb7120 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -3462,11 +3462,7 @@ static void cliMsc(char *cmdline) delay(1000); waitForSerialPortToFinishTransmitting(cliPort); stopPwmAllMotors(); - - persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_MSC_REQUEST); - - __disable_irq(); - NVIC_SystemReset(); + systemResetRequest(RESET_MSC_REQUEST); } else { cliPrint("\r\nStorage not present or failed to initialize!"); bufWriterFlush(cliWriter); diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index de5b2e7c9ac..cbc5d7cb5ea 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -90,6 +90,7 @@ #include "fc/fc_tasks.h" #include "fc/rc_controls.h" #include "fc/runtime_config.h" +#include "fc/firmware_update.h" #include "flight/failsafe.h" #include "flight/imu.h" @@ -201,6 +202,8 @@ void init(void) // Initialize system and CPU clocks to their initial values systemInit(); + __enable_irq(); + // initialize IO (needed for all IO operations) IOInitGlobal(); diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index f20e576d5e1..dd7528f0fb3 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -60,6 +60,7 @@ #include "fc/controlrate_profile.h" #include "fc/fc_msp.h" #include "fc/fc_msp_box.h" +#include "fc/firmware_update.h" #include "fc/rc_adjustments.h" #include "fc/rc_controls.h" #include "fc/rc_modes.h" @@ -2835,9 +2836,10 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) break; case MSP2_INAV_SELECT_BATTERY_PROFILE: - if (!ARMING_FLAG(ARMED)) { - if (sbufReadU8Safe(&tmp_u8, src)) + if (!ARMING_FLAG(ARMED) && sbufReadU8Safe(&tmp_u8, src)) { setConfigBatteryProfileAndWriteEEPROM(tmp_u8); + } else { + return MSP_RESULT_ERROR; } break; @@ -2861,6 +2863,32 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) break; #endif +#ifdef MSP_FIRMWARE_UPDATE + case MSP2_INAV_FWUPDT_PREPARE: + if (!firmwareUpdatePrepare(sbufReadU32(src))) { + return MSP_RESULT_ERROR; + } + break; + case MSP2_INAV_FWUPDT_STORE: + if (!firmwareUpdateStore(sbufPtr(src), sbufBytesRemaining(src))) { + return MSP_RESULT_ERROR; + } + break; + case MSP2_INAV_FWUPDT_EXEC: + firmwareUpdateExec(sbufReadU8(src)); + return MSP_RESULT_ERROR; // will only be reached if the update is not ready + break; + case MSP2_INAV_FWUPDT_ROLLBACK_PREPARE: + if (!firmwareUpdateRollbackPrepare()) { + return MSP_RESULT_ERROR; + } + break; + case MSP2_INAV_FWUPDT_ROLLBACK_EXEC: + firmwareUpdateRollbackExec(); + return MSP_RESULT_ERROR; // will only be reached if the rollback is not ready + break; +#endif + default: return MSP_RESULT_ERROR; } diff --git a/src/main/fc/firmware_update.c b/src/main/fc/firmware_update.c new file mode 100644 index 00000000000..be8a22171bd --- /dev/null +++ b/src/main/fc/firmware_update.c @@ -0,0 +1,318 @@ +/* + * This file is part of iNav. + * + * iNav is free software. You can redistribute this software + * and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * iNav is distributed in the hope that they will be + * useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include +#include +#include + +#include "platform.h" + +#include "common/crc.h" + +#include "drivers/flash.h" +#include "drivers/light_led.h" +#include "drivers/persistent.h" +#include "drivers/system.h" + +#include "fc/firmware_update.h" +#include "fc/firmware_update_common.h" +#include "fc/runtime_config.h" + +#include "io/asyncfatfs/asyncfatfs.h" + + +#ifdef MSP_FIRMWARE_UPDATE + +#if !(defined(USE_FLASHFS) || defined(USE_SDCARD)) +#error No storage backend available +#endif + +static firmwareUpdateMetadata_t updateMetadata; +static uint8_t updateFirmwareCalcCRC = 0; +static uint32_t receivedSize = 0; +static bool rollbackPrepared = false; + +#if defined(USE_SDCARD) +static uint32_t firmwareSize; +static afatfsFilePtr_t updateFile = NULL; +static afatfsFilePtr_t backupFile = NULL; + +static void updateFileOpenCallback(afatfsFilePtr_t file) +{ + updateFile = file; +} + +static void backupFileOpenCallback(afatfsFilePtr_t file) +{ + backupFile = file; +} + +#elif defined(USE_FLASHFS) +static uint32_t flashStartAddress, flashOverflowAddress; + +#endif + +static bool fullBackup(void) +{ + const uint8_t *const backupSrcEnd = (const uint8_t*)FLASH_END; + uint8_t *backupSrcPtr = (uint8_t*)&__firmware_start; + uint32_t counter = 0; + updateMetadata.backupCRC = 0; + + LED0_OFF; + LED1_OFF; + +#if defined(USE_SDCARD) + if ((afatfs_getFilesystemState() != AFATFS_FILESYSTEM_STATE_READY) || !afatfs_fopen(FIRMWARE_UPDATE_BACKUP_FILENAME, "w+", backupFileOpenCallback)) return false; + + while (backupSrcPtr < backupSrcEnd) { + + const uint16_t writeBlockSize = 512; + uint32_t justWritten = afatfs_fwriteSync(backupFile, backupSrcPtr, writeBlockSize); + updateMetadata.backupCRC = crc8_dvb_s2_update(updateMetadata.backupCRC, backupSrcPtr, justWritten); + + afatfs_poll(); + backupSrcPtr += justWritten; + + if (++counter % (50*1024/512) == 0) { + LED0_TOGGLE; + LED1_TOGGLE; + } + + } + + afatfs_fcloseSync(backupFile); + +#elif defined(USE_FLASHFS) + flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FULL_BACKUP); + if (!flashPartition) return false; + + const flashGeometry_t *flashGeometry = flashGetGeometry(); + const uint32_t flashSectorSize = flashGeometry->sectorSize; + const uint32_t flashPartitionSize = (flashPartition->endSector - flashPartition->startSector + 1) * flashSectorSize; + const uint32_t backupSize = AVAILABLE_FIRMWARE_SPACE; + if (backupSize > flashPartitionSize) return false; + + uint32_t flashAddress = flashPartition->startSector * flashSectorSize; + + const uint32_t flashPageSize = flashGeometry->pageSize; + while (backupSrcPtr < backupSrcEnd) { + + if (flashAddress % flashSectorSize == 0) { + flashEraseSector(flashAddress); + flashWaitForReady(1000); + } + + flashPageProgram(flashAddress, backupSrcPtr, flashPageSize); + updateMetadata.backupCRC = crc8_dvb_s2_update(updateMetadata.backupCRC, backupSrcPtr, flashPageSize); + + flashAddress += flashPageSize; + backupSrcPtr += flashPageSize; + + if (++counter % (10*1024/256) == 0) { + LED0_TOGGLE; + LED1_TOGGLE; + } + + } + +#endif + + return true; +} + +static bool backupIsValid(void) +{ + if (!firmwareUpdateMetadataRead(&updateMetadata) || (updateMetadata.magic != FIRMWARE_UPDATE_METADATA_MAGIC)) { + return false; + } + + LED0_OFF; + LED1_OFF; + + uint32_t counter = 0; + uint8_t calcCRC = 0; + +#if defined(USE_SDCARD) +#define SD_BACKUP_FILE_BLOCK_READ_SIZE 512 + if ((afatfs_getFilesystemState() != AFATFS_FILESYSTEM_STATE_READY) || !afatfs_fopen(FIRMWARE_UPDATE_BACKUP_FILENAME, "w+", backupFileOpenCallback)) return false; + + uint32_t totalRead = 0; + + uint8_t buffer[SD_BACKUP_FILE_BLOCK_READ_SIZE]; + while (!afatfs_feof(backupFile)) { + + uint32_t readBytes = afatfs_freadSync(backupFile, buffer, SD_BACKUP_FILE_BLOCK_READ_SIZE); + calcCRC = crc8_dvb_s2_update(calcCRC, buffer, readBytes); + + totalRead += readBytes; + + if (++counter % (50*1024/SD_BACKUP_FILE_BLOCK_READ_SIZE) == 0) { + LED0_TOGGLE; + LED1_TOGGLE; + } + + } + + afatfs_fcloseSync(backupFile); + +#elif defined(USE_FLASHFS) + flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FULL_BACKUP); + if (!flashPartition) return false; + + const flashGeometry_t *flashGeometry = flashGetGeometry(); + const uint32_t flashSectorSize = flashGeometry->sectorSize; + const uint32_t flashPartitionSize = (flashPartition->endSector - flashPartition->startSector + 1) * flashSectorSize; + const uint32_t backupSize = FLASH_END - (uint32_t)&__firmware_start; + if (backupSize > flashPartitionSize) return false; + + uint32_t flashAddress = flashPartition->startSector * flashSectorSize; + const uint32_t flashEndAddress = flashAddress + backupSize; + + uint8_t buffer[256]; + while (flashAddress < flashEndAddress) { + + flashReadBytes(flashAddress, buffer, sizeof(buffer)); + calcCRC = crc8_dvb_s2_update(calcCRC, buffer, sizeof(buffer)); + + flashAddress += sizeof(buffer); + + if (++counter % (10*1024/256) == 0) { + LED0_TOGGLE; + LED1_TOGGLE; + } + + } + +#endif + + return (calcCRC == updateMetadata.backupCRC); +} + +bool firmwareUpdatePrepare(uint32_t updateSize) +{ + if (ARMING_FLAG(ARMED) || (updateSize > AVAILABLE_FIRMWARE_SPACE)) return false; + +#if defined(USE_SDCARD) + if ((afatfs_getFilesystemState() != AFATFS_FILESYSTEM_STATE_READY) || !afatfs_fopen(FIRMWARE_UPDATE_FIRMWARE_FILENAME, "w+", updateFileOpenCallback)) return false; + + firmwareSize = updateSize; + +#elif defined(USE_FLASHFS) + flashPartition_t *flashUpdatePartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_UPDATE_FIRMWARE); + if (!flashUpdatePartition) return false; + + const flashGeometry_t *flashGeometry = flashGetGeometry(); + + flashStartAddress = flashUpdatePartition->startSector * flashGeometry->sectorSize; + flashOverflowAddress = ((flashUpdatePartition->endSector + 1) * flashGeometry->sectorSize); + receivedSize = 0; + + uint32_t partitionSize = (flashUpdatePartition->endSector - flashUpdatePartition->startSector + 1) * (flashGeometry->sectorSize * flashGeometry->pageSize); + + if (updateSize > partitionSize) { + return false; + } + + updateMetadata.firmwareSize = updateSize; + +#endif + + updateFirmwareCalcCRC = 0; + + return true; +} + +bool firmwareUpdateStore(uint8_t *data, uint16_t length) +{ + if (ARMING_FLAG(ARMED)) { + return false; + } + +#if defined(USE_SDCARD) + + if (!updateFile || !firmwareSize || (receivedSize + length > firmwareSize) + || (afatfs_fwriteSync(updateFile, data, length) != length)) { + return false; + } + +#elif defined(USE_FLASHFS) + if (!updateMetadata.firmwareSize || (receivedSize + length > updateMetadata.firmwareSize)) return false; + + const uint32_t flashAddress = flashStartAddress + receivedSize; + + if ((flashAddress + length > flashOverflowAddress) || (receivedSize + length > updateMetadata.firmwareSize)) { + updateMetadata.firmwareSize = 0; + return false; + } + + const flashGeometry_t *flashGeometry = flashGetGeometry(); + const uint32_t flashSectorSize = flashGeometry->sectorSize; + + if (flashAddress % flashSectorSize == 0) { + flashEraseSector(flashAddress); + flashWaitForReady(1000); + } + + flashPageProgram(flashAddress, data, length); + +#endif + + updateFirmwareCalcCRC = crc8_dvb_s2_update(updateFirmwareCalcCRC, data, length); + receivedSize += length; + + return true; +} + +void firmwareUpdateExec(uint8_t expectCRC) +{ + if (ARMING_FLAG(ARMED)) return; + +#if defined(USE_SDCARD) + if (!afatfs_fclose(updateFile, NULL)) return; + if (firmwareSize && (receivedSize == firmwareSize) && + (updateFirmwareCalcCRC == expectCRC) && fullBackup() && firmwareUpdateMetadataWrite(&updateMetadata)) { + systemResetRequest(RESET_BOOTLOADER_FIRMWARE_UPDATE); + } +#elif defined(USE_FLASHFS) + if (updateMetadata.firmwareSize && (receivedSize == updateMetadata.firmwareSize) && + (updateFirmwareCalcCRC == expectCRC) && fullBackup() && firmwareUpdateMetadataWrite(&updateMetadata)) { + systemResetRequest(RESET_BOOTLOADER_FIRMWARE_UPDATE); + } +#endif + +} + +bool firmwareUpdateRollbackPrepare(void) +{ + if (ARMING_FLAG(ARMED) || !(rollbackPrepared || backupIsValid())) return false; + + rollbackPrepared = true; + return true; +} + +void firmwareUpdateRollbackExec(void) +{ + if (ARMING_FLAG(ARMED) || !firmwareUpdateRollbackPrepare()) return; + + systemResetRequest(RESET_BOOTLOADER_FIRMWARE_ROLLBACK); +} + +#endif diff --git a/src/main/fc/firmware_update.h b/src/main/fc/firmware_update.h new file mode 100644 index 00000000000..4bbb11693e5 --- /dev/null +++ b/src/main/fc/firmware_update.h @@ -0,0 +1,29 @@ +/* + * This file is part of iNav. + * + * iNav is free software. You can redistribute this software + * and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * iNav is distributed in the hope that they will be + * useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +bool firmwareUpdatePrepare(uint32_t firmwareSize); +bool firmwareUpdateStore(uint8_t *data, uint16_t length); +void firmwareUpdateExec(uint8_t expectCRC); +bool firmwareUpdateRollbackPrepare(void); +void firmwareUpdateRollbackExec(void); + +bool writeMeta(void); // XXX temp diff --git a/src/main/fc/firmware_update_common.c b/src/main/fc/firmware_update_common.c new file mode 100644 index 00000000000..2d3370b78f7 --- /dev/null +++ b/src/main/fc/firmware_update_common.c @@ -0,0 +1,87 @@ + +#include +#include + +#include "platform.h" + +#include "common/log.h" + +#include "drivers/flash.h" + +#include "fc/firmware_update_common.h" + +#include "io/asyncfatfs/asyncfatfs.h" + +#ifdef MSP_FIRMWARE_UPDATE + +#if !(defined(USE_FLASHFS) || defined(USE_SDCARD)) +#error No storage backend available +#endif + +#ifdef USE_SDCARD +static afatfsFilePtr_t metaFile = NULL; + +static void metaFileOpenCallback(afatfsFilePtr_t file) +{ + metaFile = file; +} +#endif + +bool firmwareUpdateMetadataRead(firmwareUpdateMetadata_t *updateMetadata) +{ +#if defined(USE_SDCARD) + if ((afatfs_getFilesystemState() != AFATFS_FILESYSTEM_STATE_READY) + || !afatfs_fopen(FIRMWARE_UPDATE_META_FILENAME, "r", metaFileOpenCallback) + || (afatfs_freadSync(metaFile, (uint8_t *)updateMetadata, sizeof(*updateMetadata)) != sizeof(*updateMetadata))) { + return false; + } + +#elif defined(USE_FLASHFS) + flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FIRMWARE_UPDATE_META); + if (!flashPartition) return false; + + const flashGeometry_t *flashGeometry = flashGetGeometry(); + uint32_t flashAddress = flashPartition->startSector * flashGeometry->sectorSize; + + if (!flashReadBytes(flashAddress, (uint8_t *)updateMetadata, sizeof(*updateMetadata))) { + return false; + } + +#endif + + return true; +} + +bool firmwareUpdateMetadataWrite(firmwareUpdateMetadata_t *updateMetadata) +{ + updateMetadata->magic = FIRMWARE_UPDATE_METADATA_MAGIC; + +#if defined(USE_SDCARD) + if ((afatfs_getFilesystemState() != AFATFS_FILESYSTEM_STATE_READY) + || !afatfs_fopen(FIRMWARE_UPDATE_META_FILENAME, "w+", metaFileOpenCallback) + || (afatfs_fwriteSync(metaFile, (uint8_t *)updateMetadata, sizeof(*updateMetadata)) != sizeof(*updateMetadata))) { + return false; + } + + afatfs_fcloseSync(metaFile); + +#elif defined(USE_FLASHFS) + flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FIRMWARE_UPDATE_META); + if (!flashPartition) return false; + + const flashGeometry_t *flashGeometry = flashGetGeometry(); + const uint32_t flashPartitionSize = (flashPartition->endSector - flashPartition->startSector + 1) * flashGeometry->sectorSize; + uint32_t flashAddress = flashPartition->startSector * flashGeometry->sectorSize; + + if (flashPartitionSize < sizeof(*updateMetadata)) return false; + + flashEraseSector(flashAddress); + flashWaitForReady(1000); + flashPageProgram(flashAddress, (uint8_t *)updateMetadata, sizeof(*updateMetadata)); + +#endif + + return true; +} + +#endif diff --git a/src/main/fc/firmware_update_common.h b/src/main/fc/firmware_update_common.h new file mode 100644 index 00000000000..a463551b485 --- /dev/null +++ b/src/main/fc/firmware_update_common.h @@ -0,0 +1,55 @@ +/* + * This file is part of iNav. + * + * iNav is free software. You can redistribute this software + * and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * iNav is distributed in the hope that they will be + * useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include + +#include "platform.h" + +#define FIRMWARE_UPDATE_FIRMWARE_FILENAME "firmware.upt" +#define FIRMWARE_UPDATE_BACKUP_FILENAME "firmware.bak" +#define FIRMWARE_UPDATE_META_FILENAME "update.mta" + +#define FIRMWARE_UPDATE_METADATA_MAGIC 0xAABBCCDD + +#undef FLASH_END + +#define FIRMWARE_START_ADDRESS ((uint32_t)&__firmware_start) +#define FLASH_START_ADDRESS 0x08000000UL +#define FLASH_END (FLASH_START_ADDRESS + FLASH_SIZE * 1024) +#define CONFIG_START_ADDRESS ((uint32_t)&__config_start) +#define CONFIG_END_ADDRESS ((uint32_t)&__config_end) + +#define AVAILABLE_FIRMWARE_SPACE (FLASH_END - FIRMWARE_START_ADDRESS) + +extern uint8_t __firmware_start; // set via linker +extern uint8_t __config_start; +extern uint8_t __config_end; + +typedef struct { + uint32_t magic; +#ifdef USE_FLASHFS + uint32_t firmwareSize; + bool dataFlashErased; +#endif + uint8_t backupCRC; +} firmwareUpdateMetadata_t; + +bool firmwareUpdateMetadataRead(firmwareUpdateMetadata_t *updateMetadata); +bool firmwareUpdateMetadataWrite(firmwareUpdateMetadata_t *updateMetadata); diff --git a/src/main/io/asyncfatfs/asyncfatfs.c b/src/main/io/asyncfatfs/asyncfatfs.c index ecf4f268f5e..5f57a10b8b5 100644 --- a/src/main/io/asyncfatfs/asyncfatfs.c +++ b/src/main/io/asyncfatfs/asyncfatfs.c @@ -2107,6 +2107,25 @@ afatfsOperationStatus_e afatfs_fseek(afatfsFilePtr_t file, int32_t offset, afatf return afatfs_fseekInternal(file, MIN((uint32_t) offset, file->logicalSize), NULL); } +/** + * Attempt to seek the file cursor from the given point (`whence`) by the given offset, just like C's fseek(). + * + * AFATFS_SEEK_SET with offset 0 will always return AFATFS_OPERATION_SUCCESS. + * + * Returns: + * AFATFS_OPERATION_SUCCESS - The seek was completed immediately + * AFATFS_OPERATION_IN_PROGRESS - The seek was queued and will complete later. Feel free to attempt read/write + * operations on the file, they'll fail until the seek is complete. + */ +afatfsOperationStatus_e afatfs_fseekSync(afatfsFilePtr_t file, int32_t offset, afatfsSeek_e whence) +{ + while (afatfs_fileIsBusy(file)) { + afatfs_poll(); + } + + return afatfs_fseek(file, offset, whence); +} + /** * Get the byte-offset of the file's cursor from the start of the file. * @@ -2536,7 +2555,9 @@ static void afatfs_createFileContinue(afatfsFile_t *file) afatfsCreateFile_t *opState = &file->operation.state.createFile; fatDirectoryEntry_t *entry; afatfsOperationStatus_e status; +#ifndef BOOTLOADER dateTime_t now; +#endif doMore: @@ -2596,13 +2617,17 @@ static void afatfs_createFileContinue(afatfsFile_t *file) memcpy(entry->filename, opState->filename, FAT_FILENAME_LENGTH); entry->attrib = file->attrib; +#ifndef BOOTLOADER if (rtcGetDateTimeLocal(&now)) { entry->creationDate = FAT_MAKE_DATE(now.year, now.month, now.day); entry->creationTime = FAT_MAKE_TIME(now.hours, now.minutes, now.seconds); } else { +#endif entry->creationDate = AFATFS_DEFAULT_FILE_DATE; entry->creationTime = AFATFS_DEFAULT_FILE_TIME; +#ifndef BOOTLOADER } +#endif entry->lastWriteDate = entry->creationDate; entry->lastWriteTime = entry->creationTime; @@ -2867,6 +2892,20 @@ bool afatfs_fclose(afatfsFilePtr_t file, afatfsCallback_t callback) } } +/** + * Close `file` immediately + */ +void afatfs_fcloseSync(afatfsFilePtr_t file) +{ + for(unsigned i = 0; i < 1000; ++i) { + afatfs_poll(); + } + afatfs_fclose(file, NULL); + for(unsigned i = 0; i < 1000; ++i) { + afatfs_poll(); + } +} + /** * Create a new directory with the given name, or open the directory if it already exists. * @@ -2998,6 +3037,11 @@ bool afatfs_fopen(const char *filename, const char *mode, afatfsFileCallback_t c return file != NULL; } +uint32_t afatfs_fileSize(afatfsFilePtr_t file) +{ + return file->logicalSize; +} + /** * Write a single character to the file at the current cursor position. If the cache is too busy to accept the write, * it is silently dropped. @@ -3087,6 +3131,39 @@ uint32_t afatfs_fwrite(afatfsFilePtr_t file, const uint8_t *buffer, uint32_t len return writtenBytes; } +/** + * Attempt to write `len` bytes from `buffer` into the `file`. + * + * Returns the number of bytes actually written + * + * Fewer bytes than requested will be read when EOF is reached before all the bytes could be read + */ +uint32_t afatfs_fwriteSync(afatfsFilePtr_t file, uint8_t *data, uint32_t length) +{ + uint32_t written = 0; + + while (true) { + uint32_t leftToWrite = length - written; + uint32_t justWritten = afatfs_fwrite(file, data + written, leftToWrite); + /*if (justWritten != leftToWrite) LOG_E(SYSTEM, "%ld -> %ld", length, written);*/ + written += justWritten; + + if (written < length) { + + if (afatfs_isFull()) { + break; + } + + afatfs_poll(); + + } else { + break; + } + } + + return written; +} + /** * Attempt to read `len` bytes from `file` into the `buffer`. * @@ -3156,6 +3233,37 @@ uint32_t afatfs_fread(afatfsFilePtr_t file, uint8_t *buffer, uint32_t len) return readBytes; } +/** + * Attempt to read `len` bytes from `file` into the `buffer`. + * + * Returns the number of bytes actually read. + * + * Fewer bytes than requested will be read when EOF is reached before all the bytes could be read + */ +uint32_t afatfs_freadSync(afatfsFilePtr_t file, uint8_t *buffer, uint32_t length) +{ + uint32_t bytesRead = 0; + + while (true) { + uint32_t leftToRead = length - bytesRead; + uint32_t readNow = afatfs_fread(file, buffer, leftToRead); + bytesRead += readNow; + if (bytesRead < length) { + + if (afatfs_feof(file)) { + break; + } + + afatfs_poll(); + + } else { + break; + } + } + + return bytesRead; +} + /** * Returns true if the file's pointer position currently lies at the end-of-file point (i.e. one byte beyond the last * byte in the file). diff --git a/src/main/io/asyncfatfs/asyncfatfs.h b/src/main/io/asyncfatfs/asyncfatfs.h index 209ce4e6af4..521bd48fba7 100644 --- a/src/main/io/asyncfatfs/asyncfatfs.h +++ b/src/main/io/asyncfatfs/asyncfatfs.h @@ -63,14 +63,19 @@ typedef void (*afatfsCallback_t)(void); bool afatfs_fopen(const char *filename, const char *mode, afatfsFileCallback_t complete); bool afatfs_ftruncate(afatfsFilePtr_t file, afatfsFileCallback_t callback); bool afatfs_fclose(afatfsFilePtr_t file, afatfsCallback_t callback); +void afatfs_fcloseSync(afatfsFilePtr_t file); bool afatfs_funlink(afatfsFilePtr_t file, afatfsCallback_t callback); bool afatfs_feof(afatfsFilePtr_t file); void afatfs_fputc(afatfsFilePtr_t file, uint8_t c); uint32_t afatfs_fwrite(afatfsFilePtr_t file, const uint8_t *buffer, uint32_t len); +uint32_t afatfs_fwriteSync(afatfsFilePtr_t file, uint8_t *data, uint32_t length); uint32_t afatfs_fread(afatfsFilePtr_t file, uint8_t *buffer, uint32_t len); +uint32_t afatfs_freadSync(afatfsFilePtr_t file, uint8_t *buffer, uint32_t length); afatfsOperationStatus_e afatfs_fseek(afatfsFilePtr_t file, int32_t offset, afatfsSeek_e whence); +afatfsOperationStatus_e afatfs_fseekSync(afatfsFilePtr_t file, int32_t offset, afatfsSeek_e whence); bool afatfs_ftell(afatfsFilePtr_t file, uint32_t *position); +uint32_t afatfs_fileSize(afatfsFilePtr_t file); bool afatfs_mkdir(const char *filename, afatfsFileCallback_t complete); bool afatfs_chdir(afatfsFilePtr_t dirHandle); diff --git a/src/main/msp/msp_protocol_v2_inav.h b/src/main/msp/msp_protocol_v2_inav.h index 0367bc5a3bb..b2d43590f27 100755 --- a/src/main/msp/msp_protocol_v2_inav.h +++ b/src/main/msp/msp_protocol_v2_inav.h @@ -66,3 +66,9 @@ #define MSP2_SET_PID 0x2031 #define MSP2_INAV_OPFLOW_CALIBRATION 0x2032 + +#define MSP2_INAV_FWUPDT_PREPARE 0x2033 +#define MSP2_INAV_FWUPDT_STORE 0x2034 +#define MSP2_INAV_FWUPDT_EXEC 0x2035 +#define MSP2_INAV_FWUPDT_ROLLBACK_PREPARE 0x2036 +#define MSP2_INAV_FWUPDT_ROLLBACK_EXEC 0x2037 diff --git a/src/main/target/ANYFCF7/target.mk b/src/main/target/ANYFCF7/target.mk index 26d64b7bcad..35d30f5bd73 100644 --- a/src/main/target/ANYFCF7/target.mk +++ b/src/main/target/ANYFCF7/target.mk @@ -1,4 +1,4 @@ -F7X5XG_TARGETS += $(TARGET) +F765XG_TARGETS += $(TARGET) FEATURES += SDCARD VCP MSC TARGET_SRC = \ diff --git a/src/main/target/KAKUTEF7/target.mk b/src/main/target/KAKUTEF7/target.mk index 07e5ccfc947..8709f1ebcf8 100755 --- a/src/main/target/KAKUTEF7/target.mk +++ b/src/main/target/KAKUTEF7/target.mk @@ -1,4 +1,4 @@ -F7X5XG_TARGETS += $(TARGET) +F765XG_TARGETS += $(TARGET) ifeq ($(TARGET), KAKUTEF7MINI) FEATURES += VCP ONBOARDFLASH else diff --git a/src/main/target/MATEKF765/target.mk b/src/main/target/MATEKF765/target.mk index 9e34a0864e2..52b7bf2ef39 100644 --- a/src/main/target/MATEKF765/target.mk +++ b/src/main/target/MATEKF765/target.mk @@ -1,4 +1,4 @@ -F7X5XI_TARGETS += $(TARGET) +F765XI_TARGETS += $(TARGET) FEATURES += SDCARD VCP MSC TARGET_SRC = \ diff --git a/src/main/target/OMNIBUSF7/target.mk b/src/main/target/OMNIBUSF7/target.mk index 30cffe44327..ac20568838e 100644 --- a/src/main/target/OMNIBUSF7/target.mk +++ b/src/main/target/OMNIBUSF7/target.mk @@ -1,4 +1,4 @@ -F7X5XG_TARGETS += $(TARGET) +F765XG_TARGETS += $(TARGET) FEATURES += SDCARD VCP MSC TARGET_SRC = \ diff --git a/src/main/target/link/stm32_flash_f303_128k.ld b/src/main/target/link/stm32_flash_F303_128k.ld similarity index 100% rename from src/main/target/link/stm32_flash_f303_128k.ld rename to src/main/target/link/stm32_flash_F303_128k.ld diff --git a/src/main/target/link/stm32_flash_f303_256k.ld b/src/main/target/link/stm32_flash_F303_256k.ld similarity index 100% rename from src/main/target/link/stm32_flash_f303_256k.ld rename to src/main/target/link/stm32_flash_F303_256k.ld diff --git a/src/main/target/link/stm32_flash_f405.ld b/src/main/target/link/stm32_flash_F405.ld similarity index 100% rename from src/main/target/link/stm32_flash_f405.ld rename to src/main/target/link/stm32_flash_F405.ld diff --git a/src/main/target/link/stm32_flash_F405_bl.ld b/src/main/target/link/stm32_flash_F405_bl.ld new file mode 100644 index 00000000000..6ae82e6f8a7 --- /dev/null +++ b/src/main/target/link/stm32_flash_F405_bl.ld @@ -0,0 +1,43 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f405.ld +** +** Abstract : Linker script for STM32F405RG Device with +** 1024KByte FLASH, 128KByte RAM 64KByte CCM (RAM) +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x08000000 to 0x08100000 1024K full flash, +0x08000000 to 0x080DFFFF 896K firmware, +0x080E0000 to 0x08100000 128K config, // FLASH_Sector_11 +*/ + +/* Specify the memory areas */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K + FIRMWARE (rx) : ORIGIN = 0x08008000, LENGTH = 864K + FLASH_CONFIG (r) : ORIGIN = 0x080E0000, LENGTH = 128K + + RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + CCM (rwx) : ORIGIN = 0x10000000, LENGTH = 64K + BACKUP_SRAM (rwx) : ORIGIN = 0x40024000, LENGTH = 4K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("STACKRAM", CCM) +REGION_ALIAS("FASTRAM", CCM) + +__firmware_start = ORIGIN(FIRMWARE); + +INCLUDE "stm32_flash.ld" diff --git a/src/main/target/link/stm32_flash_F405_for_bl.ld b/src/main/target/link/stm32_flash_F405_for_bl.ld new file mode 100644 index 00000000000..c2a60a1429e --- /dev/null +++ b/src/main/target/link/stm32_flash_F405_for_bl.ld @@ -0,0 +1,42 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f405.ld +** +** Abstract : Linker script for STM32F405RG Device with +** 1024KByte FLASH, 128KByte RAM 64KByte CCM (RAM) +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x08000000 to 0x08100000 1024K full flash, +0x08000000 to 0x080DFFFF 896K firmware, +0x080E0000 to 0x08100000 128K config, // FLASH_Sector_11 +*/ + +/* Specify the memory areas */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08008000, LENGTH = 864K + FLASH_CONFIG (r) : ORIGIN = 0x080E0000, LENGTH = 128K + + RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + CCM (rwx) : ORIGIN = 0x10000000, LENGTH = 64K + BACKUP_SRAM (rwx) : ORIGIN = 0x40024000, LENGTH = 4K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("STACKRAM", CCM) +REGION_ALIAS("FASTRAM", CCM) + +__firmware_start = ORIGIN(FLASH); + +INCLUDE "stm32_flash.ld" diff --git a/src/main/target/link/stm32_flash_f405_opbl.ld b/src/main/target/link/stm32_flash_F405_opbl.ld similarity index 100% rename from src/main/target/link/stm32_flash_f405_opbl.ld rename to src/main/target/link/stm32_flash_F405_opbl.ld diff --git a/src/main/target/link/stm32_flash_f411.ld b/src/main/target/link/stm32_flash_F411.ld similarity index 100% rename from src/main/target/link/stm32_flash_f411.ld rename to src/main/target/link/stm32_flash_F411.ld diff --git a/src/main/target/link/stm32_flash_f411_opbl.ld b/src/main/target/link/stm32_flash_F411_opbl.ld similarity index 100% rename from src/main/target/link/stm32_flash_f411_opbl.ld rename to src/main/target/link/stm32_flash_F411_opbl.ld diff --git a/src/main/target/link/stm32_flash_f427.ld b/src/main/target/link/stm32_flash_F427.ld similarity index 100% rename from src/main/target/link/stm32_flash_f427.ld rename to src/main/target/link/stm32_flash_F427.ld diff --git a/src/main/target/link/stm32_flash_f446.ld b/src/main/target/link/stm32_flash_F446.ld similarity index 100% rename from src/main/target/link/stm32_flash_f446.ld rename to src/main/target/link/stm32_flash_F446.ld diff --git a/src/main/target/link/stm32_flash_F7.ld b/src/main/target/link/stm32_flash_F7.ld new file mode 100644 index 00000000000..e7ebaf29443 --- /dev/null +++ b/src/main/target/link/stm32_flash_F7.ld @@ -0,0 +1,184 @@ +/* +***************************************************************************** +** +** File : stm32_flash.ld +** +** Abstract : Common linker script for STM32 devices. +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = ORIGIN(STACKRAM) + LENGTH(STACKRAM); /* end of RAM */ + +/* Base address where the config is stored. */ +__config_start = ORIGIN(FLASH_CONFIG); +__config_end = ORIGIN(FLASH_CONFIG) + LENGTH(FLASH_CONFIG); + +/* Define output sections */ +SECTIONS +{ + /* The startup code goes first into FLASH */ + .isr_vector : + { + . = ALIGN(4); + PROVIDE (isr_vector_table_base = .); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + } >FLASH + + /* The program code and other data goes into FLASH */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >FLASH + + tcm_code = LOADADDR(.tcm_code); + .tcm_code (NOLOAD) : + { + . = ALIGN(4); + tcm_code_start = .; + *(.tcm_code) + *(.tcm_code*) + . = ALIGN(4); + tcm_code_end = .; + } >ITCM_RAM AT >FLASH + + .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH + .ARM : { + __exidx_start = .; + *(.ARM.exidx*) + __exidx_end = .; + } >FLASH + + .preinit_array : + { + PROVIDE_HIDDEN (__preinit_array_start = .); + KEEP (*(.preinit_array*)) + PROVIDE_HIDDEN (__preinit_array_end = .); + } >FLASH + .init_array : + { + PROVIDE_HIDDEN (__init_array_start = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array*)) + PROVIDE_HIDDEN (__init_array_end = .); + } >FLASH + .fini_array : + { + PROVIDE_HIDDEN (__fini_array_start = .); + KEEP (*(.fini_array*)) + KEEP (*(SORT(.fini_array.*))) + PROVIDE_HIDDEN (__fini_array_end = .); + } >FLASH + .pg_registry : + { + PROVIDE_HIDDEN (__pg_registry_start = .); + KEEP (*(.pg_registry)) + KEEP (*(SORT(.pg_registry.*))) + PROVIDE_HIDDEN (__pg_registry_end = .); + } >FLASH + .pg_resetdata : + { + PROVIDE_HIDDEN (__pg_resetdata_start = .); + KEEP (*(.pg_resetdata)) + PROVIDE_HIDDEN (__pg_resetdata_end = .); + } >FLASH + .busdev_registry : + { + PROVIDE_HIDDEN (__busdev_registry_start = .); + KEEP (*(.busdev_registry)) + KEEP (*(SORT(.busdev_registry.*))) + PROVIDE_HIDDEN (__busdev_registry_end = .); + } >FLASH + + /* used by the startup to initialize data */ + _sidata = .; + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >RAM AT> FLASH + + /* Uninitialized data section */ + . = ALIGN(4); + .bss : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(SORT_BY_ALIGNMENT(.bss*)) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + .fastram_bss (NOLOAD) : + { + __fastram_bss_start__ = .; + *(.fastram_bss) + *(SORT_BY_ALIGNMENT(.fastram_bss*)) + . = ALIGN(4); + __fastram_bss_end__ = .; + } >FASTRAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + _heap_stack_end = ORIGIN(STACKRAM)+LENGTH(STACKRAM) - 8; /* 8 bytes to allow for alignment */ + _heap_stack_begin = _heap_stack_end - _Min_Stack_Size - _Min_Heap_Size; + . = _heap_stack_begin; + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >STACKRAM = 0xa5 + + /* MEMORY_bank1 section, code must be located here explicitly */ + /* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */ + .memory_b1_text : + { + *(.mb1text) /* .mb1text sections (code) */ + *(.mb1text*) /* .mb1text* sections (code) */ + *(.mb1rodata) /* read-only data (constants) */ + *(.mb1rodata*) + } >MEMORY_B1 + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/src/main/target/link/stm32_flash_f746.ld b/src/main/target/link/stm32_flash_F746.ld similarity index 55% rename from src/main/target/link/stm32_flash_f746.ld rename to src/main/target/link/stm32_flash_F746.ld index 0c9041676f6..e7e8ee24ae9 100644 --- a/src/main/target/link/stm32_flash_f746.ld +++ b/src/main/target/link/stm32_flash_F746.ld @@ -26,22 +26,22 @@ ENTRY(Reset_Handler) /* Specify the memory areas */ MEMORY { - ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K - ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K + ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K /* config occupies the entire flash sector 1 for the ease of erasure, 32K on F74x */ - ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00208000, LENGTH = 32K - ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 960K + ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00208000, LENGTH = 32K + ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 960K - FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K - FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 32K - FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 960K + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K + FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 32K + FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 960K - TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K - RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 256K - MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K + TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 256K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K } /* note CCM could be used for stack */ REGION_ALIAS("STACKRAM", TCM) REGION_ALIAS("FASTRAM", TCM) -INCLUDE "stm32_flash_f7_split.ld" +INCLUDE "stm32_flash_F7_split.ld" diff --git a/src/main/target/link/stm32_flash_f765.ld b/src/main/target/link/stm32_flash_F765xI.ld similarity index 97% rename from src/main/target/link/stm32_flash_f765.ld rename to src/main/target/link/stm32_flash_F765xI.ld index 86e394c6733..3ec72586435 100644 --- a/src/main/target/link/stm32_flash_f765.ld +++ b/src/main/target/link/stm32_flash_F765xI.ld @@ -52,4 +52,4 @@ REGION_ALIAS("STACKRAM", DTCM_RAM) REGION_ALIAS("FASTRAM", DTCM_RAM) REGION_ALIAS("RAM", SRAM1) -INCLUDE "stm32_flash_f7_split.ld" \ No newline at end of file +INCLUDE "stm32_flash_F7_split.ld" diff --git a/src/main/target/link/stm32_flash_F765xI_bl.ld b/src/main/target/link/stm32_flash_F765xI_bl.ld new file mode 100644 index 00000000000..867bdbe8c4d --- /dev/null +++ b/src/main/target/link/stm32_flash_F765xI_bl.ld @@ -0,0 +1,56 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f765.ld +** +** Abstract : Linker script for STM32F765xITx Device with +** 2048KByte FLASH, 512KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x00003FFF 16K TCM RAM, + +0x08000000 to 0x081FFFFF 2048K full flash, +0x08000000 to 0x08007FFF 32K isr vector, startup code, +0x08008000 to 0x0800FFFF 32K config, +0x08010000 to 0x081FFFFF 1984K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K + + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K + ITCM_FLASH_CFG (r) : ORIGIN = 0x00208000, LENGTH = 32K + ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K + + AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K + AXIM_FIRMWARE (rx) : ORIGIN = 0x08008000, LENGTH = 32K + AXIM_FLASH_CFG (r) : ORIGIN = 0x08010000, LENGTH = 32K + + DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K + SRAM2 (rwx) : ORIGIN = 0x2007C000, LENGTH = 16K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("FLASH", AXIM_FLASH) +REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CFG) + +REGION_ALIAS("STACKRAM", DTCM_RAM) +REGION_ALIAS("FASTRAM", DTCM_RAM) +REGION_ALIAS("RAM", SRAM1) + +__firmware_start = ORIGIN(AXIM_FIRMWARE); + +INCLUDE "stm32_flash_F7.ld" diff --git a/src/main/target/link/stm32_flash_F765xI_for_bl.ld b/src/main/target/link/stm32_flash_F765xI_for_bl.ld new file mode 100644 index 00000000000..9661ff663c0 --- /dev/null +++ b/src/main/target/link/stm32_flash_F765xI_for_bl.ld @@ -0,0 +1,57 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f765.ld +** +** Abstract : Linker script for STM32F765xITx Device with +** 2048KByte FLASH, 512KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x00003FFF 16K TCM RAM, + +0x08000000 to 0x081FFFFF 2048K full flash, +0x08000000 to 0x08007FFF 32K isr vector, startup code, +0x08008000 to 0x0800FFFF 32K config, +0x08010000 to 0x081FFFFF 1984K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K + + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K + ITCM_FLASH_CFG (r) : ORIGIN = 0x00208000, LENGTH = 32K + ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K + + AXIM_FLASH (rx) : ORIGIN = 0x08008000, LENGTH = 32K + AXIM_FLASH_CFG (r) : ORIGIN = 0x08010000, LENGTH = 32K + AXIM_FLASH1 (rx) : ORIGIN = 0x08018000, LENGTH = 1984K + + DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K + SRAM2 (rwx) : ORIGIN = 0x2007C000, LENGTH = 16K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("FLASH", AXIM_FLASH) +REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CFG) +REGION_ALIAS("FLASH1", AXIM_FLASH1) + +REGION_ALIAS("STACKRAM", DTCM_RAM) +REGION_ALIAS("FASTRAM", DTCM_RAM) +REGION_ALIAS("RAM", SRAM1) + +__firmware_start = ORIGIN(AXIM_FLASH); + +INCLUDE "stm32_flash_F7_split.ld" diff --git a/src/main/target/link/stm32_flash_f7_split.ld b/src/main/target/link/stm32_flash_F7_split.ld similarity index 100% rename from src/main/target/link/stm32_flash_f7_split.ld rename to src/main/target/link/stm32_flash_F7_split.ld diff --git a/src/main/target/link/stm32_flash_f722.ld b/src/main/target/link/stm32_flash_F7x2.ld similarity index 97% rename from src/main/target/link/stm32_flash_f722.ld rename to src/main/target/link/stm32_flash_F7x2.ld index 296708678dc..7aba1e7b783 100644 --- a/src/main/target/link/stm32_flash_f722.ld +++ b/src/main/target/link/stm32_flash_F7x2.ld @@ -45,4 +45,4 @@ MEMORY REGION_ALIAS("STACKRAM", TCM) REGION_ALIAS("FASTRAM", TCM) -INCLUDE "stm32_flash_f7_split.ld" +INCLUDE "stm32_flash_F7_split.ld" diff --git a/src/main/target/link/stm32_flash_F7x2_bl.ld b/src/main/target/link/stm32_flash_F7x2_bl.ld new file mode 100644 index 00000000000..1241562d055 --- /dev/null +++ b/src/main/target/link/stm32_flash_F7x2_bl.ld @@ -0,0 +1,50 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f722.ld +** +** Abstract : Linker script for STM32F722RETx Device with +** 512KByte FLASH, 256KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x08000000 to 0x0807FFFF 512K full flash, +0x08000000 to 0x08003FFF 16K isr vector, startup code, +0x08004000 to 0x08007FFF 16K config, // FLASH_Sector_1 +0x08008000 to 0x0807FFFF 480K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 16K + + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 16K + /* config occupies the entire flash sector 1 for the ease of erasure, 16K on F72x */ + ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00204000, LENGTH = 16K + ITCM_FLASH1 (rx) : ORIGIN = 0x00208000, LENGTH = 480K + + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K + FIRMWARE (rx) : ORIGIN = 0x08008000, LENGTH = 16K + FLASH_CONFIG (r) : ORIGIN = 0x0800c000, LENGTH = 16K + + TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 192K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("STACKRAM", TCM) +REGION_ALIAS("FASTRAM", TCM) + +__firmware_start = ORIGIN(FIRMWARE); + +INCLUDE "stm32_flash_F7.ld" diff --git a/src/main/target/link/stm32_flash_F7x2_for_bl.ld b/src/main/target/link/stm32_flash_F7x2_for_bl.ld new file mode 100644 index 00000000000..5ce5fb03774 --- /dev/null +++ b/src/main/target/link/stm32_flash_F7x2_for_bl.ld @@ -0,0 +1,50 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f722.ld +** +** Abstract : Linker script for STM32F722RETx Device with +** 512KByte FLASH, 256KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x08000000 to 0x0807FFFF 512K full flash, +0x08000000 to 0x08003FFF 16K isr vector, startup code, +0x08004000 to 0x08007FFF 16K config, // FLASH_Sector_1 +0x08008000 to 0x0807FFFF 480K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 16K + + /*ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 16K*/ + /* config occupies the entire flash sector 1 for the ease of erasure, 16K on F72x */ + /*ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00204000, LENGTH = 16K*/ + /*ITCM_FLASH1 (rx) : ORIGIN = 0x00208000, LENGTH = 480K*/ + + FLASH (rx) : ORIGIN = 0x08008000, LENGTH = 16K + FLASH_CONFIG (r) : ORIGIN = 0x0800c000, LENGTH = 16K + FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 448K + + TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 192K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("STACKRAM", TCM) +REGION_ALIAS("FASTRAM", TCM) + +__firmware_start = ORIGIN(FLASH); + +INCLUDE "stm32_flash_F7_split.ld" diff --git a/src/main/target/link/stm32_flash_f745.ld b/src/main/target/link/stm32_flash_F7x5xG.ld similarity index 97% rename from src/main/target/link/stm32_flash_f745.ld rename to src/main/target/link/stm32_flash_F7x5xG.ld index a83374e4e41..0e72963cdb7 100644 --- a/src/main/target/link/stm32_flash_f745.ld +++ b/src/main/target/link/stm32_flash_F7x5xG.ld @@ -45,4 +45,4 @@ MEMORY REGION_ALIAS("STACKRAM", TCM) REGION_ALIAS("FASTRAM", TCM) -INCLUDE "stm32_flash_f7_split.ld" +INCLUDE "stm32_flash_F7_split.ld" diff --git a/src/main/target/link/stm32_flash_F7x5xG_bl.ld b/src/main/target/link/stm32_flash_F7x5xG_bl.ld new file mode 100644 index 00000000000..6639776539b --- /dev/null +++ b/src/main/target/link/stm32_flash_F7x5xG_bl.ld @@ -0,0 +1,50 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f745.ld +** +** Abstract : Linker script for STM32F745VGTx Device with +** 1024KByte FLASH, 320KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x00003FFF 16K ITCM RAM, +0x08000000 to 0x080FFFFF 1024K full flash, +0x08000000 to 0x08007FFF 32K isr vector, startup code, +0x08008000 to 0x0800FFFF 32K config, // FLASH_Sector_1 +0x08010000 to 0x080FFFFF 960K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K + /* config occupies the entire flash sector 1 for the ease of erasure, 32K on F74x */ + ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00208000, LENGTH = 32K + ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 928K + + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K + FIRMWARE (rx) : ORIGIN = 0x08008000, LENGTH = 32K + FLASH_CONFIG (r) : ORIGIN = 0x08010000, LENGTH = 32K + + TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 256K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} +/* note CCM could be used for stack */ +REGION_ALIAS("STACKRAM", TCM) +REGION_ALIAS("FASTRAM", TCM) + +__firmware_start = ORIGIN(FIRMWARE); + +INCLUDE "stm32_flash_F7.ld" diff --git a/src/main/target/link/stm32_flash_F7x5xG_for_bl.ld b/src/main/target/link/stm32_flash_F7x5xG_for_bl.ld new file mode 100644 index 00000000000..4cfd76df20a --- /dev/null +++ b/src/main/target/link/stm32_flash_F7x5xG_for_bl.ld @@ -0,0 +1,50 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f745.ld +** +** Abstract : Linker script for STM32F745VGTx Device with +** 1024KByte FLASH, 320KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x00003FFF 16K ITCM RAM, +0x08000000 to 0x080FFFFF 1024K full flash, +0x08000000 to 0x08007FFF 32K isr vector, startup code, +0x08008000 to 0x0800FFFF 32K config, // FLASH_Sector_1 +0x08010000 to 0x080FFFFF 960K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K + /* config occupies the entire flash sector 1 for the ease of erasure, 32K on F74x */ + ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00208000, LENGTH = 32K + ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 960K + + FLASH (rx) : ORIGIN = 0x08008000, LENGTH = 32K + FLASH_CONFIG (r) : ORIGIN = 0x08010000, LENGTH = 32K + FLASH1 (rx) : ORIGIN = 0x08018000, LENGTH = 928K + + TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 256K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} +/* note CCM could be used for stack */ +REGION_ALIAS("STACKRAM", TCM) +REGION_ALIAS("FASTRAM", TCM) + +__firmware_start = ORIGIN(FLASH); + +INCLUDE "stm32_flash_F7_split.ld" diff --git a/src/main/target/system.h b/src/main/target/system.h new file mode 100644 index 00000000000..916654eaa5e --- /dev/null +++ b/src/main/target/system.h @@ -0,0 +1,21 @@ +/* + * This file is part of iNav. + * + * iNav is free software. You can redistribute this software + * and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * iNav is distributed in the hope that they will be + * useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +extern uint8_t isr_vector_table_base; diff --git a/src/main/target/system_stm32f4xx.c b/src/main/target/system_stm32f4xx.c index 65add7cf710..be9b27ec3bb 100644 --- a/src/main/target/system_stm32f4xx.c +++ b/src/main/target/system_stm32f4xx.c @@ -315,6 +315,7 @@ */ #include "stm32f4xx.h" +#include "system.h" #include "system_stm32f4xx.h" uint32_t hse_value = HSE_VALUE; @@ -509,7 +510,7 @@ void SystemInit(void) #ifdef VECT_TAB_SRAM SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */ #else - SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */ + SCB->VTOR = (uint32_t) &isr_vector_table_base; /* Vector Table Relocation in Internal FLASH */ #endif } diff --git a/src/main/target/system_stm32f7xx.c b/src/main/target/system_stm32f7xx.c index 034c14a2db3..29ece48639b 100644 --- a/src/main/target/system_stm32f7xx.c +++ b/src/main/target/system_stm32f7xx.c @@ -298,7 +298,8 @@ void SystemInit(void) #ifdef VECT_TAB_SRAM SCB->VTOR = RAMDTCM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */ #else - SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */ + extern uint8_t isr_vector_table_base; /* Vector Table Relocation in Internal FLASH */ + SCB->VTOR = (uint32_t) &isr_vector_table_base; #endif /* Enable I-Cache */ diff --git a/src/utils/combine_tool b/src/utils/combine_tool new file mode 100755 index 00000000000..c32110f3d57 --- /dev/null +++ b/src/utils/combine_tool @@ -0,0 +1,29 @@ +#!/usr/bin/env ruby + +## +## This file is part of iNav. +## +## iNav is free software. You can redistribute this software +## and/or modify this software under the terms of the +## GNU General Public License as published by the Free Software +## Foundation, either version 3 of the License, or (at your option) +## any later version. +## +## iNav is distributed in the hope that they will be +## useful, but WITHOUT ANY WARRANTY; without even the implied +## warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. +## See the GNU General Public License for more details. +## +## You should have received a copy of the GNU General Public License +## along with this software. +## +## If not, see . +## + +require_relative 'intelhex' + +ih = IntelHex.new +ih.add_section 0x08000000, File.open(ARGV[0], 'rb') +ih.add_section 0x08008000, File.open(ARGV[1], 'rb') +ih.start_address = 0x08000000 +ih.write File.open(ARGV[2], 'w') diff --git a/src/utils/intelhex.rb b/src/utils/intelhex.rb new file mode 100644 index 00000000000..58dca4024d1 --- /dev/null +++ b/src/utils/intelhex.rb @@ -0,0 +1,100 @@ +## +## This file is part of iNav. +## +## iNav is free software. You can redistribute this software +## and/or modify this software under the terms of the +## GNU General Public License as published by the Free Software +## Foundation, either version 3 of the License, or (at your option) +## any later version. +## +## iNav is distributed in the hope that they will be +## useful, but WITHOUT ANY WARRANTY; without even the implied +## warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. +## See the GNU General Public License for more details. +## +## You should have received a copy of the GNU General Public License +## along with this software. +## +## If not, see . +## + +class IntelHex + + class Section < Struct.new(:address, :io); end + + def initialize address = 0, bin_io = nil, start_address = nil + @sections = Array.new + @start_address = start_address == true ? address : start_address + add_section address, bin_io if bin_io + end + + def add_section address, io + sections << Section.new(address, io) + end + + def write io + sections.each { |section| write_section section, io } + write_start_linear_address start_address, io if start_address + write_end_of_file io + nil + end + + attr_reader :sections + attr_accessor :start_address + + private + + def calc_crc address, record_type, data + sum = 0 + sum += (address & 0xFF00) >> 8 + sum += (address & 0x00FF) + sum += record_type + + if data.is_a? Integer + sum += data > 0xFFFF ? 4 : 2 + sum += (data & 0xFF000000) >> 24 + sum += (data & 0x00FF0000) >> 16 + sum += (data & 0x0000FF00) >> 8 + sum += (data & 0x000000FF) + else + sum += data.bytesize + sum += data.each_byte.sum + end + + ((sum ^ 0xFF) + 1) & 0xFF + end + + def write_end_of_file io + io.puts ":00000001FF" + end + + def write_start_linear_address address, io + crc = calc_crc 0, 5, address + io.printf ":04000005%08X%02X\n", address, crc + end + + def write_extended_linear_address address, io + address_msw = (address & 0xffff0000) >> 16 + crc = calc_crc 0, 4, address_msw + io.printf ":02000004%04X%02X\n", address_msw, crc + end + + def write_data address, data, io + address &= 0xFFFF + hex_data = data.each_byte.map { |byte| "%02X" % byte }.join + crc = calc_crc address, 0, data + io.printf ":%02X%04X00%s%02X\n", data.bytesize, address, hex_data, crc + end + + def write_section section, io + previous_address = 0 + address = section.address + while data = section.io.read(16) + write_extended_linear_address address, io if (previous_address & 0xFFFF0000) != (address & 0xFFFF0000) + previous_address = address + write_data address, data, io + address += data.bytesize + end + end + +end From 760ae1d538f3a91a0e978d142d0ce673b44d501d Mon Sep 17 00:00:00 2001 From: Ilya Guterman Date: Tue, 21 Jul 2020 13:03:58 +0300 Subject: [PATCH 060/248] bulk erase if single sector this is just a copy from betaflight the erase logic --- src/main/drivers/flash.c | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/src/main/drivers/flash.c b/src/main/drivers/flash.c index 0f2f9aca74e..33f5144407e 100644 --- a/src/main/drivers/flash.c +++ b/src/main/drivers/flash.c @@ -287,6 +287,13 @@ void flashPartitionErase(flashPartition_t *partition) { const flashGeometry_t * const geometry = flashGetGeometry(); + // if there's a single FLASHFS partition and it uses the entire flash then do a full erase + const bool doFullErase = (flashPartitionCount() == 1) && (FLASH_PARTITION_SECTOR_COUNT(partition) == geometry->sectors); + if (doFullErase) { + flashEraseCompletely(); + return; + } + for (unsigned i = partition->startSector; i <= partition->endSector; i++) { uint32_t flashAddress = geometry->sectorSize * i; flashEraseSector(flashAddress); From 21ef8fc2c2e6780139810e65199a8baf1a377022 Mon Sep 17 00:00:00 2001 From: craigmunday Date: Wed, 22 Jul 2020 21:21:09 +1000 Subject: [PATCH 061/248] Added craft name to the osd armed page --- src/main/io/osd.c | 34 +++++++++++++++++++++++----------- 1 file changed, 23 insertions(+), 11 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index dda74ae3e79..04a298e2223 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -615,6 +615,19 @@ static void osdFormatCoordinate(char *buff, char sym, int32_t val) buff[coordinateLength] = '\0'; } +static void osdFormatCraftName(char *buff) +{ + if (strlen(systemConfig()->name) == 0) + strcpy(buff, "CRAFT_NAME"); + else { + for (int i = 0; i < MAX_NAME_LENGTH; i++) { + buff[i] = sl_toupper((unsigned char)systemConfig()->name[i]); + if (systemConfig()->name[i] == 0) + break; + } + } +} + // Used twice, make sure it's exactly the same string // to save some memory #define RC_RX_LINK_LOST_MSG "!RC RX LINK LOST!" @@ -1659,15 +1672,7 @@ static bool osdDrawSingleElement(uint8_t item) } case OSD_CRAFT_NAME: - if (strlen(systemConfig()->name) == 0) - strcpy(buff, "CRAFT_NAME"); - else { - for (int i = 0; i < MAX_NAME_LENGTH; i++) { - buff[i] = sl_toupper((unsigned char)systemConfig()->name[i]); - if (systemConfig()->name[i] == 0) - break; - } - } + osdFormatCraftName(buff); break; case OSD_THROTTLE_POS: @@ -3072,15 +3077,22 @@ static void osdShowArmed(void) { dateTime_t dt; char buf[MAX(32, FORMATTED_DATE_TIME_BUFSIZE)]; + char craftNameBuf[MAX_NAME_LENGTH]; char *date; char *time; - // We need 7 visible rows - uint8_t y = MIN((osdDisplayPort->rows / 2) - 1, osdDisplayPort->rows - 7 - 1); + // We need 10 visible rows + uint8_t y = MIN((osdDisplayPort->rows / 2) - 1, osdDisplayPort->rows - 10 - 1); displayClearScreen(osdDisplayPort); displayWrite(osdDisplayPort, 12, y, "ARMED"); y += 2; + if (strlen(systemConfig()->name) > 0) { + osdFormatCraftName(craftNameBuf); + displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(systemConfig() -> name)) / 2, y, craftNameBuf ); + y += 2; + } + #if defined(USE_GPS) if (feature(FEATURE_GPS)) { if (STATE(GPS_FIX_HOME)) { From 827ac0495000e663377cdfe92adbed2a3566f0c0 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 22 Jul 2020 21:53:54 +0200 Subject: [PATCH 062/248] Unify Global Functions and Logic Conditions into single entity --- src/main/fc/fc_core.c | 2 +- src/main/flight/mixer.c | 4 +- src/main/io/osd.c | 4 +- src/main/programming/global_functions.c | 234 ++++++++++++------------ src/main/programming/global_functions.h | 23 +-- src/main/programming/logic_condition.c | 123 +++++++++++++ src/main/programming/logic_condition.h | 32 ++++ src/main/programming/programming_task.c | 1 - 8 files changed, 277 insertions(+), 146 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index e9382d2dd35..67a916371ea 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -450,7 +450,7 @@ void tryArm(void) if ( !isArmingDisabled() || emergencyArmingIsEnabled() || - GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_ARMING_SAFETY) + LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY) ) { #else if ( diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index b24b78c911d..eebb090dd1d 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -480,10 +480,10 @@ void FAST_CODE mixTable(const float dT) // Find min and max throttle based on condition. #ifdef USE_PROGRAMMING_FRAMEWORK - if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE)) { + if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE)) { throttleRangeMin = throttleIdleValue; throttleRangeMax = motorConfig()->maxthrottle; - mixerThrottleCommand = constrain(globalFunctionValues[GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE], throttleRangeMin, throttleRangeMax); + mixerThrottleCommand = constrain(logicConditionValuesByType[LOGIC_CONDITION_OVERRIDE_THROTTLE], throttleRangeMin, throttleRangeMax); } else #endif if (feature(FEATURE_REVERSIBLE_MOTORS)) { diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 2c4db39b58e..02086f85033 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -3243,8 +3243,8 @@ void osdUpdate(timeUs_t currentTimeUs) activeLayout = 1; else #ifdef USE_PROGRAMMING_FRAMEWORK - if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_OSD_LAYOUT)) - activeLayout = constrain(globalFunctionValues[GLOBAL_FUNCTION_ACTION_SET_OSD_LAYOUT], 0, OSD_ALTERNATE_LAYOUT_COUNT); + if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT)) + activeLayout = constrain(logicConditionValuesByType[LOGIC_CONDITION_SET_OSD_LAYOUT], 0, OSD_ALTERNATE_LAYOUT_COUNT); else #endif activeLayout = 0; diff --git a/src/main/programming/global_functions.c b/src/main/programming/global_functions.c index 675da332157..3b1a98fec30 100644 --- a/src/main/programming/global_functions.c +++ b/src/main/programming/global_functions.c @@ -40,9 +40,9 @@ PG_REGISTER_ARRAY_WITH_RESET_FN(globalFunction_t, MAX_GLOBAL_FUNCTIONS, globalFunctions, PG_GLOBAL_FUNCTIONS, 0); -EXTENDED_FASTRAM uint64_t globalFunctionsFlags = 0; -EXTENDED_FASTRAM globalFunctionState_t globalFunctionsStates[MAX_GLOBAL_FUNCTIONS]; -EXTENDED_FASTRAM int globalFunctionValues[GLOBAL_FUNCTION_ACTION_LAST]; +// EXTENDED_FASTRAM uint64_t globalFunctionsFlags = 0; +// EXTENDED_FASTRAM globalFunctionState_t globalFunctionsStates[MAX_GLOBAL_FUNCTIONS]; +// EXTENDED_FASTRAM int globalFunctionValues[GLOBAL_FUNCTION_ACTION_LAST]; void pgResetFn_globalFunctions(globalFunction_t *instance) { @@ -64,126 +64,118 @@ void globalFunctionsProcess(int8_t functionId) { //Process only activated functions if (globalFunctions(functionId)->enabled) { - const int conditionValue = logicConditionGetValue(globalFunctions(functionId)->conditionId); - const int previousValue = globalFunctionsStates[functionId].active; - - globalFunctionsStates[functionId].active = (bool) conditionValue; - globalFunctionsStates[functionId].value = logicConditionGetOperandValue( - globalFunctions(functionId)->withValue.type, - globalFunctions(functionId)->withValue.value - ); - - switch (globalFunctions(functionId)->action) { - case GLOBAL_FUNCTION_ACTION_OVERRIDE_ARMING_SAFETY: - if (conditionValue) { - GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_ARMING_SAFETY); - } - break; - case GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE_SCALE: - if (conditionValue) { - globalFunctionValues[GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE_SCALE] = globalFunctionsStates[functionId].value; - GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE_SCALE); - } - break; - case GLOBAL_FUNCTION_ACTION_SWAP_ROLL_YAW: - if (conditionValue) { - GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_SWAP_ROLL_YAW); - } - break; - case GLOBAL_FUNCTION_ACTION_SET_VTX_POWER_LEVEL: - if (conditionValue && !previousValue) { - vtxDeviceCapability_t vtxDeviceCapability; - if (vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)) { - vtxSettingsConfigMutable()->power = constrain(globalFunctionsStates[functionId].value, VTX_SETTINGS_MIN_POWER, vtxDeviceCapability.powerCount); - } - } - break; - case GLOBAL_FUNCTION_ACTION_SET_VTX_BAND: - if (conditionValue && !previousValue) { - vtxDeviceCapability_t vtxDeviceCapability; - if (vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)) { - vtxSettingsConfigMutable()->band = constrain(globalFunctionsStates[functionId].value, VTX_SETTINGS_MIN_BAND, VTX_SETTINGS_MAX_BAND); - } - } - break; - case GLOBAL_FUNCTION_ACTION_SET_VTX_CHANNEL: - if (conditionValue && !previousValue) { - vtxDeviceCapability_t vtxDeviceCapability; - if (vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)) { - vtxSettingsConfigMutable()->channel = constrain(globalFunctionsStates[functionId].value, VTX_SETTINGS_MIN_CHANNEL, VTX_SETTINGS_MAX_CHANNEL); - } - } - break; - case GLOBAL_FUNCTION_ACTION_INVERT_ROLL: - if (conditionValue) { - GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_ROLL); - } - break; - case GLOBAL_FUNCTION_ACTION_INVERT_PITCH: - if (conditionValue) { - GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_PITCH); - } - break; - case GLOBAL_FUNCTION_ACTION_INVERT_YAW: - if (conditionValue) { - GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_YAW); - } - break; - case GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE: - if (conditionValue) { - globalFunctionValues[GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE] = globalFunctionsStates[functionId].value; - GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE); - } - break; - case GLOBAL_FUNCTION_ACTION_SET_OSD_LAYOUT: - if(conditionValue){ - globalFunctionValues[GLOBAL_FUNCTION_ACTION_SET_OSD_LAYOUT] = globalFunctionsStates[functionId].value; - GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_OSD_LAYOUT); - } - break; - } - } -} - -void NOINLINE globalFunctionsUpdateTask(timeUs_t currentTimeUs) { - UNUSED(currentTimeUs); - - //Disable all flags - globalFunctionsFlags = 0; - - for (uint8_t i = 0; i < MAX_GLOBAL_FUNCTIONS; i++) { - globalFunctionsProcess(i); + // const int conditionValue = logicConditionGetValue(globalFunctions(functionId)->conditionId); + // const int previousValue = globalFunctionsStates[functionId].active; + + // globalFunctionsStates[functionId].active = (bool) conditionValue; + // globalFunctionsStates[functionId].value = logicConditionGetOperandValue( + // globalFunctions(functionId)->withValue.type, + // globalFunctions(functionId)->withValue.value + // ); + + // switch (globalFunctions(functionId)->action) { + // case GLOBAL_FUNCTION_ACTION_OVERRIDE_ARMING_SAFETY: + // if (conditionValue) { + // LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY); + // } + // break; + // case GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE_SCALE: + // if (conditionValue) { + // globalFunctionValues[GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE_SCALE] = globalFunctionsStates[functionId].value; + // LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE_SCALE); + // } + // break; + // case GLOBAL_FUNCTION_ACTION_SWAP_ROLL_YAW: + // if (conditionValue) { + // LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_SWAP_ROLL_YAW); + // } + // break; + // case GLOBAL_FUNCTION_ACTION_SET_VTX_POWER_LEVEL: + // if (conditionValue && !previousValue) { + // vtxDeviceCapability_t vtxDeviceCapability; + // if (vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)) { + // vtxSettingsConfigMutable()->power = constrain(globalFunctionsStates[functionId].value, VTX_SETTINGS_MIN_POWER, vtxDeviceCapability.powerCount); + // } + // } + // break; + // case GLOBAL_FUNCTION_ACTION_SET_VTX_BAND: + // if (conditionValue && !previousValue) { + // vtxDeviceCapability_t vtxDeviceCapability; + // if (vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)) { + // vtxSettingsConfigMutable()->band = constrain(globalFunctionsStates[functionId].value, VTX_SETTINGS_MIN_BAND, VTX_SETTINGS_MAX_BAND); + // } + // } + // break; + // case GLOBAL_FUNCTION_ACTION_SET_VTX_CHANNEL: + // if (conditionValue && !previousValue) { + // vtxDeviceCapability_t vtxDeviceCapability; + // if (vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)) { + // vtxSettingsConfigMutable()->channel = constrain(globalFunctionsStates[functionId].value, VTX_SETTINGS_MIN_CHANNEL, VTX_SETTINGS_MAX_CHANNEL); + // } + // } + // break; + // case GLOBAL_FUNCTION_ACTION_INVERT_ROLL: + // if (conditionValue) { + // LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_ROLL); + // } + // break; + // case GLOBAL_FUNCTION_ACTION_INVERT_PITCH: + // if (conditionValue) { + // LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_PITCH); + // } + // break; + // case GLOBAL_FUNCTION_ACTION_INVERT_YAW: + // if (conditionValue) { + // LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_YAW); + // } + // break; + // case GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE: + // if (conditionValue) { + // globalFunctionValues[GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE] = globalFunctionsStates[functionId].value; + // LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE); + // } + // break; + // case GLOBAL_FUNCTION_ACTION_SET_OSD_LAYOUT: + // if(conditionValue){ + // globalFunctionValues[GLOBAL_FUNCTION_ACTION_SET_OSD_LAYOUT] = globalFunctionsStates[functionId].value; + // LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT); + // } + // break; + // } } } -float NOINLINE getThrottleScale(float globalThrottleScale) { - if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE_SCALE)) { - return constrainf(globalFunctionValues[GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE_SCALE] / 100.0f, 0.0f, 1.0f); - } else { - return globalThrottleScale; - } -} - -int16_t getRcCommandOverride(int16_t command[], uint8_t axis) { - int16_t outputValue = command[axis]; - - if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_SWAP_ROLL_YAW) && axis == FD_ROLL) { - outputValue = command[FD_YAW]; - } else if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_SWAP_ROLL_YAW) && axis == FD_YAW) { - outputValue = command[FD_ROLL]; - } - - if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_ROLL) && axis == FD_ROLL) { - outputValue *= -1; - } - if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_PITCH) && axis == FD_PITCH) { - outputValue *= -1; - } - if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_YAW) && axis == FD_YAW) { - outputValue *= -1; - } - - return outputValue; -} +// void NOINLINE globalFunctionsUpdateTask(timeUs_t currentTimeUs) { +// UNUSED(currentTimeUs); + +// //Disable all flags +// globalFunctionsFlags = 0; + +// for (uint8_t i = 0; i < MAX_GLOBAL_FUNCTIONS; i++) { +// globalFunctionsProcess(i); +// } +// } + +// int16_t getRcCommandOverride(int16_t command[], uint8_t axis) { +// int16_t outputValue = command[axis]; + +// if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_SWAP_ROLL_YAW) && axis == FD_ROLL) { +// outputValue = command[FD_YAW]; +// } else if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_SWAP_ROLL_YAW) && axis == FD_YAW) { +// outputValue = command[FD_ROLL]; +// } + +// if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_ROLL) && axis == FD_ROLL) { +// outputValue *= -1; +// } +// if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_PITCH) && axis == FD_PITCH) { +// outputValue *= -1; +// } +// if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_YAW) && axis == FD_YAW) { +// outputValue *= -1; +// } + +// return outputValue; +// } #endif diff --git a/src/main/programming/global_functions.h b/src/main/programming/global_functions.h index e6221ef8e32..f0f0aa1e418 100644 --- a/src/main/programming/global_functions.h +++ b/src/main/programming/global_functions.h @@ -43,17 +43,6 @@ typedef enum { GLOBAL_FUNCTION_ACTION_LAST } globalFunctionActions_e; -typedef enum { - GLOBAL_FUNCTION_FLAG_OVERRIDE_ARMING_SAFETY = (1 << 0), - GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE_SCALE = (1 << 1), - GLOBAL_FUNCTION_FLAG_OVERRIDE_SWAP_ROLL_YAW = (1 << 2), - GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_ROLL = (1 << 3), - GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_PITCH = (1 << 4), - GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_YAW = (1 << 5), - GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE = (1 << 6), - GLOBAL_FUNCTION_FLAG_OVERRIDE_OSD_LAYOUT = (1 << 7), -} globalFunctionFlags_t; - typedef struct globalFunction_s { uint8_t enabled; int8_t conditionId; @@ -70,13 +59,9 @@ typedef struct globalFunctionState_s { extern uint64_t globalFunctionsFlags; -#define GLOBAL_FUNCTION_FLAG_DISABLE(mask) (globalFunctionsFlags &= ~(mask)) -#define GLOBAL_FUNCTION_FLAG_ENABLE(mask) (globalFunctionsFlags |= (mask)) -#define GLOBAL_FUNCTION_FLAG(mask) (globalFunctionsFlags & (mask)) - PG_DECLARE_ARRAY(globalFunction_t, MAX_GLOBAL_FUNCTIONS, globalFunctions); -extern int globalFunctionValues[GLOBAL_FUNCTION_ACTION_LAST]; +// extern int globalFunctionValues[GLOBAL_FUNCTION_ACTION_LAST]; -void globalFunctionsUpdateTask(timeUs_t currentTimeUs); -float getThrottleScale(float globalThrottleScale); -int16_t getRcCommandOverride(int16_t command[], uint8_t axis); \ No newline at end of file +// void globalFunctionsUpdateTask(timeUs_t currentTimeUs); +// float getThrottleScale(float globalThrottleScale); +// int16_t getRcCommandOverride(int16_t command[], uint8_t axis); \ No newline at end of file diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index d42d62fa71c..e73e868d746 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -45,8 +45,14 @@ #include "navigation/navigation.h" #include "navigation/navigation_private.h" +#include "io/vtx.h" +#include "drivers/vtx_common.h" + PG_REGISTER_ARRAY_WITH_RESET_FN(logicCondition_t, MAX_LOGIC_CONDITIONS, logicConditions, PG_LOGIC_CONDITIONS, 1); +EXTENDED_FASTRAM uint64_t logicConditionsGlobalFlags; +EXTENDED_FASTRAM int logicConditionValuesByType[LOGIC_CONDITION_LAST]; + void pgResetFn_logicConditions(logicCondition_t *instance) { for (int i = 0; i < MAX_LOGIC_CONDITIONS; i++) { @@ -76,6 +82,8 @@ static int logicConditionCompute( int operandB ) { int temporaryValue; + vtxDeviceCapability_t vtxDeviceCapability; + switch (operation) { case LOGIC_CONDITION_TRUE: @@ -180,6 +188,87 @@ static int logicConditionCompute( return operandA; } break; + + case LOGIC_CONDITION_OVERRIDE_ARMING_SAFETY: + LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY); + return true; + break; + + case LOGIC_CONDITION_OVERRIDE_THROTTLE_SCALE: + logicConditionValuesByType[LOGIC_CONDITION_OVERRIDE_THROTTLE_SCALE] = operandA; + LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE_SCALE); + return true; + break; + + case LOGIC_CONDITION_SWAP_ROLL_YAW: + LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_SWAP_ROLL_YAW); + return true; + break; + + case LOGIC_CONDITION_SET_VTX_POWER_LEVEL: + if ( + logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_POWER_LEVEL] != operandA && + vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability) + ) { + logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_POWER_LEVEL] = constrain(operandA, VTX_SETTINGS_MIN_POWER, vtxDeviceCapability.powerCount); + vtxSettingsConfigMutable()->power = logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_POWER_LEVEL]; + return logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_POWER_LEVEL]; + } else { + return false; + } + break; + + case LOGIC_CONDITION_SET_VTX_BAND: + if ( + logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_BAND] != operandA && + vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability) + ) { + logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_BAND] = constrain(operandA, VTX_SETTINGS_MIN_BAND, VTX_SETTINGS_MAX_BAND); + vtxSettingsConfigMutable()->band = logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_BAND]; + return logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_BAND]; + } else { + return false; + } + break; + case LOGIC_CONDITION_SET_VTX_CHANNEL: + if ( + logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_CHANNEL] != operandA && + vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability) + ) { + logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_CHANNEL] = constrain(operandA, VTX_SETTINGS_MIN_CHANNEL, VTX_SETTINGS_MAX_CHANNEL); + vtxSettingsConfigMutable()->channel = logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_CHANNEL]; + return logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_CHANNEL]; + } else { + return false; + } + break; + + case LOGIC_CONDITION_INVERT_ROLL: + LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_ROLL); + return true; + break; + + case LOGIC_CONDITION_INVERT_PITCH: + LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_PITCH); + return true; + break; + + case LOGIC_CONDITION_INVERT_YAW: + LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_YAW); + return true; + break; + + case LOGIC_CONDITION_OVERRIDE_THROTTLE: + logicConditionValuesByType[LOGIC_CONDITION_OVERRIDE_THROTTLE] = operandA; + LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE); + return operandA; + break; + + case LOGIC_CONDITION_SET_OSD_LAYOUT: + logicConditionValuesByType[LOGIC_CONDITION_SET_OSD_LAYOUT] = operandA; + LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT); + return operandA; + break; default: return false; @@ -453,6 +542,10 @@ int logicConditionGetValue(int8_t conditionId) { void logicConditionUpdateTask(timeUs_t currentTimeUs) { UNUSED(currentTimeUs); + + //Disable all flags + logicConditionsGlobalFlags = 0; + for (uint8_t i = 0; i < MAX_LOGIC_CONDITIONS; i++) { logicConditionProcess(i); } @@ -464,3 +557,33 @@ void logicConditionReset(void) { logicConditionStates[i].flags = 0; } } + +float NOINLINE getThrottleScale(float globalThrottleScale) { + if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE_SCALE)) { + return constrainf(logicConditionValuesByType[LOGIC_CONDITION_OVERRIDE_THROTTLE_SCALE] / 100.0f, 0.0f, 1.0f); + } else { + return globalThrottleScale; + } +} + +int16_t getRcCommandOverride(int16_t command[], uint8_t axis) { + int16_t outputValue = command[axis]; + + if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_SWAP_ROLL_YAW) && axis == FD_ROLL) { + outputValue = command[FD_YAW]; + } else if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_SWAP_ROLL_YAW) && axis == FD_YAW) { + outputValue = command[FD_ROLL]; + } + + if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_ROLL) && axis == FD_ROLL) { + outputValue *= -1; + } + if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_PITCH) && axis == FD_PITCH) { + outputValue *= -1; + } + if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_YAW) && axis == FD_YAW) { + outputValue *= -1; + } + + return outputValue; +} \ No newline at end of file diff --git a/src/main/programming/logic_condition.h b/src/main/programming/logic_condition.h index f48383870ab..b5900c4b935 100644 --- a/src/main/programming/logic_condition.h +++ b/src/main/programming/logic_condition.h @@ -50,6 +50,17 @@ typedef enum { LOGIC_CONDITION_GVAR_SET, // 18 LOGIC_CONDITION_GVAR_INC, // 19 LOGIC_CONDITION_GVAR_DEC, // 20 + LOGIC_CONDITION_OVERRIDE_ARMING_SAFETY = 129, + LOGIC_CONDITION_OVERRIDE_THROTTLE_SCALE = 130, + LOGIC_CONDITION_SWAP_ROLL_YAW = 131, + LOGIC_CONDITION_SET_VTX_POWER_LEVEL = 132, + LOGIC_CONDITION_INVERT_ROLL = 133, + LOGIC_CONDITION_INVERT_PITCH = 134, + LOGIC_CONDITION_INVERT_YAW = 135, + LOGIC_CONDITION_OVERRIDE_THROTTLE = 136, + LOGIC_CONDITION_SET_VTX_BAND = 137, + LOGIC_CONDITION_SET_VTX_CHANNEL = 138, + LOGIC_CONDITION_SET_OSD_LAYOUT = 139, LOGIC_CONDITION_LAST } logicOperation_e; @@ -107,6 +118,17 @@ typedef enum { LOGIC_CONDITION_OPERAND_FLIGHT_MODE_AIR, } logicFlightModeOperands_e; +typedef enum { + LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY = (1 << 0), + LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE_SCALE = (1 << 1), + LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_SWAP_ROLL_YAW = (1 << 2), + LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_ROLL = (1 << 3), + LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_PITCH = (1 << 4), + LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_YAW = (1 << 5), + LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE = (1 << 6), + LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT = (1 << 7), +} logicConditionsGlobalFlags_t; + typedef enum { LOGIC_CONDITION_FLAG_LATCH = 1 << 0, } logicConditionFlags_e; @@ -132,6 +154,13 @@ typedef struct logicConditionState_s { uint8_t flags; } logicConditionState_t; +extern int logicConditionValuesByType[LOGIC_CONDITION_LAST]; +extern uint64_t logicConditionsGlobalFlags; + +#define LOGIC_CONDITION_GLOBAL_FLAG_DISABLE(mask) (logicConditionsGlobalFlags &= ~(mask)) +#define LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(mask) (logicConditionsGlobalFlags |= (mask)) +#define LOGIC_CONDITION_GLOBAL_FLAG(mask) (logicConditionsGlobalFlags & (mask)) + void logicConditionProcess(uint8_t i); int logicConditionGetOperandValue(logicOperandType_e type, int operand); @@ -139,3 +168,6 @@ int logicConditionGetOperandValue(logicOperandType_e type, int operand); int logicConditionGetValue(int8_t conditionId); void logicConditionUpdateTask(timeUs_t currentTimeUs); void logicConditionReset(void); + +float getThrottleScale(float globalThrottleScale); +int16_t getRcCommandOverride(int16_t command[], uint8_t axis); \ No newline at end of file diff --git a/src/main/programming/programming_task.c b/src/main/programming/programming_task.c index 1447ffd231f..7afe4ffb3a7 100644 --- a/src/main/programming/programming_task.c +++ b/src/main/programming/programming_task.c @@ -31,5 +31,4 @@ FILE_COMPILE_FOR_SIZE void programmingFrameworkUpdateTask(timeUs_t currentTimeUs) { logicConditionUpdateTask(currentTimeUs); - globalFunctionsUpdateTask(currentTimeUs); } \ No newline at end of file From 426d21a9fc3077289cef34943272a40b91b9ae7c Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 23 Jul 2020 10:47:43 +0200 Subject: [PATCH 063/248] Cleanup --- docs/Global Functions.md | 79 -------- ...Conditions.md => Programming Framework.md} | 71 ++++++- make/source.mk | 1 - src/main/fc/cli.c | 109 ----------- src/main/fc/fc_core.c | 1 - src/main/fc/fc_msp.c | 27 --- src/main/flight/mixer.c | 1 - src/main/flight/pid.c | 3 +- src/main/io/osd.c | 3 +- src/main/programming/global_functions.c | 181 ------------------ src/main/programming/global_functions.h | 67 ------- src/main/programming/programming_task.c | 1 - 12 files changed, 70 insertions(+), 474 deletions(-) delete mode 100644 docs/Global Functions.md rename docs/{Logic Conditions.md => Programming Framework.md} (66%) delete mode 100644 src/main/programming/global_functions.c delete mode 100644 src/main/programming/global_functions.h diff --git a/docs/Global Functions.md b/docs/Global Functions.md deleted file mode 100644 index 81f350cff2b..00000000000 --- a/docs/Global Functions.md +++ /dev/null @@ -1,79 +0,0 @@ -# Global Functions - -_Global Functions_ (abbr. GF) are a mechanism allowing to override certain flight parameters (during flight). Global Functions are activated by [Logic Conditions](Logic%20Conditions.md) - -## CLI - -`gf ` - -* `` - GF ID, indexed from `0` -* `` - `0` evaluates as disabled, `1` evaluates as enabled. Only enabled GFs are executed -* `` - the ID of _LogicCondition_ used to trigger GF On/Off. Then LC evaluates `true`, GlobalFunction will be come active -* `` - action to execute when GF is active -* `` - allows to pass arguments into Global Function action. Syntax is the same as in case of Logic Conditions operands. Used only when `action` requires it. Should be kept at `0` in other case. See [Logic Conditions](Logic%20Conditions.md) -* `` - allows to pass arguments into Global Function action. Syntax is the same as in case of Logic Conditions operands. Used only when `action` requires it. Should be kept at `0` in other case. See [Logic Conditions](Logic%20Conditions.md) -* `` - allows to pass arguments into Global Function action. Syntax is the same as in case of Logic Conditions operands - -## Actions - -| Action ID | Name | Notes | -|---- |---- |---- | -| 0 | OVERRIDE_ARMING_SAFETY | Allows to arm on any angle even without GPS fix | -| 1 | OVERRIDE_THROTTLE_SCALE | Override throttle scale to the value defined by operand. Operand type `0` and value `50` means throttle will be scaled by 50%. | -| 2 | SWAP_ROLL_YAW | basically, when activated, yaw stick will control roll and roll stick will control yaw. Required for tail-sitters VTOL during vertical-horizonral transition when body frame changes | -| 3 | SET_VTX_POWER_LEVEL | Sets VTX power level. Accepted values are `0-3` for SmartAudio and `0-4` for Tramp protocol | -| 4 | INVERT_ROLL | Inverts ROLL axis input for PID/PIFF controller | -| 5 | INVERT_PITCH | Inverts PITCH axis input for PID/PIFF controller | -| 6 | INVERT_YAW | Inverts YAW axis input for PID/PIFF controller | -| 7 | OVERRIDE_THROTTLE | Override throttle value that is fed to the motors by mixer. Operand is scaled in us. `1000` means throttle cut, `1500` means half throttle | -| 8 | SET_VTX_BAND | Sets VTX band. Accepted values are `1-5` | -| 9 | SET_VTX_CHANNEL | Sets VTX channel. Accepted values are `1-8` | -| 10 | SET_OSD_LAYOUT | Sets OSD layout. Accepted values are `0-3` | - -## Flags - -Current no flags are implemented - -## Example - -### Dynamic THROTTLE scale - -`gf 0 1 0 1 0 50 0` - -Limits the THROTTLE output to 50% when Logic Condition `0` evaluates as `true` - -### Set VTX power level via Smart Audio - -`gf 0 1 0 3 0 3 0` - -Sets VTX power level to `3` when Logic Condition `0` evaluates as `true` - -### Invert ROLL and PITCH when rear facing camera FPV is used - -Solves the problem from [https://github.com/iNavFlight/inav/issues/4439](https://github.com/iNavFlight/inav/issues/4439) - -``` -gf 0 1 0 4 0 0 0 -gf 1 1 0 5 0 0 0 -``` - -Inverts ROLL and PITCH input when Logic Condition `0` evaluates as `true`. Moving Pitch stick up will cause pitch down (up for rear facing camera). Moving Roll stick right will cause roll left of a quad (right in rear facing camera) - -### Cut motors but keep other throttle bindings active - -`gf 0 1 0 7 0 1000 0` - -Sets Thhrottle output to `0%` when Logic Condition `0` evaluates as `true` - -### Set throttle to 50% and keep other throttle bindings active - -`gf 0 1 0 7 0 1500 0` - -Sets Thhrottle output to about `50%` when Logic Condition `0` evaluates as `true` - -### Set throttle control to different RC channel - -`gf 0 1 0 7 1 7 0` - -If Logic Condition `0` evaluates as `true`, motor throttle control is bound to RC channel 7 instead of throttle channel - diff --git a/docs/Logic Conditions.md b/docs/Programming Framework.md similarity index 66% rename from docs/Logic Conditions.md rename to docs/Programming Framework.md index 10ffc058d41..6bbc4ecd76e 100644 --- a/docs/Logic Conditions.md +++ b/docs/Programming Framework.md @@ -1,11 +1,16 @@ -# Logic Conditions +# INAV Programming Framework -Logic Conditions (abbr. LC) is a mechanism that allows to evaluate cenrtain flight parameters (RC channels, switches, altitude, distance, timers, other logic conditions) and use the value of evaluated expression in different places of INAV. Currently, the result of LCs can be used in: +INAV Programming Framework (abbr. IPF) is a mechanism that allows to evaluate cenrtain flight parameters (RC channels, switches, altitude, distance, timers, other logic conditions) and use the value of evaluated expression in different places of INAV. Currently, the result of LCs can be used in: * [Servo mixer](Mixer.md) to activate/deactivate certain servo mix rulers -* [Global functions](Global%20Functions.md) to activate/deactivate system overrides +* To activate/deactivate system overrides -Logic conditions can be edited using INAV Configurator user interface, of via CLI +INAV Programming Framework coinsists of: + +* Logic Conditions - each Logic Condition can be understood as a single command, a single line of code +* Global Variables - variables that can store values from and for LogiC Conditions and servo mixer + +IPF can be edited using INAV Configurator user interface, of via CLI ## CLI @@ -46,7 +51,19 @@ Logic conditions can be edited using INAV Configurator user interface, of via CL | 18 | GVAR SET | Store value from `Operand B` into the Global Variable addressed by `Operand B`. Bear in mind, that operand `Global Variable` means: Value stored in Global Variable of an index! To store in GVAR 1 use `Value 1` not `Global Variable 1` | | 19 | GVAR INC | Increase the GVAR indexed by `Operand A` with value from `Operand B` | | 20 | GVAR DEC | Decrease the GVAR indexed by `Operand A` with value from `Operand B` | -| 128 | IO PORT SET | Set I2C IO Expander pin `Operand A` to value of `Operand B`. `Operand A` accepts values `0-7` and `Operand B` accepts `0` and `1` | +| 21 | IO PORT SET | Set I2C IO Expander pin `Operand A` to value of `Operand B`. `Operand A` accepts values `0-7` and `Operand B` accepts `0` and `1` | +| 22 | OVERRIDE_ARMING_SAFETY | Allows to arm on any angle even without GPS fix | +| 23 | OVERRIDE_THROTTLE_SCALE | Override throttle scale to the value defined by operand. Operand type `0` and value `50` means throttle will be scaled by 50%. | +| 24 | SWAP_ROLL_YAW | basically, when activated, yaw stick will control roll and roll stick will control yaw. Required for tail-sitters VTOL during vertical-horizonral transition when body frame changes | +| 25 | SET_VTX_POWER_LEVEL | Sets VTX power level. Accepted values are `0-3` for SmartAudio and `0-4` for Tramp protocol | +| 26 | INVERT_ROLL | Inverts ROLL axis input for PID/PIFF controller | +| 27 | INVERT_PITCH | Inverts PITCH axis input for PID/PIFF controller | +| 28 | INVERT_YAW | Inverts YAW axis input for PID/PIFF controller | +| 29 | OVERRIDE_THROTTLE | Override throttle value that is fed to the motors by mixer. Operand is scaled in us. `1000` means throttle cut, `1500` means half throttle | +| 30 | SET_VTX_BAND | Sets VTX band. Accepted values are `1-5` | +| 31 | SET_VTX_CHANNEL | Sets VTX channel. Accepted values are `1-8` | +| 32 | SET_OSD_LAYOUT | Sets OSD layout. Accepted values are `0-3` | + ### Operands @@ -112,3 +129,47 @@ All flags are reseted on ARM and DISARM event. | bit | Decimal | Function | |---- |---- |---- | | 0 | 1 | Latch - after activation LC will stay active until LATCH flag is reseted | + +## Examples + +### Dynamic THROTTLE scale + +`logic 0 1 0 23 0 50 0 0 0` + +Limits the THROTTLE output to 50% when Logic Condition `0` evaluates as `true` + +### Set VTX power level via Smart Audio + +`logic 0 1 0 25 0 3 0 0 0` + +Sets VTX power level to `3` when Logic Condition `0` evaluates as `true` + +### Invert ROLL and PITCH when rear facing camera FPV is used + +Solves the problem from [https://github.com/iNavFlight/inav/issues/4439](https://github.com/iNavFlight/inav/issues/4439) + +``` +logic 0 1 0 26 0 0 0 0 0 +logic 1 1 0 27 0 0 0 0 0 +``` + +Inverts ROLL and PITCH input when Logic Condition `0` evaluates as `true`. Moving Pitch stick up will cause pitch down (up for rear facing camera). Moving Roll stick right will cause roll left of a quad (right in rear facing camera) + +### Cut motors but keep other throttle bindings active + +`logic 0 1 0 29 0 1000 0 0 0` + +Sets Thhrottle output to `0%` when Logic Condition `0` evaluates as `true` + +### Set throttle to 50% and keep other throttle bindings active + +`logic 0 1 0 29 0 1500 0 0 0` + +Sets Thhrottle output to about `50%` when Logic Condition `0` evaluates as `true` + +### Set throttle control to different RC channel + +`logic 0 1 0 29 1 7 0 0 0` + +If Logic Condition `0` evaluates as `true`, motor throttle control is bound to RC channel 7 instead of throttle channel + diff --git a/make/source.mk b/make/source.mk index 8de6927dc5b..21f7b7abf4e 100644 --- a/make/source.mk +++ b/make/source.mk @@ -38,7 +38,6 @@ MAIN_SRC = \ common/time.c \ common/uvarint.c \ programming/logic_condition.c \ - programming/global_functions.c \ programming/global_variables.c \ programming/programming_task.c \ config/config_eeprom.c \ diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index f9233eb7120..ffa75db9b62 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -43,7 +43,6 @@ extern uint8_t __config_end; #include "common/memory.h" #include "common/time.h" #include "common/typeconversion.h" -#include "programming/global_functions.h" #include "programming/global_variables.h" #include "config/config_eeprom.h" @@ -1950,104 +1949,6 @@ static void cliGvar(char *cmdline) { #endif -#ifdef USE_PROGRAMMING_FRAMEWORK - -static void printGlobalFunctions(uint8_t dumpMask, const globalFunction_t *globalFunctions, const globalFunction_t *defaultGlobalFunctions) -{ - const char *format = "gf %d %d %d %d %d %d %d"; - for (uint32_t i = 0; i < MAX_GLOBAL_FUNCTIONS; i++) { - const globalFunction_t gf = globalFunctions[i]; - - bool equalsDefault = false; - if (defaultGlobalFunctions) { - globalFunction_t defaultValue = defaultGlobalFunctions[i]; - equalsDefault = - gf.enabled == defaultValue.enabled && - gf.conditionId == defaultValue.conditionId && - gf.action == defaultValue.action && - gf.withValue.type == defaultValue.withValue.type && - gf.withValue.value == defaultValue.withValue.value && - gf.flags == defaultValue.flags; - - cliDefaultPrintLinef(dumpMask, equalsDefault, format, - i, - gf.enabled, - gf.conditionId, - gf.action, - gf.withValue.type, - gf.withValue.value, - gf.flags - ); - } - cliDumpPrintLinef(dumpMask, equalsDefault, format, - i, - gf.enabled, - gf.conditionId, - gf.action, - gf.withValue.type, - gf.withValue.value, - gf.flags - ); - } -} - -static void cliGlobalFunctions(char *cmdline) { - char * saveptr; - int args[7], check = 0; - uint8_t len = strlen(cmdline); - - if (len == 0) { - printGlobalFunctions(DUMP_MASTER, globalFunctions(0), NULL); - } else if (sl_strncasecmp(cmdline, "reset", 5) == 0) { - pgResetCopy(globalFunctionsMutable(0), PG_GLOBAL_FUNCTIONS); - } else { - enum { - INDEX = 0, - ENABLED, - CONDITION_ID, - ACTION, - VALUE_TYPE, - VALUE_VALUE, - FLAGS, - ARGS_COUNT - }; - char *ptr = strtok_r(cmdline, " ", &saveptr); - while (ptr != NULL && check < ARGS_COUNT) { - args[check++] = fastA2I(ptr); - ptr = strtok_r(NULL, " ", &saveptr); - } - - if (ptr != NULL || check != ARGS_COUNT) { - cliShowParseError(); - return; - } - - int32_t i = args[INDEX]; - if ( - i >= 0 && i < MAX_GLOBAL_FUNCTIONS && - args[ENABLED] >= 0 && args[ENABLED] <= 1 && - args[CONDITION_ID] >= -1 && args[CONDITION_ID] < MAX_LOGIC_CONDITIONS && - args[ACTION] >= 0 && args[ACTION] < GLOBAL_FUNCTION_ACTION_LAST && - args[VALUE_TYPE] >= 0 && args[VALUE_TYPE] < LOGIC_CONDITION_OPERAND_TYPE_LAST && - args[VALUE_VALUE] >= -1000000 && args[VALUE_VALUE] <= 1000000 && - args[FLAGS] >= 0 && args[FLAGS] <= 255 - - ) { - globalFunctionsMutable(i)->enabled = args[ENABLED]; - globalFunctionsMutable(i)->conditionId = args[CONDITION_ID]; - globalFunctionsMutable(i)->action = args[ACTION]; - globalFunctionsMutable(i)->withValue.type = args[VALUE_TYPE]; - globalFunctionsMutable(i)->withValue.value = args[VALUE_VALUE]; - globalFunctionsMutable(i)->flags = args[FLAGS]; - - cliGlobalFunctions(""); - } else { - cliShowParseError(); - } - } -} -#endif - #ifdef USE_SDCARD static void cliWriteBytes(const uint8_t *buffer, int count) @@ -3329,11 +3230,6 @@ static void printConfig(const char *cmdline, bool doDiff) printGvar(dumpMask, globalVariableConfigs_CopyArray, globalVariableConfigs(0)); #endif -#ifdef USE_PROGRAMMING_FRAMEWORK - cliPrintHashLine("gf"); - printGlobalFunctions(dumpMask, globalFunctions_CopyArray, globalFunctions(0)); -#endif - cliPrintHashLine("feature"); printFeature(dumpMask, &featureConfig_Copy, featureConfig()); @@ -3580,11 +3476,6 @@ const clicmd_t cmdTable[] = { CLI_COMMAND_DEF("gvar", "configure global variables", " \r\n" "\treset\r\n", cliGvar), -#endif -#ifdef USE_PROGRAMMING_FRAMEWORK - CLI_COMMAND_DEF("gf", "configure global functions", - " \r\n" - "\treset\r\n", cliGlobalFunctions), #endif CLI_COMMAND_DEF("set", "change setting", "[=]", cliSet), CLI_COMMAND_DEF("smix", "servo mixer", diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 67a916371ea..5317dc04704 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -32,7 +32,6 @@ FILE_COMPILE_FOR_SPEED #include "common/color.h" #include "common/utils.h" #include "common/filter.h" -#include "programming/global_functions.h" #include "drivers/light_led.h" #include "drivers/serial.h" diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index dd7528f0fb3..076b7077f1d 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -35,7 +35,6 @@ #include "common/bitarray.h" #include "common/time.h" #include "common/utils.h" -#include "programming/global_functions.h" #include "programming/global_variables.h" #include "config/parameter_group_ids.h" @@ -551,18 +550,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU32(dst, gvGet(i)); } break; -#endif -#ifdef USE_PROGRAMMING_FRAMEWORK - case MSP2_INAV_GLOBAL_FUNCTIONS: - for (int i = 0; i < MAX_GLOBAL_FUNCTIONS; i++) { - sbufWriteU8(dst, globalFunctions(i)->enabled); - sbufWriteU8(dst, globalFunctions(i)->conditionId); - sbufWriteU8(dst, globalFunctions(i)->action); - sbufWriteU8(dst, globalFunctions(i)->withValue.type); - sbufWriteU32(dst, globalFunctions(i)->withValue.value); - sbufWriteU8(dst, logicConditions(i)->flags); - } - break; #endif case MSP2_COMMON_MOTOR_MIXER: for (uint8_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) { @@ -1953,20 +1940,6 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) } else return MSP_RESULT_ERROR; break; -#endif -#ifdef USE_PROGRAMMING_FRAMEWORK - case MSP2_INAV_SET_GLOBAL_FUNCTIONS: - sbufReadU8Safe(&tmp_u8, src); - if ((dataSize == 10) && (tmp_u8 < MAX_GLOBAL_FUNCTIONS)) { - globalFunctionsMutable(tmp_u8)->enabled = sbufReadU8(src); - globalFunctionsMutable(tmp_u8)->conditionId = sbufReadU8(src); - globalFunctionsMutable(tmp_u8)->action = sbufReadU8(src); - globalFunctionsMutable(tmp_u8)->withValue.type = sbufReadU8(src); - globalFunctionsMutable(tmp_u8)->withValue.value = sbufReadU32(src); - globalFunctionsMutable(tmp_u8)->flags = sbufReadU8(src); - } else - return MSP_RESULT_ERROR; - break; #endif case MSP2_COMMON_SET_MOTOR_MIXER: sbufReadU8Safe(&tmp_u8, src); diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index eebb090dd1d..20fa78d30b6 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -29,7 +29,6 @@ FILE_COMPILE_FOR_SPEED #include "common/filter.h" #include "common/maths.h" #include "common/utils.h" -#include "programming/global_functions.h" #include "config/feature.h" #include "config/parameter_group.h" diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 732bc26520b..88dedf1814a 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -57,10 +57,11 @@ FILE_COMPILE_FOR_SPEED #include "sensors/acceleration.h" #include "sensors/compass.h" #include "sensors/pitotmeter.h" -#include "programming/global_functions.h" #include "scheduler/scheduler.h" +#include "programming/logic_condition.h" + typedef struct { float kP; // Proportional gain float kI; // Integral gain diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 02086f85033..5453718eeb7 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -52,7 +52,6 @@ FILE_COMPILE_FOR_SPEED #include "common/time.h" #include "common/typeconversion.h" #include "common/utils.h" -#include "programming/global_functions.h" #include "config/feature.h" #include "config/parameter_group.h" @@ -104,6 +103,8 @@ FILE_COMPILE_FOR_SPEED #include "sensors/temperature.h" #include "sensors/esc_sensor.h" +#include "programming/logic_condition.h" + #ifdef USE_HARDWARE_REVISION_DETECTION #include "hardware_revision.h" #endif diff --git a/src/main/programming/global_functions.c b/src/main/programming/global_functions.c deleted file mode 100644 index 3b1a98fec30..00000000000 --- a/src/main/programming/global_functions.c +++ /dev/null @@ -1,181 +0,0 @@ -/* - * This file is part of INAV Project. - * - * This Source Code Form is subject to the terms of the Mozilla Public - * License, v. 2.0. If a copy of the MPL was not distributed with this file, - * You can obtain one at http://mozilla.org/MPL/2.0/. - * - * Alternatively, the contents of this file may be used under the terms - * of the GNU General Public License Version 3, as described below: - * - * This file is free software: you may copy, redistribute and/or modify - * it under the terms of the GNU General Public License as published by the - * Free Software Foundation, either version 3 of the License, or (at your - * option) any later version. - * - * This file is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General - * Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see http://www.gnu.org/licenses/. - */ - -#include "config/config_reset.h" -#include "config/parameter_group.h" -#include "config/parameter_group_ids.h" - -#include "common/utils.h" -#include "common/maths.h" -#include "programming/global_functions.h" -#include "programming/logic_condition.h" - -#include "io/vtx.h" -#include "drivers/vtx_common.h" - -#ifdef USE_PROGRAMMING_FRAMEWORK - -#include "common/axis.h" - -PG_REGISTER_ARRAY_WITH_RESET_FN(globalFunction_t, MAX_GLOBAL_FUNCTIONS, globalFunctions, PG_GLOBAL_FUNCTIONS, 0); - -// EXTENDED_FASTRAM uint64_t globalFunctionsFlags = 0; -// EXTENDED_FASTRAM globalFunctionState_t globalFunctionsStates[MAX_GLOBAL_FUNCTIONS]; -// EXTENDED_FASTRAM int globalFunctionValues[GLOBAL_FUNCTION_ACTION_LAST]; - -void pgResetFn_globalFunctions(globalFunction_t *instance) -{ - for (int i = 0; i < MAX_GLOBAL_FUNCTIONS; i++) { - RESET_CONFIG(globalFunction_t, &instance[i], - .enabled = 0, - .conditionId = -1, - .action = 0, - .withValue = { - .type = LOGIC_CONDITION_OPERAND_TYPE_VALUE, - .value = 0 - }, - .flags = 0 - ); - } -} - -void globalFunctionsProcess(int8_t functionId) { - //Process only activated functions - if (globalFunctions(functionId)->enabled) { - - // const int conditionValue = logicConditionGetValue(globalFunctions(functionId)->conditionId); - // const int previousValue = globalFunctionsStates[functionId].active; - - // globalFunctionsStates[functionId].active = (bool) conditionValue; - // globalFunctionsStates[functionId].value = logicConditionGetOperandValue( - // globalFunctions(functionId)->withValue.type, - // globalFunctions(functionId)->withValue.value - // ); - - // switch (globalFunctions(functionId)->action) { - // case GLOBAL_FUNCTION_ACTION_OVERRIDE_ARMING_SAFETY: - // if (conditionValue) { - // LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY); - // } - // break; - // case GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE_SCALE: - // if (conditionValue) { - // globalFunctionValues[GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE_SCALE] = globalFunctionsStates[functionId].value; - // LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE_SCALE); - // } - // break; - // case GLOBAL_FUNCTION_ACTION_SWAP_ROLL_YAW: - // if (conditionValue) { - // LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_SWAP_ROLL_YAW); - // } - // break; - // case GLOBAL_FUNCTION_ACTION_SET_VTX_POWER_LEVEL: - // if (conditionValue && !previousValue) { - // vtxDeviceCapability_t vtxDeviceCapability; - // if (vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)) { - // vtxSettingsConfigMutable()->power = constrain(globalFunctionsStates[functionId].value, VTX_SETTINGS_MIN_POWER, vtxDeviceCapability.powerCount); - // } - // } - // break; - // case GLOBAL_FUNCTION_ACTION_SET_VTX_BAND: - // if (conditionValue && !previousValue) { - // vtxDeviceCapability_t vtxDeviceCapability; - // if (vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)) { - // vtxSettingsConfigMutable()->band = constrain(globalFunctionsStates[functionId].value, VTX_SETTINGS_MIN_BAND, VTX_SETTINGS_MAX_BAND); - // } - // } - // break; - // case GLOBAL_FUNCTION_ACTION_SET_VTX_CHANNEL: - // if (conditionValue && !previousValue) { - // vtxDeviceCapability_t vtxDeviceCapability; - // if (vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)) { - // vtxSettingsConfigMutable()->channel = constrain(globalFunctionsStates[functionId].value, VTX_SETTINGS_MIN_CHANNEL, VTX_SETTINGS_MAX_CHANNEL); - // } - // } - // break; - // case GLOBAL_FUNCTION_ACTION_INVERT_ROLL: - // if (conditionValue) { - // LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_ROLL); - // } - // break; - // case GLOBAL_FUNCTION_ACTION_INVERT_PITCH: - // if (conditionValue) { - // LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_PITCH); - // } - // break; - // case GLOBAL_FUNCTION_ACTION_INVERT_YAW: - // if (conditionValue) { - // LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_YAW); - // } - // break; - // case GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE: - // if (conditionValue) { - // globalFunctionValues[GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE] = globalFunctionsStates[functionId].value; - // LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE); - // } - // break; - // case GLOBAL_FUNCTION_ACTION_SET_OSD_LAYOUT: - // if(conditionValue){ - // globalFunctionValues[GLOBAL_FUNCTION_ACTION_SET_OSD_LAYOUT] = globalFunctionsStates[functionId].value; - // LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT); - // } - // break; - // } - } -} - -// void NOINLINE globalFunctionsUpdateTask(timeUs_t currentTimeUs) { -// UNUSED(currentTimeUs); - -// //Disable all flags -// globalFunctionsFlags = 0; - -// for (uint8_t i = 0; i < MAX_GLOBAL_FUNCTIONS; i++) { -// globalFunctionsProcess(i); -// } -// } - -// int16_t getRcCommandOverride(int16_t command[], uint8_t axis) { -// int16_t outputValue = command[axis]; - -// if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_SWAP_ROLL_YAW) && axis == FD_ROLL) { -// outputValue = command[FD_YAW]; -// } else if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_SWAP_ROLL_YAW) && axis == FD_YAW) { -// outputValue = command[FD_ROLL]; -// } - -// if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_ROLL) && axis == FD_ROLL) { -// outputValue *= -1; -// } -// if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_PITCH) && axis == FD_PITCH) { -// outputValue *= -1; -// } -// if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_YAW) && axis == FD_YAW) { -// outputValue *= -1; -// } - -// return outputValue; -// } - -#endif diff --git a/src/main/programming/global_functions.h b/src/main/programming/global_functions.h deleted file mode 100644 index f0f0aa1e418..00000000000 --- a/src/main/programming/global_functions.h +++ /dev/null @@ -1,67 +0,0 @@ -/* - * This file is part of INAV Project. - * - * This Source Code Form is subject to the terms of the Mozilla Public - * License, v. 2.0. If a copy of the MPL was not distributed with this file, - * You can obtain one at http://mozilla.org/MPL/2.0/. - * - * Alternatively, the contents of this file may be used under the terms - * of the GNU General Public License Version 3, as described below: - * - * This file is free software: you may copy, redistribute and/or modify - * it under the terms of the GNU General Public License as published by the - * Free Software Foundation, either version 3 of the License, or (at your - * option) any later version. - * - * This file is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General - * Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see http://www.gnu.org/licenses/. - */ -#pragma once - -#include "config/parameter_group.h" -#include "programming/logic_condition.h" - -#define MAX_GLOBAL_FUNCTIONS 8 - -typedef enum { - GLOBAL_FUNCTION_ACTION_OVERRIDE_ARMING_SAFETY = 0, // 0 - GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE_SCALE, // 1 - GLOBAL_FUNCTION_ACTION_SWAP_ROLL_YAW, // 2 - GLOBAL_FUNCTION_ACTION_SET_VTX_POWER_LEVEL, // 3 - GLOBAL_FUNCTION_ACTION_INVERT_ROLL, // 4 - GLOBAL_FUNCTION_ACTION_INVERT_PITCH, // 5 - GLOBAL_FUNCTION_ACTION_INVERT_YAW, // 6 - GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE, // 7 - GLOBAL_FUNCTION_ACTION_SET_VTX_BAND, // 8 - GLOBAL_FUNCTION_ACTION_SET_VTX_CHANNEL, // 9 - GLOBAL_FUNCTION_ACTION_SET_OSD_LAYOUT, // 10 - GLOBAL_FUNCTION_ACTION_LAST -} globalFunctionActions_e; - -typedef struct globalFunction_s { - uint8_t enabled; - int8_t conditionId; - uint8_t action; - logicOperand_t withValue; - uint8_t flags; -} globalFunction_t; - -typedef struct globalFunctionState_s { - uint8_t active; - int value; - uint8_t flags; -} globalFunctionState_t; - -extern uint64_t globalFunctionsFlags; - -PG_DECLARE_ARRAY(globalFunction_t, MAX_GLOBAL_FUNCTIONS, globalFunctions); -// extern int globalFunctionValues[GLOBAL_FUNCTION_ACTION_LAST]; - -// void globalFunctionsUpdateTask(timeUs_t currentTimeUs); -// float getThrottleScale(float globalThrottleScale); -// int16_t getRcCommandOverride(int16_t command[], uint8_t axis); \ No newline at end of file diff --git a/src/main/programming/programming_task.c b/src/main/programming/programming_task.c index 7afe4ffb3a7..ba26217fc34 100644 --- a/src/main/programming/programming_task.c +++ b/src/main/programming/programming_task.c @@ -27,7 +27,6 @@ FILE_COMPILE_FOR_SIZE #include "programming/logic_condition.h" -#include "programming/global_functions.h" void programmingFrameworkUpdateTask(timeUs_t currentTimeUs) { logicConditionUpdateTask(currentTimeUs); From 2ad51deecf3843baa60194f416db5ddaa765bf38 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 8 Jun 2020 23:05:38 +0100 Subject: [PATCH 064/248] [FRSKYOSD] Use new comments for grid drawing They save a few bytes per call. A test layout with 8 indicators flashing now uses ~30% less bytes per second. --- src/main/io/frsky_osd.c | 97 +++++++++++++++++++++++++++++++++++------ 1 file changed, 83 insertions(+), 14 deletions(-) diff --git a/src/main/io/frsky_osd.c b/src/main/io/frsky_osd.c index 719476204e9..a8551523fa1 100644 --- a/src/main/io/frsky_osd.c +++ b/src/main/io/frsky_osd.c @@ -114,6 +114,8 @@ typedef enum // MAX7456 emulation commands OSD_CMD_DRAW_GRID_CHR = 110, OSD_CMD_DRAW_GRID_STR = 111, + OSD_CMD_DRAW_GRID_CHR_2 = 112, // API2 + OSD_CMD_DRAW_GRID_STR_2 = 113, // API2 } osdCommand_e; typedef enum { @@ -159,9 +161,18 @@ typedef struct frskyOSDDrawGridStrHeaderCmd_s { uint8_t gx; uint8_t gy; uint8_t opts; - // uvarint with size and blob folow + // uvarint with size and blob follow + // string IS null-terminated } __attribute__((packed)) frskyOSDDrawGridStrHeaderCmd_t; +typedef struct frskyOSDDrawGridStrV2HeaderCmd_s { + uint8_t gx : 5; // +5 = 5 + uint8_t gy : 4; // +4 = 9 + uint8_t opts : 7; // +7 = 16 = 2 bytes + // uvarint with size and blob folow + // string IS NOT null terminated +} __attribute__((packed)) frskyOSDDrawGridStrV2HeaderCmd_t; + typedef struct frskyOSDPoint_s { int x : 12; int y : 12; @@ -212,6 +223,15 @@ typedef struct frskyOSDDrawStrMaskCommandHeaderCmd_s { // uvarint with size and blob follow } __attribute__((packed)) frskyOSDDrawStrMaskCommandHeaderCmd_t; +typedef struct frskyOSDDrawGridChrV2Cmd_s +{ + uint8_t gx : 5; // +5 = 5 + uint8_t gy : 4; // +4 = 9 + uint16_t chr : 9; // +9 = 18 + uint8_t opts : 4; // +4 = 22 from osd_bitmap_opt_t + uint8_t reserved : 2; // +2 = 24 = 3 bytes +} __attribute__((packed)) frskyOSDDrawGridChrV2Cmd_t; + typedef struct frskyOSDState_s { struct { @@ -255,6 +275,11 @@ static uint8_t frskyOSDChecksum(uint8_t crc, uint8_t c) return crc8_dvb_s2(crc, c); } +static bool frskyOSDSpeaksV2(void) +{ + return state.info.major >= 2 || (state.info.major == 1 && state.info.minor >= 99); +} + static void frskyOSDResetReceiveBuffer(void) { state.recvBuffer.state = RECV_STATE_NONE; @@ -675,7 +700,18 @@ unsigned frskyOSDGetPixelHeight(void) return state.info.viewport.height; } -static void frskyOSDSendCharInGrid(unsigned x, unsigned y, uint16_t chr, textAttributes_t attr) +static void frskyOSDSendAsyncBlobCommand(uint8_t cmd, const void *header, size_t headerSize, const void *blob, size_t blobSize) +{ + uint8_t payload[128]; + + memcpy(payload, header, headerSize); + + int uvarintSize = uvarintEncode(blobSize, &payload[headerSize], sizeof(payload) - headerSize); + memcpy(&payload[headerSize + uvarintSize], blob, blobSize); + frskyOSDSendAsyncCommand(cmd, payload, headerSize + uvarintSize + blobSize); +} + +static void frskyOSDSendCharInGrid_V1(unsigned x, unsigned y, uint16_t chr, textAttributes_t attr) { uint8_t payload[] = { x, @@ -687,15 +723,53 @@ static void frskyOSDSendCharInGrid(unsigned x, unsigned y, uint16_t chr, textAtt frskyOSDSendAsyncCommand(OSD_CMD_DRAW_GRID_CHR, payload, sizeof(payload)); } -static void frskyOSDSendAsyncBlobCommand(uint8_t cmd, const void *header, size_t headerSize, const void *blob, size_t blobSize) +static void frskyOSDSendCharInGrid_V2(unsigned x, unsigned y, uint16_t chr, textAttributes_t attr) { - uint8_t payload[128]; + frskyOSDDrawGridChrV2Cmd_t payload = { + .gx = x, + .gy = y, + .chr = chr, + .opts = frskyOSDEncodeAttr(attr), + }; + frskyOSDSendAsyncCommand(OSD_CMD_DRAW_GRID_CHR_2, &payload, sizeof(payload)); +} - memcpy(payload, header, headerSize); +static void frskyOSDSendCharInGrid(unsigned x, unsigned y, uint16_t chr, textAttributes_t attr) +{ + if (frskyOSDSpeaksV2()) { + frskyOSDSendCharInGrid_V2(x, y, chr, attr); + } else { + frskyOSDSendCharInGrid_V1(x, y, chr, attr); + } +} - int uvarintSize = uvarintEncode(blobSize, &payload[headerSize], sizeof(payload) - headerSize); - memcpy(&payload[headerSize + uvarintSize], blob, blobSize); - frskyOSDSendAsyncCommand(cmd, payload, headerSize + uvarintSize + blobSize); +static void frskyOSDSendCharSendStringInGrid_V1(unsigned x, unsigned y, const char *buff, textAttributes_t attr) +{ + frskyOSDDrawGridStrHeaderCmd_t cmd = { + .gx = x, + .gy = y, + .opts = frskyOSDEncodeAttr(attr), + }; + frskyOSDSendAsyncBlobCommand(OSD_CMD_DRAW_GRID_STR, &cmd, sizeof(cmd), buff, strlen(buff) + 1); +} + +static void frskyOSDSendCharSendStringInGrid_V2(unsigned x, unsigned y, const char *buff, textAttributes_t attr) +{ + frskyOSDDrawGridStrV2HeaderCmd_t cmd = { + .gx = x, + .gy = y, + .opts = frskyOSDEncodeAttr(attr), + }; + frskyOSDSendAsyncBlobCommand(OSD_CMD_DRAW_GRID_STR_2, &cmd, sizeof(cmd), buff, strlen(buff)); +} + +static void frskyOSDSendCharSendStringInGrid(unsigned x, unsigned y, const char *buff, textAttributes_t attr) +{ + if (frskyOSDSpeaksV2()) { + frskyOSDSendCharSendStringInGrid_V2(x, y, buff, attr); + } else { + frskyOSDSendCharSendStringInGrid_V1(x, y, buff, attr); + } } void frskyOSDDrawStringInGrid(unsigned x, unsigned y, const char *buff, textAttributes_t attr) @@ -726,12 +800,7 @@ void frskyOSDDrawStringInGrid(unsigned x, unsigned y, const char *buff, textAttr return; } - frskyOSDDrawGridStrHeaderCmd_t cmd; - cmd.gx = x; - cmd.gy = y; - cmd.opts = frskyOSDEncodeAttr(attr); - - frskyOSDSendAsyncBlobCommand(OSD_CMD_DRAW_GRID_STR, &cmd, sizeof(cmd), buff, strlen(buff) + 1); + frskyOSDSendCharSendStringInGrid(x, y, buff, attr); } void frskyOSDDrawCharInGrid(unsigned x, unsigned y, uint16_t chr, textAttributes_t attr) From f50329b44d6f81bf025a4a1960de47256cad74bf Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Tue, 9 Jun 2020 23:27:57 +0100 Subject: [PATCH 065/248] [OSD] Add support for using widgets for drawing Widgets reduce the bandwidth needed to communicate with the OSD dramatically, so for devices connected via UART they allow us to draw way more frequently. --- make/source.mk | 1 + src/main/drivers/display_canvas.c | 5 ++ src/main/drivers/display_canvas.h | 7 ++- src/main/drivers/display_widgets.c | 23 ++++++++ src/main/drivers/display_widgets.h | 54 +++++++++++++++++ src/main/io/displayport_frsky_osd.c | 71 ++++++++++++++++++++++- src/main/io/frsky_osd.c | 90 +++++++++++++++++++++-------- src/main/io/frsky_osd.h | 63 ++++++++++++++++++++ src/main/io/osd_canvas.c | 86 +++++++++++++++++++++++---- 9 files changed, 362 insertions(+), 38 deletions(-) create mode 100644 src/main/drivers/display_widgets.c create mode 100644 src/main/drivers/display_widgets.h diff --git a/make/source.mk b/make/source.mk index 8de6927dc5b..7110593f46a 100644 --- a/make/source.mk +++ b/make/source.mk @@ -51,6 +51,7 @@ MAIN_SRC = \ drivers/display.c \ drivers/display_canvas.c \ drivers/display_font_metadata.c \ + drivers/display_widgets.c \ drivers/exti.c \ drivers/io_pca9685.c \ drivers/io_pcf8574.c \ diff --git a/src/main/drivers/display_canvas.c b/src/main/drivers/display_canvas.c index 1c92bb9df47..67ab5200858 100644 --- a/src/main/drivers/display_canvas.c +++ b/src/main/drivers/display_canvas.c @@ -273,3 +273,8 @@ void displayCanvasContextPop(displayCanvas_t *displayCanvas) displayCanvas->vTable->contextPop(displayCanvas); } } + +bool displayCanvasGetWidgets(displayWidgets_t *widgets, const displayCanvas_t *displayCanvas) +{ + return displayCanvas->vTable->getWidgets ? displayCanvas->vTable->getWidgets(widgets, displayCanvas) : false; +} diff --git a/src/main/drivers/display_canvas.h b/src/main/drivers/display_canvas.h index 7676453059d..7abff66d329 100644 --- a/src/main/drivers/display_canvas.h +++ b/src/main/drivers/display_canvas.h @@ -29,6 +29,8 @@ #include #include +typedef struct displayWidgets_s displayWidgets_t; + typedef enum { DISPLAY_CANVAS_BITMAP_OPT_INVERT_COLORS = 1 << 0, DISPLAY_CANVAS_BITMAP_OPT_SOLID_BACKGROUND = 1 << 1, @@ -100,8 +102,9 @@ typedef struct displayCanvasVTable_s { void (*contextPush)(displayCanvas_t *displayCanvas); void (*contextPop)(displayCanvas_t *displayCanvas); -} displayCanvasVTable_t; + bool (*getWidgets)(displayWidgets_t *widgets, const displayCanvas_t *displayCanvas); +} displayCanvasVTable_t; void displayCanvasSetStrokeColor(displayCanvas_t *displayCanvas, displayCanvasColor_e color); void displayCanvasSetFillColor(displayCanvas_t *displayCanvas, displayCanvasColor_e color); @@ -141,3 +144,5 @@ void displayCanvasCtmRotate(displayCanvas_t *displayCanvas, float r); void displayCanvasContextPush(displayCanvas_t *displayCanvas); void displayCanvasContextPop(displayCanvas_t *displayCanvas); + +bool displayCanvasGetWidgets(displayWidgets_t *widgets, const displayCanvas_t *displayCanvas); diff --git a/src/main/drivers/display_widgets.c b/src/main/drivers/display_widgets.c new file mode 100644 index 00000000000..dafaff734dd --- /dev/null +++ b/src/main/drivers/display_widgets.c @@ -0,0 +1,23 @@ + +#include "platform.h" + +#if defined(USE_CANVAS) + +#include "drivers/display_widgets.h" + +int displayWidgetsSupportedInstances(displayWidgets_t *widgets, displayWidgetType_e widgetType) +{ + return widgets->vTable->supportedInstances ? widgets->vTable->supportedInstances(widgets, widgetType) : 0; +} + +bool displayWidgetsConfigureAHI(displayWidgets_t *widgets, unsigned instance, const widgetAHIConfiguration_t *config) +{ + return widgets->vTable->configureAHI ? widgets->vTable->configureAHI(widgets, instance, config) : false; +} + +bool displayWidgetsDrawAHI(displayWidgets_t *widgets, unsigned instance, const widgetAHIData_t *data) +{ + return widgets->vTable->drawAHI ? widgets->vTable->drawAHI(widgets, instance, data) : false; +} + +#endif diff --git a/src/main/drivers/display_widgets.h b/src/main/drivers/display_widgets.h new file mode 100644 index 00000000000..ff08eb6dc21 --- /dev/null +++ b/src/main/drivers/display_widgets.h @@ -0,0 +1,54 @@ +#pragma once + +#include + +typedef struct widgetRect_s { + int x; + int y; + unsigned w; + unsigned h; +} widgetRect_t; + +typedef enum { + DISPLAY_WIDGET_TYPE_AHI, + DISPLAY_WIDGET_TYPE_SIDEBAR, +} displayWidgetType_e; + +typedef enum { + DISPLAY_WIDGET_AHI_STYLE_STAIRCASE = 0, + DISPLAY_WIDGET_AHI_STYLE_LINE = 1, +} widgetAHIStyle_e; + +typedef enum { + DISPLAY_WIDGET_AHI_OPTION_SHOW_CORNERS = 1 << 0, +} widgetAHIOptions_t; + +typedef struct widgetAHIConfiguration_s { + widgetRect_t rect; + widgetAHIStyle_e style; + widgetAHIOptions_t options; + unsigned crosshairMargin; + unsigned strokeWidth; +} widgetAHIConfiguration_t; + +typedef struct widgetAHIData_s { + float pitch; // radians + float roll; // radians +} widgetAHIData_t; + +typedef struct displayWidgetsVTable_s displayWidgetsVTable_t; + +typedef struct displayWidgets_s { + const displayWidgetsVTable_t *vTable; + void *device; +} displayWidgets_t; + +typedef struct displayWidgetsVTable_s { + int (*supportedInstances)(displayWidgets_t *widgets, displayWidgetType_e widgetType); + bool (*configureAHI)(displayWidgets_t *widgets, unsigned instance, const widgetAHIConfiguration_t *config); + bool (*drawAHI)(displayWidgets_t *widgets, unsigned instance, const widgetAHIData_t *data); +} displayWidgetsVTable_t; + +int displayWidgetsSupportedInstances(displayWidgets_t *widgets, displayWidgetType_e widgetType); +bool displayWidgetsConfigureAHI(displayWidgets_t *widgets, unsigned instance, const widgetAHIConfiguration_t *config); +bool displayWidgetsDrawAHI(displayWidgets_t *widgets, unsigned instance, const widgetAHIData_t *data); diff --git a/src/main/io/displayport_frsky_osd.c b/src/main/io/displayport_frsky_osd.c index f5b02d6a50d..c5c022027a4 100644 --- a/src/main/io/displayport_frsky_osd.c +++ b/src/main/io/displayport_frsky_osd.c @@ -22,11 +22,13 @@ #if defined(USE_FRSKYOSD) +#include "common/maths.h" #include "common/utils.h" #include "drivers/display.h" #include "drivers/display_canvas.h" #include "drivers/display_font_metadata.h" +#include "drivers/display_widgets.h" #include "io/displayport_frsky_osd.h" #include "io/frsky_osd.h" @@ -444,6 +446,70 @@ static void contextPop(displayCanvas_t *displayCanvas) frskyOSDContextPop(); } +static int supportedInstances(displayWidgets_t *widgets, displayWidgetType_e widgetType) +{ + UNUSED(widgets); + + if (frskyOSDSupportsWidgets()) { + switch (widgetType) { + case DISPLAY_WIDGET_TYPE_AHI: + return 1; + case DISPLAY_WIDGET_TYPE_SIDEBAR: + return FRSKY_OSD_WIDGET_ID_SIDEBAR_LAST - FRSKY_OSD_WIDGET_ID_SIDEBAR_FIRST + 1; + } + } + return 0; +} + +static bool configureAHI(displayWidgets_t *widgets, unsigned instance, const widgetAHIConfiguration_t *config) +{ + UNUSED(widgets); + + if (frskyOSDSupportsWidgets() && instance == 0) { + frskyOSDWidgetAHIConfig_t cfg = { + .rect.origin.x = config->rect.x, + .rect.origin.y = config->rect.y, + .rect.size.w = config->rect.w, + .rect.size.h = config->rect.h, + .style = config->style, + .options = config->options, + .crosshairMargin = config->crosshairMargin, + .strokeWidth = config->strokeWidth, + }; + return frskyOSDSetWidgetConfig(FRSKY_OSD_WIDGET_ID_AHI, &cfg, sizeof(cfg)); + } + return false; +} + +static bool drawAHI(displayWidgets_t *widgets, unsigned instance, const widgetAHIData_t *data) +{ + UNUSED(widgets); + + if (frskyOSDSupportsWidgets() && instance == 0) { + frskyOSDWidgetAHIData_t ahiData = { + .pitch = frskyOSDQuantize(data->pitch, 0, 2 * M_PIf, 12), + .roll = frskyOSDQuantize(data->roll, 0, 2 * M_PIf, 12), + }; + return frskyOSDDrawWidget(FRSKY_OSD_WIDGET_ID_AHI, &ahiData, sizeof(ahiData)); + } + return false; +} + +static const displayWidgetsVTable_t frskyOSDWidgetsVTable = { + .supportedInstances = supportedInstances, + .configureAHI = configureAHI, + .drawAHI = drawAHI, +}; + +static bool getWidgets(displayWidgets_t *widgets, const displayCanvas_t *displayCanvas) +{ + if (frskyOSDSupportsWidgets()) { + widgets->device = displayCanvas->device; + widgets->vTable = &frskyOSDWidgetsVTable; + return true; + } + return false; +} static const displayCanvasVTable_t frskyOSDCanvasVTable = { .setStrokeColor = setStrokeColor, @@ -484,12 +550,13 @@ static const displayCanvasVTable_t frskyOSDCanvasVTable = { .contextPush = contextPush, .contextPop = contextPop, + + .getWidgets = getWidgets, }; static bool getCanvas(displayCanvas_t *canvas, const displayPort_t *instance) { - UNUSED(instance); - + canvas->device = instance->device; canvas->vTable = &frskyOSDCanvasVTable; canvas->width = frskyOSDGetPixelWidth(); canvas->height = frskyOSDGetPixelHeight(); diff --git a/src/main/io/frsky_osd.c b/src/main/io/frsky_osd.c index a8551523fa1..edebe8ec6f3 100644 --- a/src/main/io/frsky_osd.c +++ b/src/main/io/frsky_osd.c @@ -116,6 +116,10 @@ typedef enum OSD_CMD_DRAW_GRID_STR = 111, OSD_CMD_DRAW_GRID_CHR_2 = 112, // API2 OSD_CMD_DRAW_GRID_STR_2 = 113, // API2 + + OSD_CMD_WIDGET_SET_CONFIG = 115, // API2 + OSD_CMD_WIDGET_DRAW = 116, // API2 + OSD_CMD_WIDGET_ERASE = 117, // API2 } osdCommand_e; typedef enum { @@ -166,28 +170,13 @@ typedef struct frskyOSDDrawGridStrHeaderCmd_s { } __attribute__((packed)) frskyOSDDrawGridStrHeaderCmd_t; typedef struct frskyOSDDrawGridStrV2HeaderCmd_s { - uint8_t gx : 5; // +5 = 5 - uint8_t gy : 4; // +4 = 9 - uint8_t opts : 7; // +7 = 16 = 2 bytes + unsigned gx : 5; // +5 = 5 + unsigned gy : 4; // +4 = 9 + unsigned opts : 7; // +7 = 16 = 2 bytes // uvarint with size and blob folow // string IS NOT null terminated } __attribute__((packed)) frskyOSDDrawGridStrV2HeaderCmd_t; -typedef struct frskyOSDPoint_s { - int x : 12; - int y : 12; -} __attribute__((packed)) frskyOSDPoint_t; - -typedef struct frskyOSDSize_s { - int w : 12; - int h : 12; -} __attribute__((packed)) frskyOSDSize_t; - -typedef struct frskyOSDRect_s { - frskyOSDPoint_t origin; - frskyOSDSize_t size; -} __attribute__((packed)) frskyOSDRect_t; - typedef struct frskyOSDTriangle_s { frskyOSDPoint_t p1; frskyOSDPoint_t p2; @@ -225,13 +214,18 @@ typedef struct frskyOSDDrawStrMaskCommandHeaderCmd_s { typedef struct frskyOSDDrawGridChrV2Cmd_s { - uint8_t gx : 5; // +5 = 5 - uint8_t gy : 4; // +4 = 9 - uint16_t chr : 9; // +9 = 18 - uint8_t opts : 4; // +4 = 22 from osd_bitmap_opt_t - uint8_t reserved : 2; // +2 = 24 = 3 bytes + unsigned gx : 5; // +5 = 5 + unsigned gy : 4; // +4 = 9 + unsigned chr : 9; // +9 = 18 + unsigned opts : 4; // +4 = 22 from osd_bitmap_opt_t + unsigned reserved : 2; // +2 = 24 = 3 bytes } __attribute__((packed)) frskyOSDDrawGridChrV2Cmd_t; +typedef struct frskyOSDError_s { + uint8_t command; + int8_t code; +} frskyOSDError_t; + typedef struct frskyOSDState_s { struct { @@ -265,6 +259,7 @@ typedef struct frskyOSDState_s { } recvOsdCharacter; serialPort_t *port; bool initialized; + frskyOSDError_t error; timeMs_t nextInfoRequest; } frskyOSDState_t; @@ -398,10 +393,15 @@ static bool frskyOSDHandleCommand(osdCommand_e cmd, const void *payload, size_t { const uint8_t *ptr = payload; + state.error.command = 0; + state.error.code = 0; + switch (cmd) { case OSD_CMD_RESPONSE_ERROR: { if (size >= 2) { + state.error.command = *ptr; + state.error.code = *(ptr + 1); FRSKY_OSD_ERROR("Received an error %02x in response to command %u", *(ptr + 1), *ptr); return true; } @@ -456,6 +456,10 @@ static bool frskyOSDHandleCommand(osdCommand_e cmd, const void *payload, size_t // We only wait for the confirmation, we're not interested in the data return true; } + case OSD_CMD_WIDGET_SET_CONFIG: + { + return true; + } default: break; } @@ -1056,5 +1060,45 @@ void frskyOSDContextPop(void) frskyOSDSendAsyncCommand(OSD_CMD_CONTEXT_POP, NULL, 0); } +bool frskyOSDSupportsWidgets(void) +{ + return frskyOSDSpeaksV2(); +} + +bool frskyOSDSetWidgetConfig(frskyOSDWidgetID_e widget, const void *config, size_t configSize) +{ + if (!frskyOSDSupportsWidgets()) { + return false; + } + + uint8_t buffer[configSize + 1]; + buffer[0] = widget; + memcpy(buffer + 1, config, configSize); + bool ok = frskyOSDSendSyncCommand(OSD_CMD_WIDGET_SET_CONFIG, buffer, sizeof(buffer), 500); + return ok && state.error.code == 0; +} + +bool frskyOSDDrawWidget(frskyOSDWidgetID_e widget, const void *data, size_t dataSize) +{ + if (!frskyOSDSupportsWidgets()) { + return false; + } + + uint8_t buffer[dataSize + 1]; + buffer[0] = widget; + memcpy(buffer + 1, data, dataSize); + frskyOSDSendAsyncCommand(OSD_CMD_WIDGET_DRAW, buffer, sizeof(buffer)); + return true; +} + +uint32_t frskyOSDQuantize(float val, float min, float max, int bits) +{ + if (val < min) { + val = max - (min - val); + } else if (val > max) { + val = min + (val - max); + } + return (val * (1 << bits)) / max; +} #endif diff --git a/src/main/io/frsky_osd.h b/src/main/io/frsky_osd.h index f5975f1c157..130e9cac227 100644 --- a/src/main/io/frsky_osd.h +++ b/src/main/io/frsky_osd.h @@ -26,6 +26,63 @@ typedef enum { FRSKY_OSD_OUTLINE_TYPE_LEFT = 1 << 3, } frskyOSDLineOutlineType_e; +typedef enum +{ + FRSKY_OSD_WIDGET_ID_AHI = 0, + + FRSKY_OSD_WIDGET_ID_SIDEBAR_0 = 1, + FRSKY_OSD_WIDGET_ID_SIDEBAR_1 = 2, + + FRSKY_OSD_WIDGET_ID_GRAPH_0 = 3, + FRSKY_OSD_WIDGET_ID_GRAPH_1 = 4, + FRSKY_OSD_WIDGET_ID_GRAPH_2 = 5, + FRSKY_OSD_WIDGET_ID_GRAPH_3 = 6, + + FRSKY_OSD_WIDGET_ID_CHARGAUGE_0 = 7, + FRSKY_OSD_WIDGET_ID_CHARGAUGE_1 = 8, + FRSKY_OSD_WIDGET_ID_CHARGAUGE_2 = 9, + FRSKY_OSD_WIDGET_ID_CHARGAUGE_3 = 10, + + FRSKY_OSD_WIDGET_ID_SIDEBAR_FIRST = FRSKY_OSD_WIDGET_ID_SIDEBAR_0, + FRSKY_OSD_WIDGET_ID_SIDEBAR_LAST = FRSKY_OSD_WIDGET_ID_SIDEBAR_1, + + FRSKY_OSD_WIDGET_ID_GRAPH_FIRST = FRSKY_OSD_WIDGET_ID_GRAPH_0, + FRSKY_OSD_WIDGET_ID_GRAPH_LAST = FRSKY_OSD_WIDGET_ID_GRAPH_3, + + FRSKY_OSD_WIDGET_ID_CHARGAUGE_FIRST = FRSKY_OSD_WIDGET_ID_CHARGAUGE_0, + FRSKY_OSD_WIDGET_ID_CHARGAUGE_LAST = FRSKY_OSD_WIDGET_ID_CHARGAUGE_3, +} frskyOSDWidgetID_e; + +typedef struct frskyOSDPoint_s { + int x : 12; + int y : 12; +} __attribute__((packed)) frskyOSDPoint_t; + +typedef struct frskyOSDSize_s { + int w : 12; + int h : 12; +} __attribute__((packed)) frskyOSDSize_t; + +typedef struct frskyOSDRect_s { + frskyOSDPoint_t origin; + frskyOSDSize_t size; +} __attribute__((packed)) frskyOSDRect_t; + +typedef struct frskyOSDWidgetAHIData_s +{ + uint16_t pitch : 12; + uint16_t roll : 12; +} __attribute__((packed)) frskyOSDWidgetAHIData_t; + +typedef struct frskyOSDWidgetAHIConfigData_s +{ + frskyOSDRect_t rect; + uint8_t style; + uint8_t options; + uint8_t crosshairMargin; + uint8_t strokeWidth; +} __attribute__((packed)) frskyOSDWidgetAHIConfig_t; + bool frskyOSDInit(videoSystem_e videoSystem); bool frskyOSDIsReady(void); void frskyOSDUpdate(void); @@ -84,3 +141,9 @@ void frskyOSDCtmRotate(float r); void frskyOSDContextPush(void); void frskyOSDContextPop(void); + +bool frskyOSDSupportsWidgets(void); +bool frskyOSDSetWidgetConfig(frskyOSDWidgetID_e widget, const void *config, size_t configSize); +bool frskyOSDDrawWidget(frskyOSDWidgetID_e widget, const void *data, size_t dataSize); + +uint32_t frskyOSDQuantize(float val, float min, float max, int bits); diff --git a/src/main/io/osd_canvas.c b/src/main/io/osd_canvas.c index 4d42b6daf4f..d6c5741e1ee 100644 --- a/src/main/io/osd_canvas.c +++ b/src/main/io/osd_canvas.c @@ -41,6 +41,7 @@ #include "drivers/display.h" #include "drivers/display_canvas.h" +#include "drivers/display_widgets.h" #include "drivers/osd.h" #include "drivers/osd_symbols.h" #include "drivers/time.h" @@ -300,6 +301,63 @@ void osdDrawArtificialHorizonLine(displayCanvas_t *canvas, float pitchAngle, flo displayCanvasContextPop(canvas); } +static bool osdCanvasDrawArtificialHorizonWidget(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, float pitchAngle, float rollAngle) +{ + UNUSED(display); + UNUSED(p); + + const int instance = 0; + static int iterations = 0; + static bool configured = false; + + displayWidgets_t widgets; + if (displayCanvasGetWidgets(&widgets, canvas) && + displayWidgetsSupportedInstances(&widgets, DISPLAY_WIDGET_TYPE_AHI) >= instance) { + + int ahiWidth = OSD_AHI_WIDTH * canvas->gridElementWidth; + int ahiX = (canvas->width - ahiWidth) / 2; + int ahiHeight = OSD_AHI_HEIGHT * canvas->gridElementHeight; + int ahiY = (canvas->height - ahiHeight) / 2; + if (!configured) { + widgetAHIStyle_e ahiStyle = 0; + switch ((osd_ahi_style_e)osdConfig()->osd_ahi_style) { + case OSD_AHI_STYLE_DEFAULT: + ahiStyle = DISPLAY_WIDGET_AHI_STYLE_STAIRCASE; + break; + case OSD_AHI_STYLE_LINE: + ahiStyle = DISPLAY_WIDGET_AHI_STYLE_LINE; + break; + } + widgetAHIConfiguration_t config = { + .rect.x = ahiX, + .rect.y = ahiY, + .rect.w = ahiWidth, + .rect.h = ahiHeight, + .style = ahiStyle, + .options = 0, + .crosshairMargin = AHI_CROSSHAIR_MARGIN, + .strokeWidth = 1, + }; + if (!displayWidgetsConfigureAHI(&widgets, instance, &config)) { + return false; + } + configured = true; + } + widgetAHIData_t data = { + .pitch = pitchAngle, + .roll = rollAngle, + }; + if (displayWidgetsDrawAHI(&widgets, instance, &data)) { + if (++iterations == 10) { + iterations = 0; + osdGridBufferClearPixelRect(canvas, ahiX, ahiY, ahiWidth, ahiHeight); + } + return true; + } + } + return false; +} + void osdCanvasDrawArtificialHorizon(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, float pitchAngle, float rollAngle) { UNUSED(display); @@ -314,20 +372,24 @@ void osdCanvasDrawArtificialHorizon(displayPort_t *display, displayCanvas_t *can float totalError = fabsf(prevPitchAngle - pitchAngle) + fabsf(prevRollAngle - rollAngle); if ((now > nextDrawMinMs && totalError > 0.05f)|| now > nextDrawMaxMs) { - switch ((osd_ahi_style_e)osdConfig()->osd_ahi_style) { - case OSD_AHI_STYLE_DEFAULT: - { - int x, y, w, h; - osdArtificialHorizonRect(canvas, &x, &y, &w, &h); - displayCanvasClearRect(canvas, x, y, w, h); - osdDrawArtificialHorizonShapes(canvas, pitchAngle, rollAngle); - break; + + if (!osdCanvasDrawArtificialHorizonWidget(display, canvas, p, pitchAngle, rollAngle)) { + switch ((osd_ahi_style_e)osdConfig()->osd_ahi_style) { + case OSD_AHI_STYLE_DEFAULT: + { + int x, y, w, h; + osdArtificialHorizonRect(canvas, &x, &y, &w, &h); + displayCanvasClearRect(canvas, x, y, w, h); + osdDrawArtificialHorizonShapes(canvas, pitchAngle, rollAngle); + break; + } + case OSD_AHI_STYLE_LINE: + osdDrawArtificialHorizonLine(canvas, prevPitchAngle, prevRollAngle, true); + osdDrawArtificialHorizonLine(canvas, pitchAngle, rollAngle, false); + break; } - case OSD_AHI_STYLE_LINE: - osdDrawArtificialHorizonLine(canvas, prevPitchAngle, prevRollAngle, true); - osdDrawArtificialHorizonLine(canvas, pitchAngle, rollAngle, false); - break; } + prevPitchAngle = pitchAngle; prevRollAngle = rollAngle; nextDrawMinMs = now + AHI_MIN_DRAW_INTERVAL_MS; From e786889c86b05f6711cc687ed3742e732441ca0a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Tue, 9 Jun 2020 23:58:52 +0100 Subject: [PATCH 066/248] [OSD] Split OSD configuration into osdConfig_t and osdLayoutsConfig_t osdLayoutsConfig_t stores the config for the layouts, with the visible items and their positions. osdLayoutsConfig_t stores the rest. --- src/main/cms/cms_menu_osd.c | 4 +- src/main/config/parameter_group_ids.h | 3 +- src/main/fc/cli.c | 14 +- src/main/fc/fc_msp.c | 10 +- src/main/io/osd.c | 347 +++++++++++++------------- src/main/io/osd.h | 6 +- src/main/io/osd_dji_hd.c | 2 +- 7 files changed, 197 insertions(+), 189 deletions(-) diff --git a/src/main/cms/cms_menu_osd.c b/src/main/cms/cms_menu_osd.c index 33eab416707..dceb87da6b3 100755 --- a/src/main/cms/cms_menu_osd.c +++ b/src/main/cms/cms_menu_osd.c @@ -75,7 +75,7 @@ static long cmsx_osdElementOnChange(displayPort_t *displayPort, const void *ptr) { UNUSED(ptr); - uint16_t *pos = &osdConfigMutable()->item_pos[osdCurrentLayout][osdCurrentItem]; + uint16_t *pos = &osdLayoutsConfigMutable()->item_pos[osdCurrentLayout][osdCurrentItem]; *pos = OSD_POS(osdCurrentElementColumn, osdCurrentElementRow); if (osdCurrentElementVisible) { *pos |= OSD_VISIBLE_FLAG; @@ -125,7 +125,7 @@ static CMS_Menu cmsx_menuOsdElementActions = { static long osdElemActionsOnEnter(const OSD_Entry *from) { osdCurrentItem = from->itemId; - uint16_t pos = osdConfig()->item_pos[osdCurrentLayout][osdCurrentItem]; + uint16_t pos = osdLayoutsConfig()->item_pos[osdCurrentLayout][osdCurrentItem]; osdCurrentElementColumn = OSD_X(pos); osdCurrentElementRow = OSD_Y(pos); osdCurrentElementVisible = OSD_VISIBLE(pos) ? 1 : 0; diff --git a/src/main/config/parameter_group_ids.h b/src/main/config/parameter_group_ids.h index c07afcb82fb..078352ce746 100644 --- a/src/main/config/parameter_group_ids.h +++ b/src/main/config/parameter_group_ids.h @@ -112,7 +112,8 @@ #define PG_RPM_FILTER_CONFIG 1022 #define PG_GLOBAL_VARIABLE_CONFIG 1023 #define PG_SMARTPORT_MASTER_CONFIG 1024 -#define PG_INAV_END 1024 +#define PG_OSD_LAYOUTS_CONFIG 1025 +#define PG_INAV_END 1025 // OSD configuration (subject to change) //#define PG_OSD_FONT_CONFIG 2047 diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index f9233eb7120..b4c964f3ec4 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -2221,7 +2221,7 @@ static void cliFlashRead(char *cmdline) #endif #ifdef USE_OSD -static void printOsdLayout(uint8_t dumpMask, const osdConfig_t *osdConfig, const osdConfig_t *osdConfigDefault, int layout, int item) +static void printOsdLayout(uint8_t dumpMask, const osdLayoutsConfig_t *config, const osdLayoutsConfig_t *configDefault, int layout, int item) { // " " const char *format = "osd_layout %d %d %d %d %c"; @@ -2229,8 +2229,8 @@ static void printOsdLayout(uint8_t dumpMask, const osdConfig_t *osdConfig, const if (layout >= 0 && layout != ii) { continue; } - const uint16_t *layoutItems = osdConfig->item_pos[ii]; - const uint16_t *defaultLayoutItems = osdConfigDefault->item_pos[ii]; + const uint16_t *layoutItems = config->item_pos[ii]; + const uint16_t *defaultLayoutItems = configDefault->item_pos[ii]; for (int jj = 0; jj < OSD_ITEM_COUNT; jj++) { if (item >= 0 && item != jj) { continue; @@ -2322,15 +2322,15 @@ static void cliOsdLayout(char *cmdline) // No args, or just layout or layout and item. If any of them not provided, // it will be the -1 that we used during initialization, so printOsdLayout() // won't use them for filtering. - printOsdLayout(DUMP_MASTER, osdConfig(), osdConfig(), layout, item); + printOsdLayout(DUMP_MASTER, osdLayoutsConfig(), osdLayoutsConfig(), layout, item); break; case 4: // No visibility provided. Keep the previous one. - visible = OSD_VISIBLE(osdConfig()->item_pos[layout][item]); + visible = OSD_VISIBLE(osdLayoutsConfig()->item_pos[layout][item]); FALLTHROUGH; case 5: // Layout, item, pos and visibility. Set the item. - osdConfigMutable()->item_pos[layout][item] = OSD_POS(col, row) | (visible ? OSD_VISIBLE_FLAG : 0); + osdLayoutsConfigMutable()->item_pos[layout][item] = OSD_POS(col, row) | (visible ? OSD_VISIBLE_FLAG : 0); break; default: // Unhandled @@ -3380,7 +3380,7 @@ static void printConfig(const char *cmdline, bool doDiff) #ifdef USE_OSD cliPrintHashLine("osd_layout"); - printOsdLayout(dumpMask, &osdConfig_Copy, osdConfig(), -1, -1); + printOsdLayout(dumpMask, &osdLayoutsConfig_Copy, osdLayoutsConfig(), -1, -1); #endif cliPrintHashLine("master"); diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index dd7528f0fb3..5393e000c01 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -1105,7 +1105,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU16(dst, osdConfig()->dist_alarm); sbufWriteU16(dst, osdConfig()->neg_alt_alarm); for (int i = 0; i < OSD_ITEM_COUNT; i++) { - sbufWriteU16(dst, osdConfig()->item_pos[0][i]); + sbufWriteU16(dst, osdLayoutsConfig()->item_pos[0][i]); } #else sbufWriteU8(dst, OSD_DRIVER_NONE); // OSD not supported @@ -2308,7 +2308,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) } else { // set a position setting if ((dataSize >= 3) && (tmp_u8 < OSD_ITEM_COUNT)) // tmp_u8 == addr - osdConfigMutable()->item_pos[0][tmp_u8] = sbufReadU16(src); + osdLayoutsConfigMutable()->item_pos[0][tmp_u8] = sbufReadU16(src); else return MSP_RESULT_ERROR; } @@ -2755,7 +2755,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) if (!sbufReadU8Safe(&item, src)) { return MSP_RESULT_ERROR; } - if (!sbufReadU16Safe(&osdConfigMutable()->item_pos[layout][item], src)) { + if (!sbufReadU16Safe(&osdLayoutsConfigMutable()->item_pos[layout][item], src)) { return MSP_RESULT_ERROR; } // If the layout is not already overriden and it's different @@ -3175,11 +3175,11 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu *ret = MSP_RESULT_ERROR; break; } - sbufWriteU16(dst, osdConfig()->item_pos[layout][item]); + sbufWriteU16(dst, osdLayoutsConfig()->item_pos[layout][item]); } else { // Asking for an specific layout for (unsigned ii = 0; ii < OSD_ITEM_COUNT; ii++) { - sbufWriteU16(dst, osdConfig()->item_pos[layout][ii]); + sbufWriteU16(dst, osdLayoutsConfig()->item_pos[layout][ii]); } } } else { diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 2c4db39b58e..6b16fc12c6d 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -199,7 +199,8 @@ static bool osdDisplayHasCanvas; #define AH_SIDEBAR_WIDTH_POS 7 #define AH_SIDEBAR_HEIGHT_POS 3 -PG_REGISTER_WITH_RESET_FN(osdConfig_t, osdConfig, PG_OSD_CONFIG, 12); +PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 13); +PG_REGISTER_WITH_RESET_FN(osdLayoutsConfig_t, osdLayoutsConfig, PG_OSD_LAYOUTS_CONFIG, 0); static int digitCount(int32_t value) { @@ -1264,7 +1265,7 @@ static void osdDisplayAdjustableDecimalValue(uint8_t elemPosX, uint8_t elemPosY, static bool osdDrawSingleElement(uint8_t item) { - uint16_t pos = osdConfig()->item_pos[currentLayout][item]; + uint16_t pos = osdLayoutsConfig()->item_pos[currentLayout][item]; if (!OSD_VISIBLE(pos)) { return false; } @@ -2603,197 +2604,199 @@ void osdDrawNextElement(void) osdDrawSingleElement(OSD_ARTIFICIAL_HORIZON); } -void pgResetFn_osdConfig(osdConfig_t *osdConfig) +PG_RESET_TEMPLATE(osdConfig_t, osdConfig, + .rssi_alarm = 20, + .time_alarm = 10, + .alt_alarm = 100, + .dist_alarm = 1000, + .neg_alt_alarm = 5, + .current_alarm = 0, + .imu_temp_alarm_min = -200, + .imu_temp_alarm_max = 600, + .esc_temp_alarm_min = -200, + .esc_temp_alarm_max = 900, + .gforce_alarm = 5, + .gforce_axis_alarm_min = -5, + .gforce_axis_alarm_max = 5, +#ifdef USE_BARO + .baro_temp_alarm_min = -200, + .baro_temp_alarm_max = 600, +#endif + +#ifdef USE_TEMPERATURE_SENSOR + .temp_label_align = OSD_ALIGN_LEFT, +#endif + + .video_system = VIDEO_SYSTEM_AUTO, + + .ahi_reverse_roll = 0, + .ahi_max_pitch = AH_MAX_PITCH_DEFAULT, + .crosshairs_style = OSD_CROSSHAIRS_STYLE_DEFAULT, + .horizon_offset = 0, + .camera_uptilt = 0, + .camera_fov_h = 135, + .camera_fov_v = 85, + .hud_margin_h = 3, + .hud_margin_v = 3, + .hud_homing = 0, + .hud_homepoint = 0, + .hud_radar_disp = 0, + .hud_radar_range_min = 3, + .hud_radar_range_max = 4000, + .hud_radar_nearest = 0, + .hud_wp_disp = 0, + .left_sidebar_scroll = OSD_SIDEBAR_SCROLL_NONE, + .right_sidebar_scroll = OSD_SIDEBAR_SCROLL_NONE, + .sidebar_scroll_arrows = 0, + + .units = OSD_UNIT_METRIC, + .main_voltage_decimals = 1, + + .estimations_wind_compensation = true, + .coordinate_digits = 9, + + .osd_failsafe_switch_layout = false, + + .plus_code_digits = 11, +); + +void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) { - osdConfig->item_pos[0][OSD_ALTITUDE] = OSD_POS(1, 0) | OSD_VISIBLE_FLAG; - osdConfig->item_pos[0][OSD_MAIN_BATT_VOLTAGE] = OSD_POS(12, 0) | OSD_VISIBLE_FLAG; - osdConfig->item_pos[0][OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE] = OSD_POS(12, 1); + osdLayoutsConfig->item_pos[0][OSD_ALTITUDE] = OSD_POS(1, 0) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_VOLTAGE] = OSD_POS(12, 0) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE] = OSD_POS(12, 1); - osdConfig->item_pos[0][OSD_RSSI_VALUE] = OSD_POS(23, 0) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_RSSI_VALUE] = OSD_POS(23, 0) | OSD_VISIBLE_FLAG; //line 2 - osdConfig->item_pos[0][OSD_HOME_DIST] = OSD_POS(1, 1); - osdConfig->item_pos[0][OSD_TRIP_DIST] = OSD_POS(1, 2); - osdConfig->item_pos[0][OSD_MAIN_BATT_CELL_VOLTAGE] = OSD_POS(12, 1); - osdConfig->item_pos[0][OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE] = OSD_POS(12, 1); - osdConfig->item_pos[0][OSD_GPS_SPEED] = OSD_POS(23, 1); - osdConfig->item_pos[0][OSD_3D_SPEED] = OSD_POS(23, 1); - - osdConfig->item_pos[0][OSD_THROTTLE_POS] = OSD_POS(1, 2) | OSD_VISIBLE_FLAG; - osdConfig->item_pos[0][OSD_THROTTLE_POS_AUTO_THR] = OSD_POS(6, 2); - osdConfig->item_pos[0][OSD_HEADING] = OSD_POS(12, 2); - osdConfig->item_pos[0][OSD_CRUISE_HEADING_ERROR] = OSD_POS(12, 2); - osdConfig->item_pos[0][OSD_CRUISE_HEADING_ADJUSTMENT] = OSD_POS(12, 2); - osdConfig->item_pos[0][OSD_HEADING_GRAPH] = OSD_POS(18, 2); - osdConfig->item_pos[0][OSD_CURRENT_DRAW] = OSD_POS(2, 3) | OSD_VISIBLE_FLAG; - osdConfig->item_pos[0][OSD_MAH_DRAWN] = OSD_POS(1, 4) | OSD_VISIBLE_FLAG; - osdConfig->item_pos[0][OSD_WH_DRAWN] = OSD_POS(1, 5); - osdConfig->item_pos[0][OSD_BATTERY_REMAINING_CAPACITY] = OSD_POS(1, 6); - osdConfig->item_pos[0][OSD_BATTERY_REMAINING_PERCENT] = OSD_POS(1, 7); - osdConfig->item_pos[0][OSD_POWER_SUPPLY_IMPEDANCE] = OSD_POS(1, 8); - - osdConfig->item_pos[0][OSD_EFFICIENCY_MAH_PER_KM] = OSD_POS(1, 5); - osdConfig->item_pos[0][OSD_EFFICIENCY_WH_PER_KM] = OSD_POS(1, 5); - - osdConfig->item_pos[0][OSD_ATTITUDE_ROLL] = OSD_POS(1, 7); - osdConfig->item_pos[0][OSD_ATTITUDE_PITCH] = OSD_POS(1, 8); + osdLayoutsConfig->item_pos[0][OSD_HOME_DIST] = OSD_POS(1, 1); + osdLayoutsConfig->item_pos[0][OSD_TRIP_DIST] = OSD_POS(1, 2); + osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_CELL_VOLTAGE] = OSD_POS(12, 1); + osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE] = OSD_POS(12, 1); + osdLayoutsConfig->item_pos[0][OSD_GPS_SPEED] = OSD_POS(23, 1); + osdLayoutsConfig->item_pos[0][OSD_3D_SPEED] = OSD_POS(23, 1); + + osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS] = OSD_POS(1, 2) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS_AUTO_THR] = OSD_POS(6, 2); + osdLayoutsConfig->item_pos[0][OSD_HEADING] = OSD_POS(12, 2); + osdLayoutsConfig->item_pos[0][OSD_CRUISE_HEADING_ERROR] = OSD_POS(12, 2); + osdLayoutsConfig->item_pos[0][OSD_CRUISE_HEADING_ADJUSTMENT] = OSD_POS(12, 2); + osdLayoutsConfig->item_pos[0][OSD_HEADING_GRAPH] = OSD_POS(18, 2); + osdLayoutsConfig->item_pos[0][OSD_CURRENT_DRAW] = OSD_POS(2, 3) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_MAH_DRAWN] = OSD_POS(1, 4) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_WH_DRAWN] = OSD_POS(1, 5); + osdLayoutsConfig->item_pos[0][OSD_BATTERY_REMAINING_CAPACITY] = OSD_POS(1, 6); + osdLayoutsConfig->item_pos[0][OSD_BATTERY_REMAINING_PERCENT] = OSD_POS(1, 7); + osdLayoutsConfig->item_pos[0][OSD_POWER_SUPPLY_IMPEDANCE] = OSD_POS(1, 8); + + osdLayoutsConfig->item_pos[0][OSD_EFFICIENCY_MAH_PER_KM] = OSD_POS(1, 5); + osdLayoutsConfig->item_pos[0][OSD_EFFICIENCY_WH_PER_KM] = OSD_POS(1, 5); + + osdLayoutsConfig->item_pos[0][OSD_ATTITUDE_ROLL] = OSD_POS(1, 7); + osdLayoutsConfig->item_pos[0][OSD_ATTITUDE_PITCH] = OSD_POS(1, 8); // avoid OSD_VARIO under OSD_CROSSHAIRS - osdConfig->item_pos[0][OSD_VARIO] = OSD_POS(23, 5); + osdLayoutsConfig->item_pos[0][OSD_VARIO] = OSD_POS(23, 5); // OSD_VARIO_NUM at the right of OSD_VARIO - osdConfig->item_pos[0][OSD_VARIO_NUM] = OSD_POS(24, 7); - osdConfig->item_pos[0][OSD_HOME_DIR] = OSD_POS(14, 11); - osdConfig->item_pos[0][OSD_ARTIFICIAL_HORIZON] = OSD_POS(8, 6) | OSD_VISIBLE_FLAG; - osdConfig->item_pos[0][OSD_HORIZON_SIDEBARS] = OSD_POS(8, 6) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_VARIO_NUM] = OSD_POS(24, 7); + osdLayoutsConfig->item_pos[0][OSD_HOME_DIR] = OSD_POS(14, 11); + osdLayoutsConfig->item_pos[0][OSD_ARTIFICIAL_HORIZON] = OSD_POS(8, 6) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_HORIZON_SIDEBARS] = OSD_POS(8, 6) | OSD_VISIBLE_FLAG; - osdConfig->item_pos[0][OSD_CRAFT_NAME] = OSD_POS(20, 2); - osdConfig->item_pos[0][OSD_VTX_CHANNEL] = OSD_POS(8, 6); + osdLayoutsConfig->item_pos[0][OSD_CRAFT_NAME] = OSD_POS(20, 2); + osdLayoutsConfig->item_pos[0][OSD_VTX_CHANNEL] = OSD_POS(8, 6); - osdConfig->item_pos[0][OSD_ONTIME] = OSD_POS(23, 8); - osdConfig->item_pos[0][OSD_FLYTIME] = OSD_POS(23, 9); - osdConfig->item_pos[0][OSD_ONTIME_FLYTIME] = OSD_POS(23, 11) | OSD_VISIBLE_FLAG; - osdConfig->item_pos[0][OSD_RTC_TIME] = OSD_POS(23, 12); - osdConfig->item_pos[0][OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH] = OSD_POS(23, 7); - osdConfig->item_pos[0][OSD_REMAINING_DISTANCE_BEFORE_RTH] = OSD_POS(23, 6); + osdLayoutsConfig->item_pos[0][OSD_ONTIME] = OSD_POS(23, 8); + osdLayoutsConfig->item_pos[0][OSD_FLYTIME] = OSD_POS(23, 9); + osdLayoutsConfig->item_pos[0][OSD_ONTIME_FLYTIME] = OSD_POS(23, 11) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_RTC_TIME] = OSD_POS(23, 12); + osdLayoutsConfig->item_pos[0][OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH] = OSD_POS(23, 7); + osdLayoutsConfig->item_pos[0][OSD_REMAINING_DISTANCE_BEFORE_RTH] = OSD_POS(23, 6); - osdConfig->item_pos[0][OSD_GPS_SATS] = OSD_POS(0, 11) | OSD_VISIBLE_FLAG; - osdConfig->item_pos[0][OSD_GPS_HDOP] = OSD_POS(0, 10); + osdLayoutsConfig->item_pos[0][OSD_GPS_SATS] = OSD_POS(0, 11) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_GPS_HDOP] = OSD_POS(0, 10); - osdConfig->item_pos[0][OSD_GPS_LAT] = OSD_POS(0, 12); + osdLayoutsConfig->item_pos[0][OSD_GPS_LAT] = OSD_POS(0, 12); // Put this on top of the latitude, since it's very unlikely // that users will want to use both at the same time. - osdConfig->item_pos[0][OSD_PLUS_CODE] = OSD_POS(0, 12); - osdConfig->item_pos[0][OSD_FLYMODE] = OSD_POS(13, 12) | OSD_VISIBLE_FLAG; - osdConfig->item_pos[0][OSD_GPS_LON] = OSD_POS(18, 12); - - osdConfig->item_pos[0][OSD_AZIMUTH] = OSD_POS(2, 12); - - osdConfig->item_pos[0][OSD_ROLL_PIDS] = OSD_POS(2, 10); - osdConfig->item_pos[0][OSD_PITCH_PIDS] = OSD_POS(2, 11); - osdConfig->item_pos[0][OSD_YAW_PIDS] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_LEVEL_PIDS] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_POS_XY_PIDS] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_POS_Z_PIDS] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_VEL_XY_PIDS] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_VEL_Z_PIDS] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_HEADING_P] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_BOARD_ALIGN_ROLL] = OSD_POS(2, 10); - osdConfig->item_pos[0][OSD_BOARD_ALIGN_PITCH] = OSD_POS(2, 11); - osdConfig->item_pos[0][OSD_RC_EXPO] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_RC_YAW_EXPO] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_THROTTLE_EXPO] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_PITCH_RATE] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_ROLL_RATE] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_YAW_RATE] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_MANUAL_RC_EXPO] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_MANUAL_RC_YAW_EXPO] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_MANUAL_PITCH_RATE] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_MANUAL_ROLL_RATE] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_MANUAL_YAW_RATE] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_NAV_FW_CRUISE_THR] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_NAV_FW_PITCH2THR] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_FW_ALT_PID_OUTPUTS] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_FW_POS_PID_OUTPUTS] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_MC_VEL_X_PID_OUTPUTS] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_MC_VEL_Y_PID_OUTPUTS] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_MC_VEL_Z_PID_OUTPUTS] = OSD_POS(2, 12); - osdConfig->item_pos[0][OSD_MC_POS_XYZ_P_OUTPUTS] = OSD_POS(2, 12); - - osdConfig->item_pos[0][OSD_POWER] = OSD_POS(15, 1); - - osdConfig->item_pos[0][OSD_IMU_TEMPERATURE] = OSD_POS(19, 2); - osdConfig->item_pos[0][OSD_BARO_TEMPERATURE] = OSD_POS(19, 3); - osdConfig->item_pos[0][OSD_TEMP_SENSOR_0_TEMPERATURE] = OSD_POS(19, 4); - osdConfig->item_pos[0][OSD_TEMP_SENSOR_1_TEMPERATURE] = OSD_POS(19, 5); - osdConfig->item_pos[0][OSD_TEMP_SENSOR_2_TEMPERATURE] = OSD_POS(19, 6); - osdConfig->item_pos[0][OSD_TEMP_SENSOR_3_TEMPERATURE] = OSD_POS(19, 7); - osdConfig->item_pos[0][OSD_TEMP_SENSOR_4_TEMPERATURE] = OSD_POS(19, 8); - osdConfig->item_pos[0][OSD_TEMP_SENSOR_5_TEMPERATURE] = OSD_POS(19, 9); - osdConfig->item_pos[0][OSD_TEMP_SENSOR_6_TEMPERATURE] = OSD_POS(19, 10); - osdConfig->item_pos[0][OSD_TEMP_SENSOR_7_TEMPERATURE] = OSD_POS(19, 11); - - osdConfig->item_pos[0][OSD_AIR_SPEED] = OSD_POS(3, 5); - osdConfig->item_pos[0][OSD_WIND_SPEED_HORIZONTAL] = OSD_POS(3, 6); - osdConfig->item_pos[0][OSD_WIND_SPEED_VERTICAL] = OSD_POS(3, 7); - - osdConfig->item_pos[0][OSD_GFORCE] = OSD_POS(12, 4); - osdConfig->item_pos[0][OSD_GFORCE_X] = OSD_POS(12, 5); - osdConfig->item_pos[0][OSD_GFORCE_Y] = OSD_POS(12, 6); - osdConfig->item_pos[0][OSD_GFORCE_Z] = OSD_POS(12, 7); - - osdConfig->item_pos[0][OSD_VTX_POWER] = OSD_POS(3, 5); + osdLayoutsConfig->item_pos[0][OSD_PLUS_CODE] = OSD_POS(0, 12); + osdLayoutsConfig->item_pos[0][OSD_FLYMODE] = OSD_POS(13, 12) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_GPS_LON] = OSD_POS(18, 12); + + osdLayoutsConfig->item_pos[0][OSD_AZIMUTH] = OSD_POS(2, 12); + + osdLayoutsConfig->item_pos[0][OSD_ROLL_PIDS] = OSD_POS(2, 10); + osdLayoutsConfig->item_pos[0][OSD_PITCH_PIDS] = OSD_POS(2, 11); + osdLayoutsConfig->item_pos[0][OSD_YAW_PIDS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_LEVEL_PIDS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_POS_XY_PIDS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_POS_Z_PIDS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_VEL_XY_PIDS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_VEL_Z_PIDS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_HEADING_P] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_BOARD_ALIGN_ROLL] = OSD_POS(2, 10); + osdLayoutsConfig->item_pos[0][OSD_BOARD_ALIGN_PITCH] = OSD_POS(2, 11); + osdLayoutsConfig->item_pos[0][OSD_RC_EXPO] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_RC_YAW_EXPO] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_THROTTLE_EXPO] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_PITCH_RATE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_ROLL_RATE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_YAW_RATE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MANUAL_RC_EXPO] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MANUAL_RC_YAW_EXPO] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MANUAL_PITCH_RATE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MANUAL_ROLL_RATE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MANUAL_YAW_RATE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_NAV_FW_CRUISE_THR] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_NAV_FW_PITCH2THR] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_FW_ALT_PID_OUTPUTS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_FW_POS_PID_OUTPUTS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MC_VEL_X_PID_OUTPUTS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MC_VEL_Y_PID_OUTPUTS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MC_VEL_Z_PID_OUTPUTS] = OSD_POS(2, 12); + osdLayoutsConfig->item_pos[0][OSD_MC_POS_XYZ_P_OUTPUTS] = OSD_POS(2, 12); + + osdLayoutsConfig->item_pos[0][OSD_POWER] = OSD_POS(15, 1); + + osdLayoutsConfig->item_pos[0][OSD_IMU_TEMPERATURE] = OSD_POS(19, 2); + osdLayoutsConfig->item_pos[0][OSD_BARO_TEMPERATURE] = OSD_POS(19, 3); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_0_TEMPERATURE] = OSD_POS(19, 4); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_1_TEMPERATURE] = OSD_POS(19, 5); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_2_TEMPERATURE] = OSD_POS(19, 6); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_3_TEMPERATURE] = OSD_POS(19, 7); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_4_TEMPERATURE] = OSD_POS(19, 8); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_5_TEMPERATURE] = OSD_POS(19, 9); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_6_TEMPERATURE] = OSD_POS(19, 10); + osdLayoutsConfig->item_pos[0][OSD_TEMP_SENSOR_7_TEMPERATURE] = OSD_POS(19, 11); + + osdLayoutsConfig->item_pos[0][OSD_AIR_SPEED] = OSD_POS(3, 5); + osdLayoutsConfig->item_pos[0][OSD_WIND_SPEED_HORIZONTAL] = OSD_POS(3, 6); + osdLayoutsConfig->item_pos[0][OSD_WIND_SPEED_VERTICAL] = OSD_POS(3, 7); + + osdLayoutsConfig->item_pos[0][OSD_GFORCE] = OSD_POS(12, 4); + osdLayoutsConfig->item_pos[0][OSD_GFORCE_X] = OSD_POS(12, 5); + osdLayoutsConfig->item_pos[0][OSD_GFORCE_Y] = OSD_POS(12, 6); + osdLayoutsConfig->item_pos[0][OSD_GFORCE_Z] = OSD_POS(12, 7); + + osdLayoutsConfig->item_pos[0][OSD_VTX_POWER] = OSD_POS(3, 5); #if defined(USE_ESC_SENSOR) - osdConfig->item_pos[0][OSD_ESC_RPM] = OSD_POS(1, 2); - osdConfig->item_pos[0][OSD_ESC_TEMPERATURE] = OSD_POS(1, 3); + osdLayoutsConfig->item_pos[0][OSD_ESC_RPM] = OSD_POS(1, 2); + osdLayoutsConfig->item_pos[0][OSD_ESC_TEMPERATURE] = OSD_POS(1, 3); #endif #if defined(USE_RX_MSP) && defined(USE_MSP_RC_OVERRIDE) - osdConfig->item_pos[0][OSD_RC_SOURCE] = OSD_POS(3, 4); + osdLayoutsConfig->item_pos[0][OSD_RC_SOURCE] = OSD_POS(3, 4); #endif // Under OSD_FLYMODE. TODO: Might not be visible on NTSC? - osdConfig->item_pos[0][OSD_MESSAGES] = OSD_POS(1, 13) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_MESSAGES] = OSD_POS(1, 13) | OSD_VISIBLE_FLAG; for (unsigned ii = 1; ii < OSD_LAYOUT_COUNT; ii++) { - for (unsigned jj = 0; jj < ARRAYLEN(osdConfig->item_pos[0]); jj++) { - osdConfig->item_pos[ii][jj] = osdConfig->item_pos[0][jj] & ~OSD_VISIBLE_FLAG; - } - } - - osdConfig->rssi_alarm = 20; - osdConfig->time_alarm = 10; - osdConfig->alt_alarm = 100; - osdConfig->dist_alarm = 1000; - osdConfig->neg_alt_alarm = 5; - osdConfig->current_alarm = 0; - osdConfig->imu_temp_alarm_min = -200; - osdConfig->imu_temp_alarm_max = 600; - osdConfig->esc_temp_alarm_min = -200; - osdConfig->esc_temp_alarm_max = 900; - osdConfig->gforce_alarm = 5; - osdConfig->gforce_axis_alarm_min = -5; - osdConfig->gforce_axis_alarm_max = 5; -#ifdef USE_BARO - osdConfig->baro_temp_alarm_min = -200; - osdConfig->baro_temp_alarm_max = 600; -#endif - -#ifdef USE_TEMPERATURE_SENSOR - osdConfig->temp_label_align = OSD_ALIGN_LEFT; -#endif - - osdConfig->video_system = VIDEO_SYSTEM_AUTO; - - osdConfig->ahi_reverse_roll = 0; - osdConfig->ahi_max_pitch = AH_MAX_PITCH_DEFAULT; - osdConfig->crosshairs_style = OSD_CROSSHAIRS_STYLE_DEFAULT; - osdConfig->horizon_offset = 0; - osdConfig->camera_uptilt = 0; - osdConfig->camera_fov_h = 135; - osdConfig->camera_fov_v = 85; - osdConfig->hud_margin_h = 3; - osdConfig->hud_margin_v = 3; - osdConfig->hud_homing = 0; - osdConfig->hud_homepoint = 0; - osdConfig->hud_radar_disp = 0; - osdConfig->hud_radar_range_min = 3; - osdConfig->hud_radar_range_max = 4000; - osdConfig->hud_radar_nearest = 0; - osdConfig->hud_wp_disp = 0; - osdConfig->left_sidebar_scroll = OSD_SIDEBAR_SCROLL_NONE; - osdConfig->right_sidebar_scroll = OSD_SIDEBAR_SCROLL_NONE; - osdConfig->sidebar_scroll_arrows = 0; - - osdConfig->units = OSD_UNIT_METRIC; - osdConfig->main_voltage_decimals = 1; - - osdConfig->estimations_wind_compensation = true; - osdConfig->coordinate_digits = 9; - - osdConfig->osd_failsafe_switch_layout = false; - - osdConfig->plus_code_digits = 11; + for (unsigned jj = 0; jj < ARRAYLEN(osdLayoutsConfig->item_pos[0]); jj++) { + osdLayoutsConfig->item_pos[ii][jj] = osdLayoutsConfig->item_pos[0][jj] & ~OSD_VISIBLE_FLAG; + } + } } static void osdSetNextRefreshIn(uint32_t timeMs) { @@ -3288,7 +3291,7 @@ void osdStartFullRedraw(void) void osdOverrideLayout(int layout, timeMs_t duration) { - layoutOverride = constrain(layout, -1, ARRAYLEN(osdConfig()->item_pos) - 1); + layoutOverride = constrain(layout, -1, ARRAYLEN(osdLayoutsConfig()->item_pos) - 1); if (layoutOverride >= 0 && duration > 0) { layoutOverrideUntil = millis() + duration; } else { diff --git a/src/main/io/osd.h b/src/main/io/osd.h index c641875e602..e345cfc2f57 100755 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -194,10 +194,14 @@ typedef enum { OSD_AHI_STYLE_LINE, } osd_ahi_style_e; -typedef struct osdConfig_s { +typedef struct osdLayoutsConfig_s { // Layouts uint16_t item_pos[OSD_LAYOUT_COUNT][OSD_ITEM_COUNT]; +} osdLayoutsConfig_t; + +PG_DECLARE(osdLayoutsConfig_t, osdLayoutsConfig); +typedef struct osdConfig_s { // Alarms uint8_t rssi_alarm; // rssi % uint16_t time_alarm; // fly minutes diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c index 29b3abf0743..379937d63d5 100644 --- a/src/main/io/osd_dji_hd.c +++ b/src/main/io/osd_dji_hd.c @@ -303,7 +303,7 @@ static void djiSerializeOSDConfigReply(sbuf_t *dst) // Position & visibility encoded in 16 bits. Position encoding is the same between BF/DJI and INAV // However visibility is different. INAV has 3 layouts, while BF only has visibility profiles // Here we use only one OSD layout mapped to first OSD BF profile - uint16_t itemPos = osdConfig()->item_pos[0][inavOSDIdx]; + uint16_t itemPos = osdLayoutsConfig()->item_pos[0][inavOSDIdx]; // Workarounds for certain OSD element positions // INAV calculates these dynamically, while DJI expects the config to have defined coordinates From 3ecd99bb885e4a6416fda84541975a0e2fdbdca2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Wed, 10 Jun 2020 00:21:19 +0100 Subject: [PATCH 067/248] [OSD] Add AHI settings for widget based AHI osd_ahi_bordered: Wether to show a border in the corners osd_ahi_width: Width in pixels osd_ahi_height: Hight in pixels osd_ahi_vertical_offset: Offset from vertical center of the screen --- src/main/fc/settings.yaml | 25 +++++++++++++++++++++++++ src/main/io/osd.c | 4 ++++ src/main/io/osd.h | 5 +++++ src/main/io/osd_canvas.c | 14 ++++++++++---- 4 files changed, 44 insertions(+), 4 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index fcd367dba4b..cab85a143d9 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2836,6 +2836,31 @@ groups: default_value: "DEFAULT" table: osd_ahi_style + - name: osd_ahi_bordered + field: ahi_bordered + type: bool + description: Shows a border/corners around the AHI region (pixel OSD only) + default_value: "OFF" + + - name: osd_ahi_width + field: ahi_width + max: 255 + description: AHI width in pixels (pixel OSD only) + default_value: 132 + + - name: osd_ahi_height + field: ahi_height + max: 255 + description: AHI height in pixels (pixel OSD only) + default_value: 162 + + - name: osd_ahi_vertical_offset + field: ahi_vertical_offset + min: -128 + max: 127 + description: AHI vertical offset from center (pixel OSD only) + default_value: 0 + - name: PG_SYSTEM_CONFIG type: systemConfig_t headers: ["fc/config.h"] diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 6b16fc12c6d..a28f12989cd 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2658,6 +2658,10 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .osd_failsafe_switch_layout = false, .plus_code_digits = 11, + + .ahi_width = OSD_AHI_WIDTH * OSD_CHAR_WIDTH, + .ahi_height = OSD_AHI_HEIGHT * OSD_CHAR_HEIGHT, + .ahi_vertical_offset = -OSD_CHAR_HEIGHT, ); void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) diff --git a/src/main/io/osd.h b/src/main/io/osd.h index e345cfc2f57..9ce97a67301 100755 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -259,6 +259,11 @@ typedef struct osdConfig_s { bool osd_failsafe_switch_layout; uint8_t plus_code_digits; // Number of digits to use in OSD_PLUS_CODE uint8_t osd_ahi_style; + uint8_t ahi_bordered; // Only used by the AHI widget + uint8_t ahi_width; // In pixels, only used by the AHI widget + uint8_t ahi_height; // In pixels, only used by the AHI widget + int8_t ahi_vertical_offset; // Offset from center in pixels. Positive moves the AHI down. Widget only. + } osdConfig_t; PG_DECLARE(osdConfig_t, osdConfig); diff --git a/src/main/io/osd_canvas.c b/src/main/io/osd_canvas.c index d6c5741e1ee..c3dcd5e0532 100644 --- a/src/main/io/osd_canvas.c +++ b/src/main/io/osd_canvas.c @@ -314,10 +314,16 @@ static bool osdCanvasDrawArtificialHorizonWidget(displayPort_t *display, display if (displayCanvasGetWidgets(&widgets, canvas) && displayWidgetsSupportedInstances(&widgets, DISPLAY_WIDGET_TYPE_AHI) >= instance) { - int ahiWidth = OSD_AHI_WIDTH * canvas->gridElementWidth; + int ahiWidth = osdConfig()->ahi_width; int ahiX = (canvas->width - ahiWidth) / 2; - int ahiHeight = OSD_AHI_HEIGHT * canvas->gridElementHeight; - int ahiY = (canvas->height - ahiHeight) / 2; + int ahiHeight = osdConfig()->ahi_height; + int ahiY = ((canvas->height - ahiHeight) / 2) + osdConfig()->ahi_vertical_offset; + if (ahiY < 0) { + ahiY = 0; + } + if (ahiY + ahiHeight >= canvas->height) { + ahiY = canvas->height - ahiHeight - 1; + } if (!configured) { widgetAHIStyle_e ahiStyle = 0; switch ((osd_ahi_style_e)osdConfig()->osd_ahi_style) { @@ -334,7 +340,7 @@ static bool osdCanvasDrawArtificialHorizonWidget(displayPort_t *display, display .rect.w = ahiWidth, .rect.h = ahiHeight, .style = ahiStyle, - .options = 0, + .options = osdConfig()->ahi_bordered ? DISPLAY_WIDGET_AHI_OPTION_SHOW_CORNERS : 0, .crosshairMargin = AHI_CROSSHAIR_MARGIN, .strokeWidth = 1, }; From 6b8f2ba5f1f830a1ba63cb1da101173688642760 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sun, 14 Jun 2020 18:29:27 +0100 Subject: [PATCH 068/248] [OSD] Use sidebar widget for drawing sidebars when available Otherwise fallback to the grid based implementatation --- src/main/drivers/display_widgets.c | 10 ++ src/main/drivers/display_widgets.h | 23 ++++ src/main/drivers/osd.h | 8 ++ src/main/io/displayport_frsky_osd.c | 41 ++++++ src/main/io/frsky_osd.h | 16 ++- src/main/io/osd.c | 117 +--------------- src/main/io/osd_canvas.c | 200 ++++++++++++++++++++++++++++ src/main/io/osd_canvas.h | 1 + src/main/io/osd_common.c | 12 ++ src/main/io/osd_common.h | 4 + src/main/io/osd_grid.c | 123 +++++++++++++++++ src/main/io/osd_grid.h | 1 + 12 files changed, 439 insertions(+), 117 deletions(-) diff --git a/src/main/drivers/display_widgets.c b/src/main/drivers/display_widgets.c index dafaff734dd..a7fbc8e5e63 100644 --- a/src/main/drivers/display_widgets.c +++ b/src/main/drivers/display_widgets.c @@ -20,4 +20,14 @@ bool displayWidgetsDrawAHI(displayWidgets_t *widgets, unsigned instance, const w return widgets->vTable->drawAHI ? widgets->vTable->drawAHI(widgets, instance, data) : false; } +bool displayWidgetsConfigureSidebar(displayWidgets_t *widgets, unsigned instance, const widgetSidebarConfiguration_t *config) +{ + return widgets->vTable->configureSidebar ? widgets->vTable->configureSidebar(widgets, instance, config) : false; +} + +bool displayWidgetsDrawSidebar(displayWidgets_t *widgets, unsigned instance, int32_t data) +{ + return widgets->vTable->drawSidebar ? widgets->vTable->drawSidebar(widgets, instance, data) : false; +} + #endif diff --git a/src/main/drivers/display_widgets.h b/src/main/drivers/display_widgets.h index ff08eb6dc21..9e7c536999a 100644 --- a/src/main/drivers/display_widgets.h +++ b/src/main/drivers/display_widgets.h @@ -1,6 +1,9 @@ #pragma once #include +#include + +#include "drivers/osd.h" typedef struct widgetRect_s { int x; @@ -36,6 +39,22 @@ typedef struct widgetAHIData_s { float roll; // radians } widgetAHIData_t; +typedef enum +{ + DISPLAY_WIDGET_SIDEBAR_OPTION_LEFT = 1 << 0, // Display the sidebar oriented to the left. Default is to the right + DISPLAY_WIDGET_SIDEBAR_OPTION_REVERSE = 1 << 1, // Reverse the sidebar direction, so positive values move it down + DISPLAY_WIDGET_SIDEBAR_OPTION_UNLABELED = 1 << 2, // Don't display the central label with the value. + DISPLAY_WIDGET_SIDEBAR_OPTION_STATIC = 1 << 3, // The sidebar doesn't scroll nor display values along it. +} widgetSidebarOptions_t; + +typedef struct widgetSidebarConfiguration_s { + widgetRect_t rect; + widgetSidebarOptions_t options; + uint8_t divisions; // How many divisions the sidebar will have + uint16_t counts_per_step; // How much the value increases/decreases per division BEFORE applying the unit scale + osdUnit_t unit; // The unit used to display the values in the sidebar +} widgetSidebarConfiguration_t; + typedef struct displayWidgetsVTable_s displayWidgetsVTable_t; typedef struct displayWidgets_s { @@ -47,8 +66,12 @@ typedef struct displayWidgetsVTable_s { int (*supportedInstances)(displayWidgets_t *widgets, displayWidgetType_e widgetType); bool (*configureAHI)(displayWidgets_t *widgets, unsigned instance, const widgetAHIConfiguration_t *config); bool (*drawAHI)(displayWidgets_t *widgets, unsigned instance, const widgetAHIData_t *data); + bool (*configureSidebar)(displayWidgets_t *widgets, unsigned instance, const widgetSidebarConfiguration_t *config); + bool (*drawSidebar)(displayWidgets_t *widgets, unsigned instance, int32_t data); } displayWidgetsVTable_t; int displayWidgetsSupportedInstances(displayWidgets_t *widgets, displayWidgetType_e widgetType); bool displayWidgetsConfigureAHI(displayWidgets_t *widgets, unsigned instance, const widgetAHIConfiguration_t *config); bool displayWidgetsDrawAHI(displayWidgets_t *widgets, unsigned instance, const widgetAHIData_t *data); +bool displayWidgetsConfigureSidebar(displayWidgets_t *widgets, unsigned instance, const widgetSidebarConfiguration_t *config); +bool displayWidgetsDrawSidebar(displayWidgets_t *widgets, unsigned instance, int32_t data); diff --git a/src/main/drivers/osd.h b/src/main/drivers/osd.h index bdbd1508b59..8859325d10b 100644 --- a/src/main/drivers/osd.h +++ b/src/main/drivers/osd.h @@ -61,6 +61,14 @@ typedef struct osdCharacter_s { uint8_t data[OSD_CHAR_BYTES]; } osdCharacter_t; +typedef struct osdUnit_t +{ + uint16_t scale; // The scale between the value and the represented unit. e.g. if you're providing cms but you want to draw meters this should be 100 ([0, 1023]) + uint16_t symbol; // Symbol to append/prepend to the value when it's not scaled [0, 511] + uint16_t divisor; // If abs(value) > divisor, divide it by this. e.g. for meters and km you'd set this to 1000 [0, UINT16_MAX) + uint16_t divided_symbol; // Symbol to append/prepend to the value when it's divided (e.g. the km symbol) [0, 511] +} osdUnit_t; + #define OSD_CHARACTER_GRID_MAX_WIDTH 30 #define OSD_CHARACTER_GRID_MAX_HEIGHT 16 #define OSD_CHARACTER_GRID_BUFFER_SIZE (OSD_CHARACTER_GRID_MAX_WIDTH * OSD_CHARACTER_GRID_MAX_HEIGHT) diff --git a/src/main/io/displayport_frsky_osd.c b/src/main/io/displayport_frsky_osd.c index c5c022027a4..b3571b85224 100644 --- a/src/main/io/displayport_frsky_osd.c +++ b/src/main/io/displayport_frsky_osd.c @@ -495,10 +495,51 @@ static bool drawAHI(displayWidgets_t *widgets, unsigned instance, const widgetAH return false; } +static bool configureSidebar(displayWidgets_t *widgets, unsigned instance, const widgetSidebarConfiguration_t *config) +{ + UNUSED(widgets); + + if (frskyOSDSupportsWidgets()) { + frskyOSDWidgetID_e id = FRSKY_OSD_WIDGET_ID_SIDEBAR_FIRST + instance; + if (id <= FRSKY_OSD_WIDGET_ID_SIDEBAR_LAST) { + frskyOSDWidgetSidebarConfig_t cfg = { + .rect.origin.x = config->rect.x, + .rect.origin.y = config->rect.y, + .rect.size.w = config->rect.w, + .rect.size.h = config->rect.h, + .options = config->options, + .divisions = config->divisions, + .counts_per_step = config->counts_per_step, + .unit = config->unit, + }; + return frskyOSDSetWidgetConfig(id, &cfg, sizeof(cfg)); + } + } + return false; +} + +static bool drawSidebar(displayWidgets_t *widgets, unsigned instance, int32_t data) +{ + UNUSED(widgets); + + if (frskyOSDSupportsWidgets()) { + frskyOSDWidgetID_e id = FRSKY_OSD_WIDGET_ID_SIDEBAR_FIRST + instance; + if (id <= FRSKY_OSD_WIDGET_ID_SIDEBAR_LAST) { + frskyOSDWidgetSidebarData_t sidebarData = { + .value = data, + }; + return frskyOSDDrawWidget(id, &sidebarData, sizeof(sidebarData)); + } + } + return false; +} + static const displayWidgetsVTable_t frskyOSDWidgetsVTable = { .supportedInstances = supportedInstances, .configureAHI = configureAHI, .drawAHI = drawAHI, + .configureSidebar = configureSidebar, + .drawSidebar = drawSidebar, }; static bool getWidgets(displayWidgets_t *widgets, const displayCanvas_t *displayCanvas) diff --git a/src/main/io/frsky_osd.h b/src/main/io/frsky_osd.h index 130e9cac227..3190f556f92 100644 --- a/src/main/io/frsky_osd.h +++ b/src/main/io/frsky_osd.h @@ -74,7 +74,7 @@ typedef struct frskyOSDWidgetAHIData_s uint16_t roll : 12; } __attribute__((packed)) frskyOSDWidgetAHIData_t; -typedef struct frskyOSDWidgetAHIConfigData_s +typedef struct frskyOSDWidgetAHIConfig_s { frskyOSDRect_t rect; uint8_t style; @@ -83,6 +83,20 @@ typedef struct frskyOSDWidgetAHIConfigData_s uint8_t strokeWidth; } __attribute__((packed)) frskyOSDWidgetAHIConfig_t; +typedef struct frskyOSDWidgetSidebarData_s +{ + int32_t value : 24; +} __attribute__((packed)) frskyOSDWidgetSidebarData_t; + +typedef struct frskyOSDWidgetSidebarConfig_s +{ + frskyOSDRect_t rect; + uint8_t options; + uint8_t divisions; + uint16_t counts_per_step; + osdUnit_t unit; +} __attribute__((packed)) frskyOSDWidgetSidebarConfig_t; + bool frskyOSDInit(videoSystem_e videoSystem); bool frskyOSDIsReady(void); void frskyOSDUpdate(void); diff --git a/src/main/io/osd.c b/src/main/io/osd.c index a28f12989cd..d13f9969da6 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -159,19 +159,6 @@ typedef struct statistic_s { static statistic_t stats; -typedef enum { - OSD_SIDEBAR_ARROW_NONE, - OSD_SIDEBAR_ARROW_UP, - OSD_SIDEBAR_ARROW_DOWN, -} osd_sidebar_arrow_e; - -typedef struct osd_sidebar_s { - int32_t offset; - timeMs_t updated; - osd_sidebar_arrow_e arrow; - uint8_t idle; -} osd_sidebar_t; - static timeUs_t resumeRefreshAt = 0; static bool refreshWaitForResumeCmdRelease; @@ -196,8 +183,6 @@ static bool osdDisplayHasCanvas; #endif #define AH_MAX_PITCH_DEFAULT 20 // Specify default maximum AHI pitch value displayed (degrees) -#define AH_SIDEBAR_WIDTH_POS 7 -#define AH_SIDEBAR_HEIGHT_POS 3 PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 13); PG_REGISTER_WITH_RESET_FN(osdLayoutsConfig_t, osdLayoutsConfig, PG_OSD_LAYOUTS_CONFIG, 0); @@ -926,70 +911,6 @@ static inline int32_t osdGetAltitudeMsl(void) #endif } -static uint8_t osdUpdateSidebar(osd_sidebar_scroll_e scroll, osd_sidebar_t *sidebar, timeMs_t currentTimeMs) -{ - // Scroll between SYM_AH_DECORATION_MIN and SYM_AH_DECORATION_MAX. - // Zero scrolling should draw SYM_AH_DECORATION. - uint8_t decoration = SYM_AH_DECORATION; - int offset; - int steps; - switch (scroll) { - case OSD_SIDEBAR_SCROLL_NONE: - sidebar->arrow = OSD_SIDEBAR_ARROW_NONE; - sidebar->offset = 0; - return decoration; - case OSD_SIDEBAR_SCROLL_ALTITUDE: - // Move 1 char for every 20cm - offset = osdGetAltitude(); - steps = offset / 20; - break; - case OSD_SIDEBAR_SCROLL_GROUND_SPEED: -#if defined(USE_GPS) - offset = gpsSol.groundSpeed; -#else - offset = 0; -#endif - // Move 1 char for every 20 cm/s - steps = offset / 20; - break; - case OSD_SIDEBAR_SCROLL_HOME_DISTANCE: -#if defined(USE_GPS) - offset = GPS_distanceToHome; -#else - offset = 0; -#endif - // Move 1 char for every 5m - steps = offset / 5; - break; - } - if (offset) { - decoration -= steps % SYM_AH_DECORATION_COUNT; - if (decoration > SYM_AH_DECORATION_MAX) { - decoration -= SYM_AH_DECORATION_COUNT; - } else if (decoration < SYM_AH_DECORATION_MIN) { - decoration += SYM_AH_DECORATION_COUNT; - } - } - if (currentTimeMs - sidebar->updated > 100) { - if (offset > sidebar->offset) { - sidebar->arrow = OSD_SIDEBAR_ARROW_UP; - sidebar->idle = 0; - } else if (offset < sidebar->offset) { - sidebar->arrow = OSD_SIDEBAR_ARROW_DOWN; - sidebar->idle = 0; - } else { - if (sidebar->idle > 3) { - sidebar->arrow = OSD_SIDEBAR_ARROW_NONE; - } else { - sidebar->idle++; - } - } - sidebar->offset = offset; - sidebar->updated = currentTimeMs; - } - return decoration; -} - static bool osdIsHeadingValid(void) { return isImuHeadingValid(); @@ -1812,43 +1733,7 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_HORIZON_SIDEBARS: { - osdCrosshairPosition(&elemPosX, &elemPosY); - - static osd_sidebar_t left; - static osd_sidebar_t right; - - timeMs_t currentTimeMs = millis(); - uint8_t leftDecoration = osdUpdateSidebar(osdConfig()->left_sidebar_scroll, &left, currentTimeMs); - uint8_t rightDecoration = osdUpdateSidebar(osdConfig()->right_sidebar_scroll, &right, currentTimeMs); - - const int8_t hudwidth = AH_SIDEBAR_WIDTH_POS; - const int8_t hudheight = AH_SIDEBAR_HEIGHT_POS; - - // Arrows - if (osdConfig()->sidebar_scroll_arrows) { - displayWriteChar(osdDisplayPort, elemPosX - hudwidth, elemPosY - hudheight - 1, - left.arrow == OSD_SIDEBAR_ARROW_UP ? SYM_AH_DECORATION_UP : SYM_BLANK); - - displayWriteChar(osdDisplayPort, elemPosX + hudwidth, elemPosY - hudheight - 1, - right.arrow == OSD_SIDEBAR_ARROW_UP ? SYM_AH_DECORATION_UP : SYM_BLANK); - - displayWriteChar(osdDisplayPort, elemPosX - hudwidth, elemPosY + hudheight + 1, - left.arrow == OSD_SIDEBAR_ARROW_DOWN ? SYM_AH_DECORATION_DOWN : SYM_BLANK); - - displayWriteChar(osdDisplayPort, elemPosX + hudwidth, elemPosY + hudheight + 1, - right.arrow == OSD_SIDEBAR_ARROW_DOWN ? SYM_AH_DECORATION_DOWN : SYM_BLANK); - } - - // Draw AH sides - for (int y = -hudheight; y <= hudheight; y++) { - displayWriteChar(osdDisplayPort, elemPosX - hudwidth, elemPosY + y, leftDecoration); - displayWriteChar(osdDisplayPort, elemPosX + hudwidth, elemPosY + y, rightDecoration); - } - - // AH level indicators - displayWriteChar(osdDisplayPort, elemPosX - hudwidth + 1, elemPosY, SYM_AH_RIGHT); - displayWriteChar(osdDisplayPort, elemPosX + hudwidth - 1, elemPosY, SYM_AH_LEFT); - + osdDrawSidebars(osdDisplayPort, osdGetDisplayPortCanvas()); return true; } diff --git a/src/main/io/osd_canvas.c b/src/main/io/osd_canvas.c index c3dcd5e0532..3ad02d643f0 100644 --- a/src/main/io/osd_canvas.c +++ b/src/main/io/osd_canvas.c @@ -34,6 +34,11 @@ #define AHI_MAX_DRAW_INTERVAL_MS 1000 #define AHI_CROSSHAIR_MARGIN 6 +#define SIDEBAR_REDRAW_INTERVAL_MS 100 +#define WIDGET_SIDEBAR_LEFT_INSTANCE 0 +#define WIDGET_SIDEBAR_RIGHT_INSTANCE 1 + +#include "common/constants.h" #include "common/log.h" #include "common/maths.h" #include "common/typeconversion.h" @@ -49,6 +54,8 @@ #include "io/osd_common.h" #include "io/osd.h" +#include "navigation/navigation.h" + void osdCanvasDrawVarioShape(displayCanvas_t *canvas, unsigned ex, unsigned ey, float zvel, bool erase) { char sym; @@ -462,4 +469,197 @@ void osdCanvasDrawHeadingGraph(displayPort_t *display, displayCanvas_t *canvas, displayCanvasFillStrokeTriangle(canvas, rmx - 2, py - 1, rmx + 2, py - 1, rmx, py + 1); } +static int32_t osdCanvasSidebarGetValue(osd_sidebar_scroll_e scroll) +{ + switch (scroll) { + case OSD_SIDEBAR_SCROLL_NONE: + break; + case OSD_SIDEBAR_SCROLL_ALTITUDE: + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_IMPERIAL: + return CENTIMETERS_TO_CENTIFEET(osdGetAltitude()); + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_METRIC: + return osdGetAltitude(); + } + break; + case OSD_SIDEBAR_SCROLL_GROUND_SPEED: +#if defined(USE_GPS) + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + return CENTIMETERS_TO_CENTIFEET(gpsSol.groundSpeed); + case OSD_UNIT_METRIC: + return gpsSol.groundSpeed; + } +#endif + break; + case OSD_SIDEBAR_SCROLL_HOME_DISTANCE: +#if defined(USE_GPS) + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_IMPERIAL: + return CENTIMETERS_TO_CENTIFEET(GPS_distanceToHome * 100); + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_METRIC: + return GPS_distanceToHome * 100; +#endif + } + break; + } + return 0; +} + +static uint8_t osdCanvasSidebarGetOptions(int *width, osd_sidebar_scroll_e scroll) +{ + switch (scroll) { + case OSD_SIDEBAR_SCROLL_NONE: + break; + case OSD_SIDEBAR_SCROLL_ALTITUDE: + FALLTHROUGH; + case OSD_SIDEBAR_SCROLL_GROUND_SPEED: + FALLTHROUGH; + case OSD_SIDEBAR_SCROLL_HOME_DISTANCE: + *width = OSD_CHAR_WIDTH * 5; // 4 numbers + unit + return 0; + } + *width = OSD_CHAR_WIDTH; + return DISPLAY_WIDGET_SIDEBAR_OPTION_STATIC | DISPLAY_WIDGET_SIDEBAR_OPTION_UNLABELED; +} + +static void osdCanvasSidebarGetUnit(osdUnit_t *unit, osd_sidebar_scroll_e scroll) +{ + // We always count in 1/100 units, converting to + // "centifeet" when displaying imperial units + unit->scale = 100; + + switch (scroll) { + case OSD_SIDEBAR_SCROLL_NONE: + unit->symbol = 0; + unit->divisor = 0; + unit->divided_symbol = 0; + break; + case OSD_SIDEBAR_SCROLL_ALTITUDE: + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_IMPERIAL: + unit->symbol = SYM_ALT_FT; + unit->divisor = FEET_PER_KILOFEET; + unit->divided_symbol = SYM_ALT_KFT; + break; + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_METRIC: + unit->symbol = SYM_ALT_M; + unit->divisor = METERS_PER_KILOMETER; + unit->divided_symbol = SYM_ALT_KM; + break; + } + break; + case OSD_SIDEBAR_SCROLL_GROUND_SPEED: + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_IMPERIAL: + unit->symbol = SYM_MPH; + unit->divisor = 0; + unit->divided_symbol = 0; + break; + case OSD_UNIT_METRIC: + unit->symbol = SYM_KMH; + unit->divisor = 0; + unit->divided_symbol = 0; + break; + } + break; + case OSD_SIDEBAR_SCROLL_HOME_DISTANCE: + switch ((osd_unit_e)osdConfig()->units) { + case OSD_UNIT_IMPERIAL: + unit->symbol = SYM_FT; + unit->divisor = FEET_PER_MILE; + unit->divided_symbol = SYM_MI; + break; + case OSD_UNIT_UK: + FALLTHROUGH; + case OSD_UNIT_METRIC: + unit->symbol = SYM_M; + unit->divisor = METERS_PER_KILOMETER; + unit->divided_symbol = SYM_KM; + break; + } + break; + } +} + +static bool osdCanvasDrawSidebar(uint8_t *configured, displayWidgets_t *widgets, + int instance, osd_sidebar_scroll_e scroll) +{ + // Configuration + uint8_t configuration = scroll << 4 | osdConfig()->units; + if (configuration != *configured) { + int width; + uint8_t options = osdCanvasSidebarGetOptions(&width, scroll); + uint8_t ex; + uint8_t ey; + osdCrosshairPosition(&ex, &ey); + const int height = 2 * OSD_AH_SIDEBAR_HEIGHT_POS * OSD_CHAR_HEIGHT; + const int y = (ey - OSD_AH_SIDEBAR_HEIGHT_POS) * OSD_CHAR_HEIGHT; + + widgetSidebarConfiguration_t config = { + .rect.y = y, + .rect.w = width, + .rect.h = height, + .options = options, + .divisions = OSD_AH_SIDEBAR_HEIGHT_POS * 2, + }; + osdCanvasSidebarGetUnit(&config.unit, scroll); + config.counts_per_step = config.unit.scale * 100; + + if (instance == WIDGET_SIDEBAR_LEFT_INSTANCE) { + config.rect.x = ((ex - OSD_AH_SIDEBAR_WIDTH_POS) * OSD_CHAR_WIDTH) - width; + config.options |= DISPLAY_WIDGET_SIDEBAR_OPTION_LEFT; + } else { + config.rect.x = ((ex + OSD_AH_SIDEBAR_WIDTH_POS) * OSD_CHAR_WIDTH); + } + + if (!displayWidgetsConfigureSidebar(widgets, instance, &config)) { + return false; + } + + *configured = configuration; + } + // Actual drawing + int32_t data = osdCanvasSidebarGetValue(scroll); + return displayWidgetsDrawSidebar(widgets, instance, data); +} + +bool osdCanvasDrawSidebars(displayPort_t *display, displayCanvas_t *canvas) +{ + UNUSED(display); + + static uint8_t leftConfigured = 0xFF; + static uint8_t rightConfigured = 0xFF; + static timeMs_t nextRedraw = 0; + + timeMs_t now = millis(); + + if (now < nextRedraw) { + return true; + } + + displayWidgets_t widgets; + if (displayCanvasGetWidgets(&widgets, canvas)) { + if (!osdCanvasDrawSidebar(&leftConfigured, &widgets, WIDGET_SIDEBAR_LEFT_INSTANCE, osdConfig()->left_sidebar_scroll)) { + return false; + } + if (!osdCanvasDrawSidebar(&rightConfigured, &widgets, WIDGET_SIDEBAR_RIGHT_INSTANCE, osdConfig()->right_sidebar_scroll)) { + return false; + } + nextRedraw = now + SIDEBAR_REDRAW_INTERVAL_MS; + return true; + } + return false; +} + #endif diff --git a/src/main/io/osd_canvas.h b/src/main/io/osd_canvas.h index 38243cb6d9e..b6fc2722ce9 100644 --- a/src/main/io/osd_canvas.h +++ b/src/main/io/osd_canvas.h @@ -36,3 +36,4 @@ void osdCanvasDrawVario(displayPort_t *display, displayCanvas_t *canvas, const o void osdCanvasDrawDirArrow(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, float degrees, bool eraseBefore); void osdCanvasDrawArtificialHorizon(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, float pitchAngle, float rollAngle); void osdCanvasDrawHeadingGraph(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, int heading); +bool osdCanvasDrawSidebars(displayPort_t *display, displayCanvas_t *canvas); diff --git a/src/main/io/osd_common.c b/src/main/io/osd_common.c index 7d632edc9de..5dc53ea41dd 100644 --- a/src/main/io/osd_common.c +++ b/src/main/io/osd_common.c @@ -139,3 +139,15 @@ void osdDrawHeadingGraph(displayPort_t *display, displayCanvas_t *canvas, const } #endif } + +void osdDrawSidebars(displayPort_t *display, displayCanvas_t *canvas) +{ +#if defined(USE_CANVAS) + if (osdCanvasDrawSidebars(display, canvas)) { + return; + } +#else + UNUSED(canvas); +#endif + osdGridDrawSidebars(display); +} diff --git a/src/main/io/osd_common.h b/src/main/io/osd_common.h index 1614033b6db..a878c2f3d4c 100644 --- a/src/main/io/osd_common.h +++ b/src/main/io/osd_common.h @@ -41,6 +41,9 @@ #define OSD_HEADING_GRAPH_WIDTH 9 #define OSD_HEADING_GRAPH_DECIDEGREES_PER_CHAR 225 +#define OSD_AH_SIDEBAR_WIDTH_POS 7 +#define OSD_AH_SIDEBAR_HEIGHT_POS 3 + typedef struct displayPort_s displayPort_t; typedef struct displayCanvas_s displayCanvas_t; @@ -78,3 +81,4 @@ void osdDrawArtificialHorizon(displayPort_t *display, displayCanvas_t *canvas, c // Draws a heading graph with heading given as 0.1 degree steps i.e. [0, 3600). It uses 9 horizontal // grid slots. void osdDrawHeadingGraph(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, int heading); +void osdDrawSidebars(displayPort_t *display, displayCanvas_t *canvas); diff --git a/src/main/io/osd_grid.c b/src/main/io/osd_grid.c index 97f499e7581..d0d4c24d274 100644 --- a/src/main/io/osd_grid.c +++ b/src/main/io/osd_grid.c @@ -35,10 +35,26 @@ #include "drivers/display.h" #include "drivers/osd_symbols.h" +#include "drivers/time.h" #include "io/osd.h" #include "io/osd_common.h" +#include "navigation/navigation.h" + +typedef enum { + OSD_SIDEBAR_ARROW_NONE, + OSD_SIDEBAR_ARROW_UP, + OSD_SIDEBAR_ARROW_DOWN, +} osd_sidebar_arrow_e; + +typedef struct osd_sidebar_s { + int32_t offset; + timeMs_t updated; + osd_sidebar_arrow_e arrow; + uint8_t idle; +} osd_sidebar_t; + void osdGridDrawVario(displayPort_t *display, unsigned gx, unsigned gy, float zvel) { int v = zvel / OSD_VARIO_CM_S_PER_ARROW; @@ -197,4 +213,111 @@ void osdGridDrawHeadingGraph(displayPort_t *display, unsigned gx, unsigned gy, i displayWrite(display, gx, gy, buf); } +static uint8_t osdUpdateSidebar(osd_sidebar_scroll_e scroll, osd_sidebar_t *sidebar, timeMs_t currentTimeMs) +{ + // Scroll between SYM_AH_DECORATION_MIN and SYM_AH_DECORATION_MAX. + // Zero scrolling should draw SYM_AH_DECORATION. + uint8_t decoration = SYM_AH_DECORATION; + int offset; + int steps; + switch (scroll) { + case OSD_SIDEBAR_SCROLL_NONE: + sidebar->arrow = OSD_SIDEBAR_ARROW_NONE; + sidebar->offset = 0; + return decoration; + case OSD_SIDEBAR_SCROLL_ALTITUDE: + // Move 1 char for every 20cm + offset = osdGetAltitude(); + steps = offset / 20; + break; + case OSD_SIDEBAR_SCROLL_GROUND_SPEED: +#if defined(USE_GPS) + offset = gpsSol.groundSpeed; +#else + offset = 0; +#endif + // Move 1 char for every 20 cm/s + steps = offset / 20; + break; + case OSD_SIDEBAR_SCROLL_HOME_DISTANCE: +#if defined(USE_GPS) + offset = GPS_distanceToHome; +#else + offset = 0; +#endif + // Move 1 char for every 5m + steps = offset / 5; + break; + } + if (offset) { + decoration -= steps % SYM_AH_DECORATION_COUNT; + if (decoration > SYM_AH_DECORATION_MAX) { + decoration -= SYM_AH_DECORATION_COUNT; + } else if (decoration < SYM_AH_DECORATION_MIN) { + decoration += SYM_AH_DECORATION_COUNT; + } + } + if (currentTimeMs - sidebar->updated > 100) { + if (offset > sidebar->offset) { + sidebar->arrow = OSD_SIDEBAR_ARROW_UP; + sidebar->idle = 0; + } else if (offset < sidebar->offset) { + sidebar->arrow = OSD_SIDEBAR_ARROW_DOWN; + sidebar->idle = 0; + } else { + if (sidebar->idle > 3) { + sidebar->arrow = OSD_SIDEBAR_ARROW_NONE; + } else { + sidebar->idle++; + } + } + sidebar->offset = offset; + sidebar->updated = currentTimeMs; + } + return decoration; +} + +void osdGridDrawSidebars(displayPort_t *display) +{ + uint8_t elemPosX; + uint8_t elemPosY; + + osdCrosshairPosition(&elemPosX, &elemPosY); + + static osd_sidebar_t left; + static osd_sidebar_t right; + + timeMs_t currentTimeMs = millis(); + uint8_t leftDecoration = osdUpdateSidebar(osdConfig()->left_sidebar_scroll, &left, currentTimeMs); + uint8_t rightDecoration = osdUpdateSidebar(osdConfig()->right_sidebar_scroll, &right, currentTimeMs); + + const int8_t hudwidth = OSD_AH_SIDEBAR_WIDTH_POS; + const int8_t hudheight = OSD_AH_SIDEBAR_HEIGHT_POS; + + // Arrows + if (osdConfig()->sidebar_scroll_arrows) { + displayWriteChar(display, elemPosX - hudwidth, elemPosY - hudheight - 1, + left.arrow == OSD_SIDEBAR_ARROW_UP ? SYM_AH_DECORATION_UP : SYM_BLANK); + + displayWriteChar(display, elemPosX + hudwidth, elemPosY - hudheight - 1, + right.arrow == OSD_SIDEBAR_ARROW_UP ? SYM_AH_DECORATION_UP : SYM_BLANK); + + displayWriteChar(display, elemPosX - hudwidth, elemPosY + hudheight + 1, + left.arrow == OSD_SIDEBAR_ARROW_DOWN ? SYM_AH_DECORATION_DOWN : SYM_BLANK); + + displayWriteChar(display, elemPosX + hudwidth, elemPosY + hudheight + 1, + right.arrow == OSD_SIDEBAR_ARROW_DOWN ? SYM_AH_DECORATION_DOWN : SYM_BLANK); + } + + // Draw AH sides + for (int y = -hudheight; y <= hudheight; y++) { + displayWriteChar(display, elemPosX - hudwidth, elemPosY + y, leftDecoration); + displayWriteChar(display, elemPosX + hudwidth, elemPosY + y, rightDecoration); + } + + // AH level indicators + displayWriteChar(display, elemPosX - hudwidth + 1, elemPosY, SYM_AH_RIGHT); + displayWriteChar(display, elemPosX + hudwidth - 1, elemPosY, SYM_AH_LEFT); +} + #endif diff --git a/src/main/io/osd_grid.h b/src/main/io/osd_grid.h index c4c8b7b0e0e..baf69dc9186 100644 --- a/src/main/io/osd_grid.h +++ b/src/main/io/osd_grid.h @@ -32,3 +32,4 @@ void osdGridDrawVario(displayPort_t *display, unsigned gx, unsigned gy, float zv void osdGridDrawDirArrow(displayPort_t *display, unsigned gx, unsigned gy, float degrees); void osdGridDrawArtificialHorizon(displayPort_t *display, unsigned gx, unsigned gy, float pitchAngle, float rollAngle); void osdGridDrawHeadingGraph(displayPort_t *display, unsigned gx, unsigned gy, int heading); +void osdGridDrawSidebars(displayPort_t *display); From 144ba419bcd5d3fcd788889ec9eeb12c2638f721 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sun, 14 Jun 2020 18:54:04 +0100 Subject: [PATCH 069/248] [OSD] Fix clearing of the local OSD buffer osdCharacterGridBufferClear(), osdGridBufferClearGridRect() and osdGridBufferClearPixelRect() where setting the whole buffer to 0 instead of SYM_BLANK, so when the map code read back the buffer in order to determine if a slot was free it never found one available. Fixes #5522 --- src/main/drivers/osd.c | 8 ++++++-- src/main/drivers/osd.h | 3 ++- 2 files changed, 8 insertions(+), 3 deletions(-) diff --git a/src/main/drivers/osd.c b/src/main/drivers/osd.c index bddefea7ce0..82e882f6c67 100644 --- a/src/main/drivers/osd.c +++ b/src/main/drivers/osd.c @@ -23,8 +23,11 @@ * */ +#include "platform.h" + #include "drivers/display_canvas.h" #include "drivers/osd.h" +#include "drivers/osd_symbols.h" uint16_t osdCharacterGridBuffer[OSD_CHARACTER_GRID_BUFFER_SIZE] ALIGNED(4); @@ -32,8 +35,9 @@ void osdCharacterGridBufferClear(void) { uint32_t *ptr = (uint32_t *)osdCharacterGridBuffer; uint32_t *end = (uint32_t *)(ARRAYEND(osdCharacterGridBuffer)); + uint32_t blank32 = SYM_BLANK << 24 | SYM_BLANK << 16 | SYM_BLANK << 8 | SYM_BLANK; for (; ptr < end; ptr++) { - *ptr = 0; + *ptr = blank32; } } @@ -74,7 +78,7 @@ void osdGridBufferClearGridRect(int x, int y, int w, int h) int maxY = y + h; for (int ii = x; ii <= maxX; ii++) { for (int jj = y; jj <= maxY; jj++) { - *osdCharacterGridBufferGetEntryPtr(ii, jj) = 0; + *osdCharacterGridBufferGetEntryPtr(ii, jj) = SYM_BLANK; } } } diff --git a/src/main/drivers/osd.h b/src/main/drivers/osd.h index 8859325d10b..62f0c05dc59 100644 --- a/src/main/drivers/osd.h +++ b/src/main/drivers/osd.h @@ -75,8 +75,9 @@ typedef struct osdUnit_t extern uint16_t osdCharacterGridBuffer[OSD_CHARACTER_GRID_BUFFER_SIZE] ALIGNED(4); -// Sets all buffer entries to 0 +// Sets all buffer entries to SYM_BLANK void osdCharacterGridBufferClear(void); void osdGridBufferClearGridRect(int x, int y, int w, int h); void osdGridBufferClearPixelRect(displayCanvas_t *canvas, int x, int y, int w, int h); + uint16_t *osdCharacterGridBufferGetEntryPtr(unsigned x, unsigned y); From a25fcd5656c54105877e4341f070a5a481b6a53f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 15 Jun 2020 12:20:55 +0100 Subject: [PATCH 070/248] [MSP/CLI] Constrain receive baud rates indices to their valid values MSP was not restricting anything an accepting any values, while CLI had some seemingly arbitrary bounds. Now both interfaces accept the full range of valid values. --- src/main/fc/cli.c | 16 ++++------------ src/main/fc/fc_msp.c | 16 ++++++++-------- src/main/io/serial.h | 5 ++++- 3 files changed, 16 insertions(+), 21 deletions(-) diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index b4c964f3ec4..44d7d3867c0 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -811,27 +811,19 @@ static void cliSerial(char *cmdline) switch (i) { case 0: - if (baudRateIndex < BAUD_1200 || baudRateIndex > BAUD_2470000) { - continue; - } + baudRateIndex = constrain(baudRateIndex, BAUD_MIN, BAUD_MAX); portConfig.msp_baudrateIndex = baudRateIndex; break; case 1: - if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) { - continue; - } + baudRateIndex = constrain(baudRateIndex, BAUD_MIN, BAUD_MAX); portConfig.gps_baudrateIndex = baudRateIndex; break; case 2: - if (baudRateIndex != BAUD_AUTO && baudRateIndex > BAUD_115200) { - continue; - } + baudRateIndex = constrain(baudRateIndex, BAUD_MIN, BAUD_MAX); portConfig.telemetry_baudrateIndex = baudRateIndex; break; case 3: - if (baudRateIndex < BAUD_19200 || baudRateIndex > BAUD_250000) { - continue; - } + baudRateIndex = constrain(baudRateIndex, BAUD_MIN, BAUD_MAX); portConfig.peripheral_baudrateIndex = baudRateIndex; break; } diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 5393e000c01..cd26f87ccb5 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -2602,10 +2602,10 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) portConfig->identifier = identifier; portConfig->functionMask = sbufReadU16(src); - portConfig->msp_baudrateIndex = sbufReadU8(src); - portConfig->gps_baudrateIndex = sbufReadU8(src); - portConfig->telemetry_baudrateIndex = sbufReadU8(src); - portConfig->peripheral_baudrateIndex = sbufReadU8(src); + portConfig->msp_baudrateIndex = constrain(sbufReadU8(src), BAUD_MIN, BAUD_MAX); + portConfig->gps_baudrateIndex = constrain(sbufReadU8(src), BAUD_MIN, BAUD_MAX); + portConfig->telemetry_baudrateIndex = constrain(sbufReadU8(src), BAUD_MIN, BAUD_MAX); + portConfig->peripheral_baudrateIndex = constrain(sbufReadU8(src), BAUD_MIN, BAUD_MAX); } } break; @@ -2630,10 +2630,10 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) portConfig->identifier = identifier; portConfig->functionMask = sbufReadU32(src); - portConfig->msp_baudrateIndex = sbufReadU8(src); - portConfig->gps_baudrateIndex = sbufReadU8(src); - portConfig->telemetry_baudrateIndex = sbufReadU8(src); - portConfig->peripheral_baudrateIndex = sbufReadU8(src); + portConfig->msp_baudrateIndex = constrain(sbufReadU8(src), BAUD_MIN, BAUD_MAX); + portConfig->gps_baudrateIndex = constrain(sbufReadU8(src), BAUD_MIN, BAUD_MAX); + portConfig->telemetry_baudrateIndex = constrain(sbufReadU8(src), BAUD_MIN, BAUD_MAX); + portConfig->peripheral_baudrateIndex = constrain(sbufReadU8(src), BAUD_MIN, BAUD_MAX); } } break; diff --git a/src/main/io/serial.h b/src/main/io/serial.h index 76e57b36388..9ea7869ab10 100644 --- a/src/main/io/serial.h +++ b/src/main/io/serial.h @@ -74,7 +74,10 @@ typedef enum { BAUD_1000000, BAUD_1500000, BAUD_2000000, - BAUD_2470000 + BAUD_2470000, + + BAUD_MIN = BAUD_AUTO, + BAUD_MAX = BAUD_2470000, } baudRate_e; extern const uint32_t baudRates[]; From 2f8e86e7cde5eb244fe8ef67f502b766f59c8c5a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 15 Jun 2020 12:52:07 +0100 Subject: [PATCH 071/248] [FRSKYOSD] Add support for increasing the default data rate Since v1, FrSkyOSD allows changing the baudrate to higher values but we were ignoring that. Now if the user has configured the respective port to a higher baudrate, we will switch to it at runtime. This also requires adding support to probe at different baud rates on startup since the FC might have been rebooted without rebooting the OSD. --- src/main/io/frsky_osd.c | 239 ++++++++++++++++++++++++++++------------ 1 file changed, 170 insertions(+), 69 deletions(-) diff --git a/src/main/io/frsky_osd.c b/src/main/io/frsky_osd.c index edebe8ec6f3..7486e1efbfa 100644 --- a/src/main/io/frsky_osd.c +++ b/src/main/io/frsky_osd.c @@ -18,8 +18,8 @@ #include "io/frsky_osd.h" #include "io/serial.h" -#define FRSKY_OSD_BAUDRATE 115200 -#define FRSKY_OSD_SUPPORTED_API_VERSION 1 +#define FRSKY_OSD_DEFAULT_BAUDRATE_INDEX BAUD_115200 +#define FRSKY_OSD_SUPPORTED_API_VERSION 2 #define FRSKY_OSD_PREAMBLE_BYTE_0 '$' #define FRSKY_OSD_PREAMBLE_BYTE_1 'A' @@ -40,7 +40,8 @@ #define FRSKY_OSD_CMD_RESPONSE_ERROR 0 -#define FRSKY_OSD_INFO_INTERVAL_MS 1000 +#define FRSKY_OSD_INFO_INTERVAL_MS 100 +#define FRSKY_OSD_INFO_READY_INTERVAL_MS 5000 #define FRSKY_OSD_TRACE(fmt, ...) #define FRSKY_OSD_DEBUG(fmt, ...) LOG_D(OSD, "FrSky OSD: " fmt, ##__VA_ARGS__) @@ -120,6 +121,8 @@ typedef enum OSD_CMD_WIDGET_SET_CONFIG = 115, // API2 OSD_CMD_WIDGET_DRAW = 116, // API2 OSD_CMD_WIDGET_ERASE = 117, // API2 + + OSD_CMD_SET_DATA_RATE = 122, } osdCommand_e; typedef enum { @@ -170,10 +173,12 @@ typedef struct frskyOSDDrawGridStrHeaderCmd_s { } __attribute__((packed)) frskyOSDDrawGridStrHeaderCmd_t; typedef struct frskyOSDDrawGridStrV2HeaderCmd_s { - unsigned gx : 5; // +5 = 5 - unsigned gy : 4; // +4 = 9 - unsigned opts : 7; // +7 = 16 = 2 bytes - // uvarint with size and blob folow + unsigned gx : 5; // +5 = 5 + unsigned gy : 4; // +4 = 9 + unsigned opts : 3; // +3 = 12 + unsigned size : 4; // +4 = 16 = 2 bytes + // if size == 0, uvarint with size follows + // blob with the given size follows // string IS NOT null terminated } __attribute__((packed)) frskyOSDDrawGridStrV2HeaderCmd_t; @@ -217,8 +222,9 @@ typedef struct frskyOSDDrawGridChrV2Cmd_s unsigned gx : 5; // +5 = 5 unsigned gy : 4; // +4 = 9 unsigned chr : 9; // +9 = 18 - unsigned opts : 4; // +4 = 22 from osd_bitmap_opt_t - unsigned reserved : 2; // +2 = 24 = 3 bytes + unsigned opts : 3; // +3 = 21, from osd_bitmap_opt_t + unsigned as_mask : 1; // +1 = 22 + unsigned color : 2; // +2 = 24 = 3 bytes, only used when drawn as as_mask = 1 } __attribute__((packed)) frskyOSDDrawGridChrV2Cmd_t; typedef struct frskyOSDError_s { @@ -258,6 +264,8 @@ typedef struct frskyOSDState_s { osdCharacter_t *chr; } recvOsdCharacter; serialPort_t *port; + baudRate_e baudrate; + bool keepBaudrate; bool initialized; frskyOSDError_t error; timeMs_t nextInfoRequest; @@ -265,6 +273,8 @@ typedef struct frskyOSDState_s { static frskyOSDState_t state; +static bool frskyOSDDispatchResponse(void); + static uint8_t frskyOSDChecksum(uint8_t crc, uint8_t c) { return crc8_dvb_s2(crc, c); @@ -314,7 +324,7 @@ static void frskyOSDSendCommand(uint8_t cmd, const void *payload, size_t size) } } -static void frskyOSDStateReset(serialPort_t *port) +static void frskyOSDStateReset(serialPort_t *port, baudRate_e baudrate) { frskyOSDResetReceiveBuffer(); frskyOSDResetSendBuffer(); @@ -324,6 +334,8 @@ static void frskyOSDStateReset(serialPort_t *port) state.info.viewport.height = 0; state.port = port; + state.baudrate = baudrate; + state.keepBaudrate = false; state.initialized = false; } @@ -389,6 +401,42 @@ static bool frskyOSDIsResponseAvailable(void) return state.recvBuffer.state == RECV_STATE_DONE; } +static void frskyOSDClearReceiveBuffer(void) +{ + frskyOSDUpdateReceiveBuffer(); + + if (frskyOSDIsResponseAvailable()) { + frskyOSDDispatchResponse(); + } else if (state.recvBuffer.pos > 0) { + FRSKY_OSD_DEBUG("Discarding receive buffer with %u bytes", state.recvBuffer.pos); + frskyOSDResetReceiveBuffer(); + } +} + +static void frskyOSDSendAsyncCommand(uint8_t cmd, const void *data, size_t size) +{ + FRSKY_OSD_TRACE("Send async cmd %u", cmd); + frskyOSDSendCommand(cmd, data, size); +} + +static bool frskyOSDSendSyncCommand(uint8_t cmd, const void *data, size_t size, timeMs_t timeout) +{ + FRSKY_OSD_TRACE("Send sync cmd %u", cmd); + frskyOSDClearReceiveBuffer(); + frskyOSDSendCommand(cmd, data, size); + frskyOSDFlushSendBuffer(); + timeMs_t end = millis() + timeout; + while (millis() < end) { + frskyOSDUpdateReceiveBuffer(); + if (frskyOSDIsResponseAvailable() && frskyOSDDispatchResponse()) { + FRSKY_OSD_TRACE("Got sync response"); + return true; + } + } + FRSKY_OSD_DEBUG("Sync response failed"); + return false; +} + static bool frskyOSDHandleCommand(osdCommand_e cmd, const void *payload, size_t size) { const uint8_t *ptr = payload; @@ -418,6 +466,21 @@ static bool frskyOSDHandleCommand(osdCommand_e cmd, const void *payload, size_t resp->magic[0], resp->magic[1], resp->magic[2]); return false; } + FRSKY_OSD_TRACE("received OSD_CMD_INFO at %u", (unsigned)baudRates[state.baudrate]); + if (!state.keepBaudrate) { + const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_FRSKY_OSD); + if (portConfig && portConfig->peripheral_baudrateIndex > FRSKY_OSD_DEFAULT_BAUDRATE_INDEX && + portConfig->peripheral_baudrateIndex != state.baudrate) { + + // Try switching baudrates + uint32_t portBaudrate = baudRates[portConfig->peripheral_baudrateIndex]; + FRSKY_OSD_TRACE("requesting baudrate switch from %u to %u", + (unsigned)baudRates[state.baudrate], (unsigned)portBaudrate); + frskyOSDSendAsyncCommand(OSD_CMD_SET_DATA_RATE, &portBaudrate, sizeof(portBaudrate)); + frskyOSDFlushSendBuffer(); + return true; + } + } state.info.major = resp->versionMajor; state.info.minor = resp->versionMinor; state.info.grid.rows = resp->gridRows; @@ -460,6 +523,35 @@ static bool frskyOSDHandleCommand(osdCommand_e cmd, const void *payload, size_t { return true; } + case OSD_CMD_SET_DATA_RATE: + { + if (size < sizeof(uint32_t)) { + break; + } + const uint32_t *newBaudrate = payload; + if (*newBaudrate && *newBaudrate != baudRates[state.baudrate]) { + FRSKY_OSD_TRACE("changed baudrate from %u to %u", (unsigned)baudRates[state.baudrate], + (unsigned)*newBaudrate); + serialSetBaudRate(state.port, *newBaudrate); + // OSD might have returned a different baudrate from our + // predefined ones. Be ready to handle that + state.baudrate = 0; + for (baudRate_e ii = 0; ii <= BAUD_MAX; ii++) { + if (baudRates[ii] == *newBaudrate) { + state.baudrate = ii; + break; + } + } + } else { + FRSKY_OSD_TRACE("baudrate refused, returned %u", (unsigned)*newBaudrate); + } + // Make sure we request OSD_CMD_INFO again as soon + // as possible and don't try to change the baudrate + // anymore. + state.nextInfoRequest = 0; + state.keepBaudrate = true; + return true; + } default: break; } @@ -487,42 +579,6 @@ static bool frskyOSDDispatchResponse(void) return ok; } -static void frskyOSDClearReceiveBuffer(void) -{ - frskyOSDUpdateReceiveBuffer(); - - if (frskyOSDIsResponseAvailable()) { - frskyOSDDispatchResponse(); - } else if (state.recvBuffer.pos > 0) { - FRSKY_OSD_DEBUG("Discarding receive buffer with %u bytes", state.recvBuffer.pos); - frskyOSDResetReceiveBuffer(); - } -} - -static void frskyOSDSendAsyncCommand(uint8_t cmd, const void *data, size_t size) -{ - FRSKY_OSD_TRACE("Send async cmd %u", cmd); - frskyOSDSendCommand(cmd, data, size); -} - -static bool frskyOSDSendSyncCommand(uint8_t cmd, const void *data, size_t size, timeMs_t timeout) -{ - FRSKY_OSD_TRACE("Send sync cmd %u", cmd); - frskyOSDClearReceiveBuffer(); - frskyOSDSendCommand(cmd, data, size); - frskyOSDFlushSendBuffer(); - timeMs_t end = millis() + timeout; - while (millis() < end) { - frskyOSDUpdateReceiveBuffer(); - if (frskyOSDIsResponseAvailable() && frskyOSDDispatchResponse()) { - FRSKY_OSD_DEBUG("Got sync response"); - return true; - } - } - FRSKY_OSD_DEBUG("Sync response failed"); - return false; -} - static bool frskyOSDShouldRequestInfo(void) { return !frskyOSDIsReady() || millis() > state.nextInfoRequest; @@ -532,13 +588,52 @@ static void frskyOSDRequestInfo(void) { timeMs_t now = millis(); if (state.info.nextRequest < now) { + timeMs_t interval; + if (frskyOSDIsReady()) { + // We already contacted the OSD, so we're just + // polling it to see if the video changed. + interval = FRSKY_OSD_INFO_READY_INTERVAL_MS; + } else { + // We haven't yet heard from the OSD. If this is not + // the first request, switch to the next baudrate. + if (state.info.nextRequest > 0 && !state.keepBaudrate) { + if (state.baudrate == BAUD_MAX) { + state.baudrate = FRSKY_OSD_DEFAULT_BAUDRATE_INDEX; + } else { + state.baudrate++; + } + serialSetBaudRate(state.port, baudRates[state.baudrate]); + } + interval = FRSKY_OSD_INFO_INTERVAL_MS; + } + state.info.nextRequest = now + interval; + uint8_t version = FRSKY_OSD_SUPPORTED_API_VERSION; + FRSKY_OSD_TRACE("request OSD_CMD_INFO at %u", (unsigned)baudRates[state.baudrate]); frskyOSDSendAsyncCommand(OSD_CMD_INFO, &version, sizeof(version)); frskyOSDFlushSendBuffer(); - state.info.nextRequest = now + FRSKY_OSD_INFO_INTERVAL_MS; } } +static bool frskyOSDOpenPort(baudRate_e baudrate) +{ + const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_FRSKY_OSD); + if (portConfig) { + FRSKY_OSD_TRACE("configured, trying to connect..."); + portOptions_t portOptions = SERIAL_STOPBITS_1 | SERIAL_PARITY_NO; + serialPort_t *port = openSerialPort(portConfig->identifier, + FUNCTION_FRSKY_OSD, NULL, NULL, baudRates[baudrate], + MODE_RXTX, portOptions); + + if (port) { + frskyOSDStateReset(port, baudrate); + frskyOSDRequestInfo(); + return true; + } + } + return false; +} + static uint8_t frskyOSDEncodeAttr(textAttributes_t attr) { uint8_t frskyOSDAttr = 0; @@ -554,23 +649,8 @@ static uint8_t frskyOSDEncodeAttr(textAttributes_t attr) bool frskyOSDInit(videoSystem_e videoSystem) { UNUSED(videoSystem); - // TODO: Use videoSystem to set the signal standard when - // no input is detected. - const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_FRSKY_OSD); - if (portConfig) { - FRSKY_OSD_TRACE("configured, trying to connect..."); - portOptions_t portOptions = 0; - serialPort_t *port = openSerialPort(portConfig->identifier, - FUNCTION_FRSKY_OSD, NULL, NULL, FRSKY_OSD_BAUDRATE, - MODE_RXTX, portOptions); - if (port) { - frskyOSDStateReset(port); - frskyOSDRequestInfo(); - return true; - } - } - return false; + return frskyOSDOpenPort(FRSKY_OSD_DEFAULT_BAUDRATE_INDEX); } bool frskyOSDIsReady(void) @@ -704,17 +784,32 @@ unsigned frskyOSDGetPixelHeight(void) return state.info.viewport.height; } -static void frskyOSDSendAsyncBlobCommand(uint8_t cmd, const void *header, size_t headerSize, const void *blob, size_t blobSize) +static void frskyOSDSendAsyncBlobCommand(uint8_t cmd, const void *header, size_t headerSize, const void *blob, size_t blobSize, bool explicitBlobSize) { uint8_t payload[128]; memcpy(payload, header, headerSize); - int uvarintSize = uvarintEncode(blobSize, &payload[headerSize], sizeof(payload) - headerSize); + int uvarintSize; + if (explicitBlobSize) { + uvarintSize = uvarintEncode(blobSize, &payload[headerSize], sizeof(payload) - headerSize); + } else { + uvarintSize = 0; + } memcpy(&payload[headerSize + uvarintSize], blob, blobSize); frskyOSDSendAsyncCommand(cmd, payload, headerSize + uvarintSize + blobSize); } +static void frskyOSDSendAsyncBlobWithExplicitSizeCommand(uint8_t cmd, const void *header, size_t headerSize, const void *blob, size_t blobSize) +{ + frskyOSDSendAsyncBlobCommand(cmd, header, headerSize, blob, blobSize, true); +} + +static void frskyOSDSendAsyncBlobWithoutExplicitSizeCommand(uint8_t cmd, const void *header, size_t headerSize, const void *blob, size_t blobSize) +{ + frskyOSDSendAsyncBlobCommand(cmd, header, headerSize, blob, blobSize, false); +} + static void frskyOSDSendCharInGrid_V1(unsigned x, unsigned y, uint16_t chr, textAttributes_t attr) { uint8_t payload[] = { @@ -754,7 +849,7 @@ static void frskyOSDSendCharSendStringInGrid_V1(unsigned x, unsigned y, const ch .gy = y, .opts = frskyOSDEncodeAttr(attr), }; - frskyOSDSendAsyncBlobCommand(OSD_CMD_DRAW_GRID_STR, &cmd, sizeof(cmd), buff, strlen(buff) + 1); + frskyOSDSendAsyncBlobWithExplicitSizeCommand(OSD_CMD_DRAW_GRID_STR, &cmd, sizeof(cmd), buff, strlen(buff) + 1); } static void frskyOSDSendCharSendStringInGrid_V2(unsigned x, unsigned y, const char *buff, textAttributes_t attr) @@ -764,7 +859,13 @@ static void frskyOSDSendCharSendStringInGrid_V2(unsigned x, unsigned y, const ch .gy = y, .opts = frskyOSDEncodeAttr(attr), }; - frskyOSDSendAsyncBlobCommand(OSD_CMD_DRAW_GRID_STR_2, &cmd, sizeof(cmd), buff, strlen(buff)); + size_t len = strlen(buff); + if (len <= 15) { + cmd.size = len; + frskyOSDSendAsyncBlobWithoutExplicitSizeCommand(OSD_CMD_DRAW_GRID_STR_2, &cmd, sizeof(cmd), buff, len); + } else { + frskyOSDSendAsyncBlobWithExplicitSizeCommand(OSD_CMD_DRAW_GRID_STR_2, &cmd, sizeof(cmd), buff, len); + } } static void frskyOSDSendCharSendStringInGrid(unsigned x, unsigned y, const char *buff, textAttributes_t attr) @@ -932,7 +1033,7 @@ void frskyOSDDrawString(int x, int y, const char *s, uint8_t opts) cmd.p.y = y; cmd.opts = opts; - frskyOSDSendAsyncBlobCommand(OSD_CMD_DRAWING_DRAW_STRING, &cmd, sizeof(cmd), s, strlen(s) + 1); + frskyOSDSendAsyncBlobWithExplicitSizeCommand(OSD_CMD_DRAWING_DRAW_STRING, &cmd, sizeof(cmd), s, strlen(s) + 1); } void frskyOSDDrawStringMask(int x, int y, const char *s, frskyOSDColor_e color, uint8_t opts) @@ -943,7 +1044,7 @@ void frskyOSDDrawStringMask(int x, int y, const char *s, frskyOSDColor_e color, cmd.opts = opts; cmd.maskColor = color; - frskyOSDSendAsyncBlobCommand(OSD_CMD_DRAWING_DRAW_STRING_MASK, &cmd, sizeof(cmd), s, strlen(s) + 1); + frskyOSDSendAsyncBlobWithExplicitSizeCommand(OSD_CMD_DRAWING_DRAW_STRING_MASK, &cmd, sizeof(cmd), s, strlen(s) + 1); } void frskyOSDMoveToPoint(int x, int y) From 4021ba09b00c0ca8e8074365622677835b5a16a6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 15 Jun 2020 12:58:08 +0100 Subject: [PATCH 072/248] [BUILD] Fix compilation for targets without OSD --- src/main/drivers/osd.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/main/drivers/osd.c b/src/main/drivers/osd.c index 82e882f6c67..54e9753a97c 100644 --- a/src/main/drivers/osd.c +++ b/src/main/drivers/osd.c @@ -25,6 +25,8 @@ #include "platform.h" +#if defined(USE_OSD) + #include "drivers/display_canvas.h" #include "drivers/osd.h" #include "drivers/osd_symbols.h" @@ -106,3 +108,5 @@ uint16_t *osdCharacterGridBufferGetEntryPtr(unsigned x, unsigned y) unsigned pos = y * OSD_CHARACTER_GRID_MAX_WIDTH + x; return &osdCharacterGridBuffer[pos]; } + +#endif From 4d1f21c94f3ab2caee44e72926b28594e950f91e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sat, 20 Jun 2020 23:19:43 +0100 Subject: [PATCH 073/248] [OSD] Allow moving sidebars left and right Introduce a osd_sidebar_horizontal_offset parameter that uses grid slots or pixels as units, depending on the OSD type. int8_t is enough to move the sidebars to the corner of the screen even with pixel OSD. Positive values move the bars closer to the screen edges, while negative values bring them closer to the center. --- src/main/fc/settings.yaml | 8 ++++++++ src/main/io/osd.c | 1 + src/main/io/osd.h | 13 +++++++++---- src/main/io/osd_canvas.c | 21 +++++++++++++-------- src/main/io/osd_grid.c | 14 ++++++++------ 5 files changed, 39 insertions(+), 18 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index cab85a143d9..f9f6522e354 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2861,6 +2861,14 @@ groups: description: AHI vertical offset from center (pixel OSD only) default_value: 0 + - name: osd_sidebar_horizontal_offset + field: sidebar_horizontal_offset + min: -128 + max: 127 + default_value: 0 + description: Sidebar horizontal offset from default position. Positive values move the sidebars closer to the edges. + + - name: PG_SYSTEM_CONFIG type: systemConfig_t headers: ["fc/config.h"] diff --git a/src/main/io/osd.c b/src/main/io/osd.c index d13f9969da6..ffd3f4413be 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2547,6 +2547,7 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .ahi_width = OSD_AHI_WIDTH * OSD_CHAR_WIDTH, .ahi_height = OSD_AHI_HEIGHT * OSD_CHAR_HEIGHT, .ahi_vertical_offset = -OSD_CHAR_HEIGHT, + .sidebar_horizontal_offset = OSD_AH_SIDEBAR_WIDTH_POS * OSD_CHAR_WIDTH, ); void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 9ce97a67301..2c27e8dcc9c 100755 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -160,6 +160,8 @@ typedef enum { OSD_UNIT_IMPERIAL, OSD_UNIT_METRIC, OSD_UNIT_UK, // Show speed in mp/h, other values in metric + + OSD_UNIT_MAX = OSD_UNIT_UK, } osd_unit_e; typedef enum { @@ -182,6 +184,8 @@ typedef enum { OSD_SIDEBAR_SCROLL_ALTITUDE, OSD_SIDEBAR_SCROLL_GROUND_SPEED, OSD_SIDEBAR_SCROLL_HOME_DISTANCE, + + OSD_SIDEBAR_SCROLL_MAX = OSD_SIDEBAR_SCROLL_HOME_DISTANCE, } osd_sidebar_scroll_e; typedef enum { @@ -259,10 +263,11 @@ typedef struct osdConfig_s { bool osd_failsafe_switch_layout; uint8_t plus_code_digits; // Number of digits to use in OSD_PLUS_CODE uint8_t osd_ahi_style; - uint8_t ahi_bordered; // Only used by the AHI widget - uint8_t ahi_width; // In pixels, only used by the AHI widget - uint8_t ahi_height; // In pixels, only used by the AHI widget - int8_t ahi_vertical_offset; // Offset from center in pixels. Positive moves the AHI down. Widget only. + uint8_t ahi_bordered; // Only used by the AHI widget + uint8_t ahi_width; // In pixels, only used by the AHI widget + uint8_t ahi_height; // In pixels, only used by the AHI widget + int8_t ahi_vertical_offset; // Offset from center in pixels. Positive moves the AHI down. Widget only. + int8_t sidebar_horizontal_offset; // Horizontal offset from default position. Units are grid slots for grid OSDs, pixels for pixel based OSDs. Positive values move sidebars closer to the edges. } osdConfig_t; diff --git a/src/main/io/osd_canvas.c b/src/main/io/osd_canvas.c index 3ad02d643f0..3d42c608b41 100644 --- a/src/main/io/osd_canvas.c +++ b/src/main/io/osd_canvas.c @@ -592,11 +592,14 @@ static void osdCanvasSidebarGetUnit(osdUnit_t *unit, osd_sidebar_scroll_e scroll } } -static bool osdCanvasDrawSidebar(uint8_t *configured, displayWidgets_t *widgets, +static bool osdCanvasDrawSidebar(uint16_t *configured, displayWidgets_t *widgets, + displayCanvas_t *canvas, int instance, osd_sidebar_scroll_e scroll) { + STATIC_ASSERT(OSD_SIDEBAR_SCROLL_MAX <= 3, adjust_scroll_shift); + STATIC_ASSERT(OSD_UNIT_MAX <= 3, adjust_units_shift); // Configuration - uint8_t configuration = scroll << 4 | osdConfig()->units; + uint16_t configuration = osdConfig()->sidebar_horizontal_offset << 8 | scroll << 6 | osdConfig()->units << 4; if (configuration != *configured) { int width; uint8_t options = osdCanvasSidebarGetOptions(&width, scroll); @@ -616,11 +619,13 @@ static bool osdCanvasDrawSidebar(uint8_t *configured, displayWidgets_t *widgets, osdCanvasSidebarGetUnit(&config.unit, scroll); config.counts_per_step = config.unit.scale * 100; + int center = ex * OSD_CHAR_WIDTH; + int horizontalOffset = osdConfig()->sidebar_horizontal_offset; if (instance == WIDGET_SIDEBAR_LEFT_INSTANCE) { - config.rect.x = ((ex - OSD_AH_SIDEBAR_WIDTH_POS) * OSD_CHAR_WIDTH) - width; + config.rect.x = MAX(center - horizontalOffset - width, 0); config.options |= DISPLAY_WIDGET_SIDEBAR_OPTION_LEFT; } else { - config.rect.x = ((ex + OSD_AH_SIDEBAR_WIDTH_POS) * OSD_CHAR_WIDTH); + config.rect.x = MIN(center + horizontalOffset, canvas->width - width - 1); } if (!displayWidgetsConfigureSidebar(widgets, instance, &config)) { @@ -638,8 +643,8 @@ bool osdCanvasDrawSidebars(displayPort_t *display, displayCanvas_t *canvas) { UNUSED(display); - static uint8_t leftConfigured = 0xFF; - static uint8_t rightConfigured = 0xFF; + static uint16_t leftConfigured = UINT16_MAX; + static uint16_t rightConfigured = UINT16_MAX; static timeMs_t nextRedraw = 0; timeMs_t now = millis(); @@ -650,10 +655,10 @@ bool osdCanvasDrawSidebars(displayPort_t *display, displayCanvas_t *canvas) displayWidgets_t widgets; if (displayCanvasGetWidgets(&widgets, canvas)) { - if (!osdCanvasDrawSidebar(&leftConfigured, &widgets, WIDGET_SIDEBAR_LEFT_INSTANCE, osdConfig()->left_sidebar_scroll)) { + if (!osdCanvasDrawSidebar(&leftConfigured, &widgets, canvas, WIDGET_SIDEBAR_LEFT_INSTANCE, osdConfig()->left_sidebar_scroll)) { return false; } - if (!osdCanvasDrawSidebar(&rightConfigured, &widgets, WIDGET_SIDEBAR_RIGHT_INSTANCE, osdConfig()->right_sidebar_scroll)) { + if (!osdCanvasDrawSidebar(&rightConfigured, &widgets, canvas, WIDGET_SIDEBAR_RIGHT_INSTANCE, osdConfig()->right_sidebar_scroll)) { return false; } nextRedraw = now + SIDEBAR_REDRAW_INTERVAL_MS; diff --git a/src/main/io/osd_grid.c b/src/main/io/osd_grid.c index d0d4c24d274..26a1c643389 100644 --- a/src/main/io/osd_grid.c +++ b/src/main/io/osd_grid.c @@ -291,8 +291,8 @@ void osdGridDrawSidebars(displayPort_t *display) uint8_t leftDecoration = osdUpdateSidebar(osdConfig()->left_sidebar_scroll, &left, currentTimeMs); uint8_t rightDecoration = osdUpdateSidebar(osdConfig()->right_sidebar_scroll, &right, currentTimeMs); - const int8_t hudwidth = OSD_AH_SIDEBAR_WIDTH_POS; - const int8_t hudheight = OSD_AH_SIDEBAR_HEIGHT_POS; + const int hudwidth = OSD_AH_SIDEBAR_WIDTH_POS; + const int hudheight = OSD_AH_SIDEBAR_HEIGHT_POS; // Arrows if (osdConfig()->sidebar_scroll_arrows) { @@ -310,14 +310,16 @@ void osdGridDrawSidebars(displayPort_t *display) } // Draw AH sides + int leftX = MAX(elemPosX - hudwidth - osdConfig()->sidebar_horizontal_offset, 0); + int rightX = MIN(elemPosX + hudwidth + osdConfig()->sidebar_horizontal_offset, display->cols - 1); for (int y = -hudheight; y <= hudheight; y++) { - displayWriteChar(display, elemPosX - hudwidth, elemPosY + y, leftDecoration); - displayWriteChar(display, elemPosX + hudwidth, elemPosY + y, rightDecoration); + displayWriteChar(display, leftX, elemPosY + y, leftDecoration); + displayWriteChar(display, rightX, elemPosY + y, rightDecoration); } // AH level indicators - displayWriteChar(display, elemPosX - hudwidth + 1, elemPosY, SYM_AH_RIGHT); - displayWriteChar(display, elemPosX + hudwidth - 1, elemPosY, SYM_AH_LEFT); + displayWriteChar(display, leftX + 1, elemPosY, SYM_AH_RIGHT); + displayWriteChar(display, rightX - 1, elemPosY, SYM_AH_LEFT); } #endif From ef5f3ece499e4a6221fcdae9fdeb3ea3300193ea Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sun, 21 Jun 2020 00:03:45 +0100 Subject: [PATCH 074/248] [OSD] Change default counts per divisions in sidebars, make them configurable Change the default stepping in sidebar divisions to more sensible values depending on what's causing them to scroll. Also, introduce a setting per sidebar so the user can a custom stepping per sidebar. --- src/main/fc/settings.yaml | 12 ++++++++++++ src/main/io/osd.h | 2 ++ src/main/io/osd_canvas.c | 41 ++++++++++++++++++++++++++++----------- 3 files changed, 44 insertions(+), 11 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index f9f6522e354..1a239d8acbc 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2868,6 +2868,18 @@ groups: default_value: 0 description: Sidebar horizontal offset from default position. Positive values move the sidebars closer to the edges. + - name: osd_left_sidebar_scroll_step + field: left_sidebar_scroll_step + max: 255 + default_value: 0 + description: How many units each sidebar step represents. 0 means the default value for the scroll type. + + - name: osd_right_sidebar_scroll_step + field: right_sidebar_scroll_step + max: 255 + default_value: 0 + description: Same as left_sidebar_scroll_step, but for the right sidebar + - name: PG_SYSTEM_CONFIG type: systemConfig_t diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 2c27e8dcc9c..554fd4a82e6 100755 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -268,6 +268,8 @@ typedef struct osdConfig_s { uint8_t ahi_height; // In pixels, only used by the AHI widget int8_t ahi_vertical_offset; // Offset from center in pixels. Positive moves the AHI down. Widget only. int8_t sidebar_horizontal_offset; // Horizontal offset from default position. Units are grid slots for grid OSDs, pixels for pixel based OSDs. Positive values move sidebars closer to the edges. + uint8_t left_sidebar_scroll_step; // How many units each sidebar step represents. 0 means the default value for the scroll type. + uint8_t right_sidebar_scroll_step; // Same as left_sidebar_scroll_step, but for the right sidebar. } osdConfig_t; diff --git a/src/main/io/osd_canvas.c b/src/main/io/osd_canvas.c index 3d42c608b41..02de3b0649d 100644 --- a/src/main/io/osd_canvas.c +++ b/src/main/io/osd_canvas.c @@ -529,7 +529,7 @@ static uint8_t osdCanvasSidebarGetOptions(int *width, osd_sidebar_scroll_e scrol return DISPLAY_WIDGET_SIDEBAR_OPTION_STATIC | DISPLAY_WIDGET_SIDEBAR_OPTION_UNLABELED; } -static void osdCanvasSidebarGetUnit(osdUnit_t *unit, osd_sidebar_scroll_e scroll) +static void osdCanvasSidebarGetUnit(osdUnit_t *unit, uint16_t *countsPerStep, osd_sidebar_scroll_e scroll) { // We always count in 1/100 units, converting to // "centifeet" when displaying imperial units @@ -540,6 +540,7 @@ static void osdCanvasSidebarGetUnit(osdUnit_t *unit, osd_sidebar_scroll_e scroll unit->symbol = 0; unit->divisor = 0; unit->divided_symbol = 0; + *countsPerStep = 1; break; case OSD_SIDEBAR_SCROLL_ALTITUDE: switch ((osd_unit_e)osdConfig()->units) { @@ -547,6 +548,7 @@ static void osdCanvasSidebarGetUnit(osdUnit_t *unit, osd_sidebar_scroll_e scroll unit->symbol = SYM_ALT_FT; unit->divisor = FEET_PER_KILOFEET; unit->divided_symbol = SYM_ALT_KFT; + *countsPerStep = 50; break; case OSD_UNIT_UK: FALLTHROUGH; @@ -554,6 +556,7 @@ static void osdCanvasSidebarGetUnit(osdUnit_t *unit, osd_sidebar_scroll_e scroll unit->symbol = SYM_ALT_M; unit->divisor = METERS_PER_KILOMETER; unit->divided_symbol = SYM_ALT_KM; + *countsPerStep = 20; break; } break; @@ -565,11 +568,13 @@ static void osdCanvasSidebarGetUnit(osdUnit_t *unit, osd_sidebar_scroll_e scroll unit->symbol = SYM_MPH; unit->divisor = 0; unit->divided_symbol = 0; + *countsPerStep = 5; break; case OSD_UNIT_METRIC: unit->symbol = SYM_KMH; unit->divisor = 0; unit->divided_symbol = 0; + *countsPerStep = 10; break; } break; @@ -579,6 +584,7 @@ static void osdCanvasSidebarGetUnit(osdUnit_t *unit, osd_sidebar_scroll_e scroll unit->symbol = SYM_FT; unit->divisor = FEET_PER_MILE; unit->divided_symbol = SYM_MI; + *countsPerStep = 300; break; case OSD_UNIT_UK: FALLTHROUGH; @@ -586,20 +592,22 @@ static void osdCanvasSidebarGetUnit(osdUnit_t *unit, osd_sidebar_scroll_e scroll unit->symbol = SYM_M; unit->divisor = METERS_PER_KILOMETER; unit->divided_symbol = SYM_KM; + *countsPerStep = 100; break; } break; } } -static bool osdCanvasDrawSidebar(uint16_t *configured, displayWidgets_t *widgets, +static bool osdCanvasDrawSidebar(uint32_t *configured, displayWidgets_t *widgets, displayCanvas_t *canvas, - int instance, osd_sidebar_scroll_e scroll) + int instance, + osd_sidebar_scroll_e scroll, unsigned scrollStep) { STATIC_ASSERT(OSD_SIDEBAR_SCROLL_MAX <= 3, adjust_scroll_shift); STATIC_ASSERT(OSD_UNIT_MAX <= 3, adjust_units_shift); // Configuration - uint16_t configuration = osdConfig()->sidebar_horizontal_offset << 8 | scroll << 6 | osdConfig()->units << 4; + uint32_t configuration = scrollStep << 16 | (unsigned)osdConfig()->sidebar_horizontal_offset << 8 | scroll << 6 | osdConfig()->units << 4; if (configuration != *configured) { int width; uint8_t options = osdCanvasSidebarGetOptions(&width, scroll); @@ -616,11 +624,11 @@ static bool osdCanvasDrawSidebar(uint16_t *configured, displayWidgets_t *widgets .options = options, .divisions = OSD_AH_SIDEBAR_HEIGHT_POS * 2, }; - osdCanvasSidebarGetUnit(&config.unit, scroll); - config.counts_per_step = config.unit.scale * 100; + uint16_t countsPerStep; + osdCanvasSidebarGetUnit(&config.unit, &countsPerStep, scroll); int center = ex * OSD_CHAR_WIDTH; - int horizontalOffset = osdConfig()->sidebar_horizontal_offset; + int horizontalOffset = OSD_AH_SIDEBAR_WIDTH_POS * OSD_CHAR_WIDTH + osdConfig()->sidebar_horizontal_offset; if (instance == WIDGET_SIDEBAR_LEFT_INSTANCE) { config.rect.x = MAX(center - horizontalOffset - width, 0); config.options |= DISPLAY_WIDGET_SIDEBAR_OPTION_LEFT; @@ -628,6 +636,11 @@ static bool osdCanvasDrawSidebar(uint16_t *configured, displayWidgets_t *widgets config.rect.x = MIN(center + horizontalOffset, canvas->width - width - 1); } + if (scrollStep > 0) { + countsPerStep = scrollStep; + } + config.counts_per_step = config.unit.scale * countsPerStep; + if (!displayWidgetsConfigureSidebar(widgets, instance, &config)) { return false; } @@ -643,8 +656,8 @@ bool osdCanvasDrawSidebars(displayPort_t *display, displayCanvas_t *canvas) { UNUSED(display); - static uint16_t leftConfigured = UINT16_MAX; - static uint16_t rightConfigured = UINT16_MAX; + static uint32_t leftConfigured = UINT32_MAX; + static uint32_t rightConfigured = UINT32_MAX; static timeMs_t nextRedraw = 0; timeMs_t now = millis(); @@ -655,10 +668,16 @@ bool osdCanvasDrawSidebars(displayPort_t *display, displayCanvas_t *canvas) displayWidgets_t widgets; if (displayCanvasGetWidgets(&widgets, canvas)) { - if (!osdCanvasDrawSidebar(&leftConfigured, &widgets, canvas, WIDGET_SIDEBAR_LEFT_INSTANCE, osdConfig()->left_sidebar_scroll)) { + if (!osdCanvasDrawSidebar(&leftConfigured, &widgets, canvas, + WIDGET_SIDEBAR_LEFT_INSTANCE, + osdConfig()->left_sidebar_scroll, + osdConfig()->left_sidebar_scroll_step)) { return false; } - if (!osdCanvasDrawSidebar(&rightConfigured, &widgets, canvas, WIDGET_SIDEBAR_RIGHT_INSTANCE, osdConfig()->right_sidebar_scroll)) { + if (!osdCanvasDrawSidebar(&rightConfigured, &widgets, canvas, + WIDGET_SIDEBAR_RIGHT_INSTANCE, + osdConfig()->right_sidebar_scroll, + osdConfig()->right_sidebar_scroll_step)) { return false; } nextRedraw = now + SIDEBAR_REDRAW_INTERVAL_MS; From 038862af09eed78f06499c96e0d58591e1d7014f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 22 Jun 2020 14:59:09 +0100 Subject: [PATCH 075/248] [CANVAS] Fix crash when retrieving the widgets for OSD without canvas --- src/main/drivers/display_canvas.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/display_canvas.c b/src/main/drivers/display_canvas.c index 67ab5200858..a3738e5edb9 100644 --- a/src/main/drivers/display_canvas.c +++ b/src/main/drivers/display_canvas.c @@ -276,5 +276,5 @@ void displayCanvasContextPop(displayCanvas_t *displayCanvas) bool displayCanvasGetWidgets(displayWidgets_t *widgets, const displayCanvas_t *displayCanvas) { - return displayCanvas->vTable->getWidgets ? displayCanvas->vTable->getWidgets(widgets, displayCanvas) : false; + return displayCanvas && displayCanvas->vTable->getWidgets ? displayCanvas->vTable->getWidgets(widgets, displayCanvas) : false; } From 606ea81c28ffadab2fcc9277996a70d1ea5caece Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 22 Jun 2020 20:42:12 +0100 Subject: [PATCH 076/248] [CANVAS] New vario implementation for canvas - Respect the coordinates of the grid based indicator - Reduce the traffic needed to the OSD for a redraw by 10x --- src/main/io/osd_canvas.c | 82 +++++++++++++++++++++++----------------- 1 file changed, 47 insertions(+), 35 deletions(-) diff --git a/src/main/io/osd_canvas.c b/src/main/io/osd_canvas.c index 02de3b0649d..c55c988b5e8 100644 --- a/src/main/io/osd_canvas.c +++ b/src/main/io/osd_canvas.c @@ -56,36 +56,19 @@ #include "navigation/navigation.h" -void osdCanvasDrawVarioShape(displayCanvas_t *canvas, unsigned ex, unsigned ey, float zvel, bool erase) +#define OSD_CANVAS_VARIO_ARROWS_PER_SLOT 2.0f + +static void osdCanvasVarioRect(int *y, int *h, displayCanvas_t *canvas, int midY, float zvel) { - char sym; - float ratio = zvel / (OSD_VARIO_CM_S_PER_ARROW * 2); - int height = -ratio * canvas->gridElementHeight; - int step; - int x = ex * canvas->gridElementWidth; - int start; - int dstart; - if (zvel > 0) { - sym = SYM_VARIO_UP_2A; - start = ceilf(OSD_VARIO_HEIGHT_ROWS / 2.0f); - dstart = start - 1; - step = -canvas->gridElementHeight; + int maxHeight = ceilf(OSD_VARIO_HEIGHT_ROWS /OSD_CANVAS_VARIO_ARROWS_PER_SLOT) * canvas->gridElementHeight; + // We use font characters with 2 arrows per slot + int height = MIN(fabsf(zvel) / (OSD_VARIO_CM_S_PER_ARROW * OSD_CANVAS_VARIO_ARROWS_PER_SLOT) * canvas->gridElementHeight, maxHeight); + if (zvel >= 0) { + *y = midY - height; } else { - sym = SYM_VARIO_DOWN_2A; - start = floorf(OSD_VARIO_HEIGHT_ROWS / 2.0f); - dstart = start; - step = canvas->gridElementHeight; - } - int y = (start + ey) * canvas->gridElementHeight; - displayCanvasClipToRect(canvas, x, y, canvas->gridElementWidth, height); - int dy = (dstart + ey) * canvas->gridElementHeight; - for (int ii = 0, yy = dy; ii < (OSD_VARIO_HEIGHT_ROWS + 1) / 2; ii++, yy += step) { - if (erase) { - displayCanvasDrawCharacterMask(canvas, x, yy, sym, DISPLAY_CANVAS_COLOR_TRANSPARENT, 0); - } else { - displayCanvasDrawCharacter(canvas, x, yy, sym, 0); - } + *y = midY; } + *h = height; } void osdCanvasDrawVario(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, float zvel) @@ -94,17 +77,46 @@ void osdCanvasDrawVario(displayPort_t *display, displayCanvas_t *canvas, const o static float prev = 0; - if (fabsf(prev - zvel) < (OSD_VARIO_CM_S_PER_ARROW / 20.0f)) { + if (fabsf(prev - zvel) < (OSD_VARIO_CM_S_PER_ARROW / (OSD_CANVAS_VARIO_ARROWS_PER_SLOT * 10))) { return; } - uint8_t ex; - uint8_t ey; - - osdDrawPointGetGrid(&ex, &ey, display, canvas, p); - - osdCanvasDrawVarioShape(canvas, ex, ey, prev, true); - osdCanvasDrawVarioShape(canvas, ex, ey, zvel, false); + // Make sure we clear the grid buffer + uint8_t gx; + uint8_t gy; + osdDrawPointGetGrid(&gx, &gy, display, canvas, p); + osdGridBufferClearGridRect(gx, gy, 1, OSD_VARIO_HEIGHT_ROWS); + + int midY = gy * canvas->gridElementHeight + (OSD_VARIO_HEIGHT_ROWS * canvas->gridElementHeight) / 2; + // Make sure we're aligned with the center-ish of the grid based variant + midY -= canvas->gridElementHeight; + + int x = gx * canvas->gridElementWidth; + int w = canvas->gridElementWidth; + int y; + int h; + + osdCanvasVarioRect(&y, &h, canvas, midY, zvel); + + if (signbit(prev) != signbit(zvel) || fabsf(prev) > fabsf(zvel)) { + // New rectangle doesn't overwrite the old one, we need to erase + int py; + int ph; + osdCanvasVarioRect(&py, &ph, canvas, midY, prev); + if (ph != h) { + displayCanvasClearRect(canvas, x, py, w, ph); + } + } + displayCanvasClipToRect(canvas, x, y, w, h); + if (zvel > 0) { + for (int yy = midY - canvas->gridElementHeight; yy > midY - h - canvas->gridElementHeight; yy -= canvas->gridElementHeight) { + displayCanvasDrawCharacter(canvas, x, yy, SYM_VARIO_UP_2A, DISPLAY_CANVAS_BITMAP_OPT_ERASE_TRANSPARENT); + } + } else { + for (int yy = midY; yy < midY + h; yy += canvas->gridElementHeight) { + displayCanvasDrawCharacter(canvas, x, yy, SYM_VARIO_DOWN_2A, DISPLAY_CANVAS_BITMAP_OPT_ERASE_TRANSPARENT); + } + } prev = zvel; } From 694eed63a12ba020d669db039700a36e331d2667 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 22 Jun 2020 20:54:42 +0100 Subject: [PATCH 077/248] [CANVAS] Draw the crosshair centered on the display When we have direct pixel access, we can center it perfectly. --- src/main/io/osd.c | 2 +- src/main/io/osd_hud.c | 13 ++++++++++++- src/main/io/osd_hud.h | 4 +++- 3 files changed, 16 insertions(+), 3 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index ffd3f4413be..a340e0ecad3 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1628,7 +1628,7 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_CROSSHAIRS: // Hud is a sub-element of the crosshair osdCrosshairPosition(&elemPosX, &elemPosY); - osdHudDrawCrosshair(elemPosX, elemPosY); + osdHudDrawCrosshair(osdGetDisplayPortCanvas(), elemPosX, elemPosY); if (osdConfig()->hud_homing && STATE(GPS_FIX) && STATE(GPS_FIX_HOME) && isImuHeadingValid()) { osdHudDrawHoming(elemPosX, elemPosY); diff --git a/src/main/io/osd_hud.c b/src/main/io/osd_hud.c index 535bb32c9ef..ed131f74961 100644 --- a/src/main/io/osd_hud.c +++ b/src/main/io/osd_hud.c @@ -28,6 +28,7 @@ #include "io/osd_hud.h" #include "drivers/display.h" +#include "drivers/display_canvas.h" #include "drivers/osd.h" #include "drivers/osd_symbols.h" #include "drivers/time.h" @@ -215,7 +216,7 @@ void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitu /* * Draw the crosshair */ -void osdHudDrawCrosshair(uint8_t px, uint8_t py) +void osdHudDrawCrosshair(displayCanvas_t *canvas, uint8_t px, uint8_t py) { static const uint16_t crh_style_all[] = { SYM_AH_CH_LEFT, SYM_AH_CH_CENTER, SYM_AH_CH_RIGHT, @@ -227,11 +228,21 @@ void osdHudDrawCrosshair(uint8_t px, uint8_t py) SYM_AH_CH_TYPE7, SYM_AH_CH_TYPE7 + 1, SYM_AH_CH_TYPE7 + 2, }; + // Center on the screen + if (canvas) { + displayCanvasContextPush(canvas); + displayCanvasCtmTranslate(canvas, -canvas->gridElementWidth / 2, -canvas->gridElementHeight / 2); + } + uint8_t crh_crosshair = (osd_crosshairs_style_e)osdConfig()->crosshairs_style; displayWriteChar(osdGetDisplayPort(), px - 1, py,crh_style_all[crh_crosshair * 3]); displayWriteChar(osdGetDisplayPort(), px, py, crh_style_all[crh_crosshair * 3 + 1]); displayWriteChar(osdGetDisplayPort(), px + 1, py, crh_style_all[crh_crosshair * 3 + 2]); + + if (canvas) { + displayCanvasContextPop(canvas); + } } diff --git a/src/main/io/osd_hud.h b/src/main/io/osd_hud.h index 3845c2347b5..a22ab188462 100644 --- a/src/main/io/osd_hud.h +++ b/src/main/io/osd_hud.h @@ -19,9 +19,11 @@ #include +typedef struct displayCanvas_s displayCanvas_t; + void osdHudClear(void); -void osdHudDrawCrosshair(uint8_t px, uint8_t py); +void osdHudDrawCrosshair(displayCanvas_t *canvas, uint8_t px, uint8_t py); void osdHudDrawHoming(uint8_t px, uint8_t py); void osdHudDrawPoi(uint32_t poiDistance, int16_t poiDirection, int32_t poiAltitude, uint8_t poiType, uint16_t poiSymbol, int16_t poiP1, int16_t poiP2); void osdHudDrawExtras(uint8_t poi_id); From 9bc355ccf3036ac9a8cd529403ad347ed9a9d7a7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 22 Jun 2020 21:01:04 +0100 Subject: [PATCH 078/248] [WIDGETS] Increase AHI redrawing frequency from 10hz to 20hz Since widgets require so few data for each update, we can now afford to double the update rate. --- src/main/io/osd_canvas.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/osd_canvas.c b/src/main/io/osd_canvas.c index c55c988b5e8..801fb1703eb 100644 --- a/src/main/io/osd_canvas.c +++ b/src/main/io/osd_canvas.c @@ -30,7 +30,7 @@ #if defined(USE_CANVAS) -#define AHI_MIN_DRAW_INTERVAL_MS 100 +#define AHI_MIN_DRAW_INTERVAL_MS 50 #define AHI_MAX_DRAW_INTERVAL_MS 1000 #define AHI_CROSSHAIR_MARGIN 6 From 4f3e7a3d5e3da95cb836b20bda2db5adbec6fd36 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 22 Jun 2020 21:13:41 +0100 Subject: [PATCH 079/248] [CMS] Wrap CMS updates in display transactions Otherwise, a display device with transactions might not update the on screen data immediately, since updates outside of transactions might be buffered for performance reasons. This doesn't affect devices that don't support transactions at all. --- src/main/cms/cms.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/main/cms/cms.c b/src/main/cms/cms.c index ee3742b1274..f98d5abf91b 100644 --- a/src/main/cms/cms.c +++ b/src/main/cms/cms.c @@ -1314,6 +1314,7 @@ void cmsUpdate(uint32_t currentTimeUs) rcDelayMs = BUTTON_PAUSE; // Tends to overshoot if BUTTON_TIME } } else { + displayBeginTransaction(pCurrentDisplay, DISPLAY_TRANSACTION_OPT_RESET_DRAWING); // Check if we're yielding and its's time to stop it if (cmsYieldUntil > 0 && currentTimeMs > cmsYieldUntil) { @@ -1339,6 +1340,7 @@ void cmsUpdate(uint32_t currentTimeUs) displayHeartbeat(pCurrentDisplay); lastCmsHeartBeatMs = currentTimeMs; } + displayCommitTransaction(pCurrentDisplay); } // Some key (command), notably flash erase, takes too long to use the From 59f160f21f5fbfeff95a8a8f8abc8d1aa5853fb6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Tue, 7 Jul 2020 21:09:53 +0100 Subject: [PATCH 080/248] [CANVAS] Fix leftover pixels when drawing the home direction arrow MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Since the arrow is taller than the width of a grid slow, it overflows the slot a bit when it's rotated by 90º. Also, simplify the algorithm for drawing it a bit so it transmits a bit less data per redrawing. --- src/main/io/osd.c | 2 +- src/main/io/osd_canvas.c | 33 +++++++++++++++++++++------------ src/main/io/osd_canvas.h | 2 +- src/main/io/osd_common.c | 7 ++----- src/main/io/osd_common.h | 2 +- 5 files changed, 26 insertions(+), 20 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index a340e0ecad3..0d3b7d75d43 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1310,7 +1310,7 @@ static bool osdDrawSingleElement(uint8_t item) else { int homeDirection = GPS_directionToHome - DECIDEGREES_TO_DEGREES(osdGetHeading()); - osdDrawDirArrow(osdDisplayPort, osdGetDisplayPortCanvas(), OSD_DRAW_POINT_GRID(elemPosX, elemPosY), homeDirection, true); + osdDrawDirArrow(osdDisplayPort, osdGetDisplayPortCanvas(), OSD_DRAW_POINT_GRID(elemPosX, elemPosY), homeDirection); } } else { // No home or no fix or unknown heading, blink. diff --git a/src/main/io/osd_canvas.c b/src/main/io/osd_canvas.c index 801fb1703eb..a649b10b5b9 100644 --- a/src/main/io/osd_canvas.c +++ b/src/main/io/osd_canvas.c @@ -120,32 +120,41 @@ void osdCanvasDrawVario(displayPort_t *display, displayCanvas_t *canvas, const o prev = zvel; } -void osdCanvasDrawDirArrow(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, float degrees, bool eraseBefore) +void osdCanvasDrawDirArrow(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, float degrees) { UNUSED(display); + const int top = 6; + const int topInset = -2; + const int bottom = -6; + const int width = 5; + // Since grid slots are not square, when we rotate the arrow + // it overflows horizontally a bit. Making a square-ish arrow + // doesn't look good, so it's better to overstep the grid slot + // boundaries a bit and then clean after ourselves. + const int overflow = 3; + int px; int py; osdDrawPointGetPixels(&px, &py, display, canvas, p); - displayCanvasClipToRect(canvas, px, py, canvas->gridElementWidth, canvas->gridElementHeight); - - if (eraseBefore) { - displayCanvasSetFillColor(canvas, DISPLAY_CANVAS_COLOR_TRANSPARENT); - displayCanvasFillRect(canvas, px, py, canvas->gridElementWidth, canvas->gridElementHeight); - } + displayCanvasClearRect(canvas, px - overflow, py, canvas->gridElementWidth + overflow * 2, canvas->gridElementHeight); displayCanvasSetFillColor(canvas, DISPLAY_CANVAS_COLOR_WHITE); displayCanvasSetStrokeColor(canvas, DISPLAY_CANVAS_COLOR_BLACK); displayCanvasCtmRotate(canvas, -DEGREES_TO_RADIANS(180 + degrees)); displayCanvasCtmTranslate(canvas, px + canvas->gridElementWidth / 2, py + canvas->gridElementHeight / 2); - displayCanvasFillStrokeTriangle(canvas, 0, 6, 5, -6, -5, -6); + + // Main triangle + displayCanvasFillStrokeTriangle(canvas, 0, top, width, bottom, -width, bottom); + // Inset triangle displayCanvasSetFillColor(canvas, DISPLAY_CANVAS_COLOR_TRANSPARENT); - displayCanvasFillStrokeTriangle(canvas, 0, -2, 6, -7, -6, -7); - displayCanvasMoveToPoint(canvas, 6, -7); - displayCanvasSetStrokeColor(canvas, DISPLAY_CANVAS_COLOR_TRANSPARENT); - displayCanvasStrokeLineToPoint(canvas, -6, -7); + displayCanvasFillTriangle(canvas, 0, topInset, width + 1, bottom - 1, -width, bottom - 1); + // Draw bottom strokes of the triangle + displayCanvasMoveToPoint(canvas, -width, bottom - 1); + displayCanvasStrokeLineToPoint(canvas, 0, topInset); + displayCanvasStrokeLineToPoint(canvas, width, bottom - 1); } static void osdDrawArtificialHorizonLevelLine(displayCanvas_t *canvas, int width, int pos, int margin) diff --git a/src/main/io/osd_canvas.h b/src/main/io/osd_canvas.h index b6fc2722ce9..6a8d013e807 100644 --- a/src/main/io/osd_canvas.h +++ b/src/main/io/osd_canvas.h @@ -33,7 +33,7 @@ typedef struct displayCanvas_s displayCanvas_t; typedef struct osdDrawPoint_s osdDrawPoint_t; void osdCanvasDrawVario(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, float zvel); -void osdCanvasDrawDirArrow(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, float degrees, bool eraseBefore); +void osdCanvasDrawDirArrow(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, float degrees); void osdCanvasDrawArtificialHorizon(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, float pitchAngle, float rollAngle); void osdCanvasDrawHeadingGraph(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, int heading); bool osdCanvasDrawSidebars(displayPort_t *display, displayCanvas_t *canvas); diff --git a/src/main/io/osd_common.c b/src/main/io/osd_common.c index 5dc53ea41dd..f5453f4ec64 100644 --- a/src/main/io/osd_common.c +++ b/src/main/io/osd_common.c @@ -88,17 +88,14 @@ void osdDrawVario(displayPort_t *display, displayCanvas_t *canvas, const osdDraw #endif } -void osdDrawDirArrow(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, float degrees, bool eraseBefore) +void osdDrawDirArrow(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, float degrees) { -#if !defined(USE_CANVAS) - UNUSED(eraseBefore); -#endif uint8_t gx; uint8_t gy; #if defined(USE_CANVAS) if (canvas) { - osdCanvasDrawDirArrow(display, canvas, p, degrees, eraseBefore); + osdCanvasDrawDirArrow(display, canvas, p, degrees); } else { #endif osdDrawPointGetGrid(&gx, &gy, display, canvas, p); diff --git a/src/main/io/osd_common.h b/src/main/io/osd_common.h index a878c2f3d4c..054f458a63d 100644 --- a/src/main/io/osd_common.h +++ b/src/main/io/osd_common.h @@ -76,7 +76,7 @@ void osdDrawVario(displayPort_t *display, displayCanvas_t *canvas, const osdDraw // Draws an arrow at the given point, where 0 degrees points to the top of the viewport and // positive angles result in clockwise rotation. If eraseBefore is true, the rect surrouing // the arrow will be erased first (need for e.g. the home arrow, since it uses multiple symbols) -void osdDrawDirArrow(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, float degrees, bool eraseBefore); +void osdDrawDirArrow(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, float degrees); void osdDrawArtificialHorizon(displayPort_t *display, displayCanvas_t *canvas, const osdDrawPoint_t *p, float rollAngle, float pitchAngle); // Draws a heading graph with heading given as 0.1 degree steps i.e. [0, 3600). It uses 9 horizontal // grid slots. From c9cc44920fa58ede91f665ebd1a356439789bf2e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Tue, 7 Jul 2020 21:12:08 +0100 Subject: [PATCH 081/248] [CANVAS] Fix drawn sidebar scroll values for speed The values were not correctly converted the units expected by the sidebar. Fixes https://github.com/FrSkyRC/PixelOSD/issues/3 --- src/main/io/osd_canvas.c | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/main/io/osd_canvas.c b/src/main/io/osd_canvas.c index a649b10b5b9..dedb36db34d 100644 --- a/src/main/io/osd_canvas.c +++ b/src/main/io/osd_canvas.c @@ -511,9 +511,11 @@ static int32_t osdCanvasSidebarGetValue(osd_sidebar_scroll_e scroll) case OSD_UNIT_UK: FALLTHROUGH; case OSD_UNIT_IMPERIAL: - return CENTIMETERS_TO_CENTIFEET(gpsSol.groundSpeed); + // cms/s to (mi/h) * 100 + return gpsSol.groundSpeed * 224 / 100; case OSD_UNIT_METRIC: - return gpsSol.groundSpeed; + // cm/s to (km/h) * 100 + return gpsSol.groundSpeed * 36 / 10; } #endif break; From e8aac7d00610ecf78632e029b377a28ff0c28ed4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Tue, 7 Jul 2020 21:29:23 +0100 Subject: [PATCH 082/248] [OSD] Add osd_force_grid Forces a pixel based OSD to be used in as if it was a grid based OSD. This is intended for development, so the FrSkyOSD simulator can be used for developing features for the MAX7456 based OSDs without needing an analog video to USB adapter. --- src/main/fc/settings.yaml | 6 ++++++ src/main/io/osd.c | 6 +++++- src/main/io/osd.h | 1 + 3 files changed, 12 insertions(+), 1 deletion(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 1a239d8acbc..7700c3586c6 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2836,6 +2836,12 @@ groups: default_value: "DEFAULT" table: osd_ahi_style + - name: osd_force_grid + field: force_grid + type: bool + default_value: "OFF" + description: Force OSD to work in grid mode even if the OSD device supports pixel level access (mainly used for development) + - name: osd_ahi_bordered field: ahi_bordered type: bool diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 0d3b7d75d43..e0b02faf3c6 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2707,7 +2707,11 @@ static void osdCompleteAsyncInitialization(void) osdDisplayIsReady = true; #if defined(USE_CANVAS) - osdDisplayHasCanvas = displayGetCanvas(&osdCanvas, osdDisplayPort); + if (osdConfig()->force_grid) { + osdDisplayHasCanvas = false; + } else { + osdDisplayHasCanvas = displayGetCanvas(&osdCanvas, osdDisplayPort); + } #endif displayBeginTransaction(osdDisplayPort, DISPLAY_TRANSACTION_OPT_RESET_DRAWING); diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 554fd4a82e6..6415b7530b4 100755 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -263,6 +263,7 @@ typedef struct osdConfig_s { bool osd_failsafe_switch_layout; uint8_t plus_code_digits; // Number of digits to use in OSD_PLUS_CODE uint8_t osd_ahi_style; + uint8_t force_grid; // Force a pixel based OSD to use grid mode. uint8_t ahi_bordered; // Only used by the AHI widget uint8_t ahi_width; // In pixels, only used by the AHI widget uint8_t ahi_height; // In pixels, only used by the AHI widget From d225f67cafd0714101c310e4e3c8a5cb37e5ac5e Mon Sep 17 00:00:00 2001 From: SeanTheITGuy Date: Sat, 27 Jun 2020 08:22:26 -0300 Subject: [PATCH 083/248] [TARGET] Initial cut on FLYWOO411 --- docs/Board - FLYWOOF411.md | 33 ++++++ src/main/target/FLYWOOF411/target.c | 41 ++++++++ src/main/target/FLYWOOF411/target.h | 152 +++++++++++++++++++++++++++ src/main/target/FLYWOOF411/target.mk | 19 ++++ 4 files changed, 245 insertions(+) create mode 100755 docs/Board - FLYWOOF411.md create mode 100644 src/main/target/FLYWOOF411/target.c create mode 100644 src/main/target/FLYWOOF411/target.h create mode 100644 src/main/target/FLYWOOF411/target.mk diff --git a/docs/Board - FLYWOOF411.md b/docs/Board - FLYWOOF411.md new file mode 100755 index 00000000000..3c6243de51a --- /dev/null +++ b/docs/Board - FLYWOOF411.md @@ -0,0 +1,33 @@ +# Board - FLYWOOF411 + +![Banggood](https://img.staticbg.com/thumb/view/oaupload/banggood/images/A5/01/79d28a2c-ef4b-4e4f-bab6-14edf66bbb23.jpg) +![Banggood](https://img.staticbg.com/images/oaupload/banggood/images/2E/C5/c14a1e86-4e58-4bc8-85de-8e344cb382b9.jpg) +![Banggood](https://img.staticbg.com/images/oaupload/banggood/images/42/F7/45a68ade-9be1-4fff-afec-bbdd45f0331d.jpg) + +*Note:* This board used to be sold as a 'NOX F4' but is now an updated version similar to a Flywoo F411 + +## Banggood Specification: +* Model: Upgrade Betaflight F4 Noxe V1 +* Version: Acro Version / Deluxe Version +* Acro Version: Without Barometer and Blackbox +* Deluxe Version: With Barometer and Blackbox +* CPU: STM32F411C +* MPU: MPU6000 +* Input Voltage: Support 2-6S Lipo Input +* Built-In Betaflight OSD +* Built-in 5V @ 2.5A BEC & 8V @ 3A BEC +* 3.3V +* 4.5V powered by USB +* DShot, Proshot ESC +* Support Spektrum 1024 /2048 , SBUS, IBUS, PPM +* Built in flash for blackbox 16MB +* Support WS2812 LED strip +* Size: 27x27mm +* Mounting Hole: 20x20mm , M2.5 +* Weight: 4.3g +* DSM / IBUS/SBUS Receiver, choose UART RX2 +* PPM Receiver, don't need choose UART Port + + +## Where to buy: +* [Banggood](https://inavflight.com/shop/s/bg/1310419) diff --git a/src/main/target/FLYWOOF411/target.c b/src/main/target/FLYWOOF411/target.c new file mode 100644 index 00000000000..56a44b256d7 --- /dev/null +++ b/src/main/target/FLYWOOF411/target.c @@ -0,0 +1,41 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include +#include "drivers/io.h" +#include "drivers/dma.h" +#include "drivers/timer.h" +#include "drivers/bus.h" +#include "drivers/pwm_mapping.h" + + +const timerHardware_t timerHardware[] = { + DEF_TIM(TIM9, CH1, PA2, TIM_USE_PPM, 0, 0), // PPM IN + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S1_OUT 2,1 + DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S2_OUT 2,2 + DEF_TIM(TIM1, CH3, PA10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3_OUT 2,6 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S4_OUT 1,7 + + DEF_TIM(TIM3, CH4, PB1, TIM_USE_ANY, 0, 0), // RSSI 1,2 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_ANY, 0, 1), // RX2 1,0 + DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // LED 1,5 + +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/FLYWOOF411/target.h b/src/main/target/FLYWOOF411/target.h new file mode 100644 index 00000000000..3f2d63e993b --- /dev/null +++ b/src/main/target/FLYWOOF411/target.h @@ -0,0 +1,152 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + + +#define TARGET_BOARD_IDENTIFIER "FLYWOOF411" +#define USBD_PRODUCT_STRING "FlywooF411" + +#define LED0 PC13 + +#define BEEPER PC14 +#define BEEPER_INVERTED + + +// *************** SPI ********************** +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + + +// *************** SPI Gyro & ACC ********************** + +#define USE_IMU_MPU6000 +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_BUS BUS_SPI1 +#define IMU_MPU6000_ALIGN CW180_DEG + +#define USE_IMU_ICM20689 +#define ICM20689_CS_PIN PA4 +#define ICM20689_SPI_BUS BUS_SPI1 +#define IMU_ICM20689_ALIGN CW180_DEG + +#define USE_EXTI +#define GYRO_INT_EXTI PB3 +#define USE_MPU_DATA_READY_SIGNAL + +// *************** Baro ***************************** + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +// *************** SPI OSD ***************************** +#define USE_OSD +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +// *************** SPI FLASH ************************** +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_CS_PIN PB2 +#define M25P16_SPI_BUS BUS_SPI2 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +// *************** UART ***************************** +//#define USE_UART_INVERTER + +#define USE_VCP + +#define USE_UART1 +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +// #define INVERTER_PIN_UART2 PC14 +//#define INVERTER_PIN_UART2_RX PC14 // PC14 used as inverter select GPIO + +#define USE_SOFTSERIAL1 +#define SOFTSERIAL_1_TX_PIN PA2 // Workaround for softserial not initializing with only RX +#define SOFTSERIAL_1_RX_PIN PA2 // Backdoor timer on UART2_TX, used for ESC telemetry + +#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART2, SOFTSERIAL1 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART2 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC_CHANNEL_1_PIN PA1 +#define ADC_CHANNEL_2_PIN PA0 +#define ADC_CHANNEL_3_PIN PB1 + +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 +#define VBAT_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 + +// *************** LED2812 ************************ +#define USE_LED_STRIP +#define WS2811_PIN PA15 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST6_HANDLER +#define WS2811_DMA_STREAM DMA1_Stream6 +#define WS2811_DMA_CHANNEL DMA_Channel_6 + +// *************** OTHERS ************************* +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL) + +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIALSHOT +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) + +#define MAX_PWM_OUTPUT_PORTS 4 + + diff --git a/src/main/target/FLYWOOF411/target.mk b/src/main/target/FLYWOOF411/target.mk new file mode 100644 index 00000000000..f83631e49e3 --- /dev/null +++ b/src/main/target/FLYWOOF411/target.mk @@ -0,0 +1,19 @@ +F411_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH MSC + +TARGET_SRC = \ + drivers/accgyro/accgyro_mpu6000.c \ + drivers/accgyro/accgyro_mpu6500.c \ + drivers/accgyro/accgyro_icm20689.c \ + drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_bmp085.c \ + drivers/barometer/barometer_ms56xx.c \ + drivers/compass/compass_hmc5883l.c \ + drivers/compass/compass_qmc5883l.c \ + drivers/compass/compass_ist8310.c \ + drivers/compass/compass_ist8308.c \ + drivers/compass/compass_mag3110.c \ + drivers/compass/compass_lis3mdl.c \ + drivers/light_ws2811strip.c \ + drivers/flash_m25p16.c \ + drivers/max7456.c From 7caa8b28da941bd4a9eea3da9f9102e145e539b5 Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Tue, 21 Jul 2020 15:50:00 +0200 Subject: [PATCH 084/248] [TARGET] FLYWOOF411 fixups --- src/main/target/FLYWOOF411/target.h | 47 +++++++++++----------------- src/main/target/FLYWOOF411/target.mk | 10 +++--- 2 files changed, 23 insertions(+), 34 deletions(-) diff --git a/src/main/target/FLYWOOF411/target.h b/src/main/target/FLYWOOF411/target.h index 3f2d63e993b..4c471a044a7 100644 --- a/src/main/target/FLYWOOF411/target.h +++ b/src/main/target/FLYWOOF411/target.h @@ -17,9 +17,8 @@ #pragma once - -#define TARGET_BOARD_IDENTIFIER "FLYWOOF411" -#define USBD_PRODUCT_STRING "FlywooF411" +#define TARGET_BOARD_IDENTIFIER "FW41" +#define USBD_PRODUCT_STRING "FLYWOOF411" #define LED0 PC13 @@ -30,14 +29,14 @@ // *************** SPI ********************** #define USE_SPI #define USE_SPI_DEVICE_1 -#define SPI1_SCK_PIN PA5 -#define SPI1_MISO_PIN PA6 -#define SPI1_MOSI_PIN PA7 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 #define USE_SPI_DEVICE_2 -#define SPI2_SCK_PIN PB13 -#define SPI2_MISO_PIN PB14 -#define SPI2_MOSI_PIN PB15 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 // *************** SPI Gyro & ACC ********************** @@ -64,7 +63,7 @@ #define I2C1_SDA PB9 #define USE_BARO -#define BARO_I2C_BUS BUS_I2C1 +#define BARO_I2C_BUS BUS_I2C1 #define USE_BARO_BMP280 #define USE_BARO_MS5611 @@ -91,8 +90,6 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT // *************** UART ***************************** -//#define USE_UART_INVERTER - #define USE_VCP #define USE_UART1 @@ -100,17 +97,14 @@ #define UART1_RX_PIN PB7 #define USE_UART2 -#define UART2_TX_PIN PA2 +#define UART2_TX_PIN NONE //PA2 #define UART2_RX_PIN PA3 -// #define INVERTER_PIN_UART2 PC14 -//#define INVERTER_PIN_UART2_RX PC14 // PC14 used as inverter select GPIO - #define USE_SOFTSERIAL1 -#define SOFTSERIAL_1_TX_PIN PA2 // Workaround for softserial not initializing with only RX -#define SOFTSERIAL_1_RX_PIN PA2 // Backdoor timer on UART2_TX, used for ESC telemetry +#define SOFTSERIAL_1_TX_PIN PA2 // Clash with TX2, possible to use as S.Port or VTX control +#define SOFTSERIAL_1_RX_PIN PA2 -#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART2, SOFTSERIAL1 +#define SERIAL_PORT_COUNT 4 // VCP, USART1, USART2, SS1 #define DEFAULT_RX_TYPE RX_TYPE_SERIAL #define SERIALRX_PROVIDER SERIALRX_SBUS @@ -118,24 +112,21 @@ // *************** ADC ***************************** #define USE_ADC -#define ADC_INSTANCE ADC1 +#define ADC_INSTANCE ADC1 #define ADC_CHANNEL_1_PIN PA1 #define ADC_CHANNEL_2_PIN PA0 #define ADC_CHANNEL_3_PIN PB1 -#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 -#define VBAT_ADC_CHANNEL ADC_CHN_2 -#define RSSI_ADC_CHANNEL ADC_CHN_3 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 +#define VBAT_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 // *************** LED2812 ************************ #define USE_LED_STRIP #define WS2811_PIN PA15 -#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST6_HANDLER -#define WS2811_DMA_STREAM DMA1_Stream6 -#define WS2811_DMA_CHANNEL DMA_Channel_6 // *************** OTHERS ************************* -#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL) +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_OSD | FEATURE_VBAT | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL) #define USE_DSHOT #define USE_ESC_SENSOR @@ -148,5 +139,3 @@ #define TARGET_IO_PORTD (BIT(2)) #define MAX_PWM_OUTPUT_PORTS 4 - - diff --git a/src/main/target/FLYWOOF411/target.mk b/src/main/target/FLYWOOF411/target.mk index f83631e49e3..e6cb4cec024 100644 --- a/src/main/target/FLYWOOF411/target.mk +++ b/src/main/target/FLYWOOF411/target.mk @@ -2,13 +2,13 @@ F411_TARGETS += $(TARGET) FEATURES += VCP ONBOARDFLASH MSC TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_icm20689.c \ + drivers/accgyro/accgyro_mpu6000.c \ + drivers/accgyro/accgyro_mpu6500.c \ + drivers/accgyro/accgyro_icm20689.c \ drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_bmp085.c \ + drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ + drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ drivers/compass/compass_ist8310.c \ drivers/compass/compass_ist8308.c \ From a0db81090881479811f6378acf32fc82fddd4cdb Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Tue, 21 Jul 2020 16:19:12 +0200 Subject: [PATCH 085/248] [TARGET] Initial cut on FLYWOOF7DUAL target --- src/main/target/FLYWOOF7DUAL/target.c | 47 +++++++ src/main/target/FLYWOOF7DUAL/target.h | 164 +++++++++++++++++++++++++ src/main/target/FLYWOOF7DUAL/target.mk | 19 +++ 3 files changed, 230 insertions(+) create mode 100644 src/main/target/FLYWOOF7DUAL/target.c create mode 100644 src/main/target/FLYWOOF7DUAL/target.h create mode 100644 src/main/target/FLYWOOF7DUAL/target.mk diff --git a/src/main/target/FLYWOOF7DUAL/target.c b/src/main/target/FLYWOOF7DUAL/target.c new file mode 100644 index 00000000000..6d49f5a5897 --- /dev/null +++ b/src/main/target/FLYWOOF7DUAL/target.c @@ -0,0 +1,47 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include +#include +#include "drivers/io.h" +#include "drivers/bus.h" +#include "drivers/timer.h" +#include "drivers/sensor.h" +#include "drivers/pwm_mapping.h" + +// IMU 1 +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000_1, DEVHW_MPU6000, GYRO_1_SPI_BUS, GYRO_1_CS_PIN, GYRO_1_EXTI_PIN, 0, DEVFLAGS_NONE, GYRO_1_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500_1, DEVHW_MPU6500, GYRO_1_SPI_BUS, GYRO_1_CS_PIN, GYRO_1_EXTI_PIN, 0, DEVFLAGS_NONE, GYRO_1_ALIGN); + +// IMU 2 +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000_2, DEVHW_MPU6000, GYRO_2_SPI_BUS, GYRO_2_CS_PIN, GYRO_2_EXTI_PIN, 1, DEVFLAGS_NONE, GYRO_2_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500_2, DEVHW_MPU6500, GYRO_2_SPI_BUS, GYRO_2_CS_PIN, GYRO_2_EXTI_PIN, 1, DEVFLAGS_NONE, GYRO_2_ALIGN); + +const timerHardware_t timerHardware[] = { + DEF_TIM(TIM8, CH1, PC6, TIM_USE_PPM, 0, 0), // PPM&SBUS + + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 - D(1,2) + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 - D(1,4) + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 - D(1,6) + DEF_TIM(TIM2, CH1, PA15, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 - D(1,5) + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 - D(2,4) + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 - D(2,1) + + DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0), // LED STRIP(1,5) +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/FLYWOOF7DUAL/target.h b/src/main/target/FLYWOOF7DUAL/target.h new file mode 100644 index 00000000000..faad1abbaee --- /dev/null +++ b/src/main/target/FLYWOOF7DUAL/target.h @@ -0,0 +1,164 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#define TARGET_BOARD_IDENTIFIER "FWF7" +#define USBD_PRODUCT_STRING "FLYWOOF7DUAL" + +/*** Indicators ***/ +#define LED0 PC15 +#define BEEPER PC14 +#define BEEPER_INVERTED + +/*** IMU sensors ***/ +#define USE_EXTI + +// We use dual IMU sensors, they have to be described in the target file +#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS +#define USE_MPU_DATA_READY_SIGNAL +#define USE_DUAL_GYRO + +#define USE_IMU_MPU6000 +#define USE_IMU_MPU6500 + +#define GYRO_1_SPI_BUS BUS_SPI1 +#define GYRO_1_CS_PIN PA4 +#define GYRO_1_EXTI_PIN PC3 +#define GYRO_1_ALIGN CW180_DEG_FLIP + +#define GYRO_2_SPI_BUS BUS_SPI1 +#define GYRO_2_CS_PIN PB2 +#define GYRO_2_EXTI_PIN PC4 +#define GYRO_2_ALIGN CW270_DEG + +/*** SPI/I2C bus ***/ +#define USE_SPI +#define USE_SPI_DEVICE_1 // Gyro 1/2 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_SPI_DEVICE_2 // MAX7456 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_SPI_DEVICE_3 // FLASH +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PB5 + +#define USE_I2C +#define USE_I2C_DEVICE_1 // I2C pads +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 + +/*** Onboard flash ***/ +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_CS_PIN PC13 +#define M25P16_SPI_BUS BUS_SPI3 + +/*** OSD ***/ +#define USE_OSD +#define USE_MAX7456 +#define MAX7456_CS_PIN PB12 +#define MAX7456_SPI_BUS BUS_SPI2 + +/*** Serial ports ***/ +#define USE_VCP + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 + +#define USE_UART3 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 + +#define USE_UART4 +#define UART4_TX_PIN PA0 +#define UART4_RX_PIN PA1 + +#define USE_UART5 +#define UART5_TX_PIN PC12 +#define UART5_RX_PIN PD2 + +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +#define SERIAL_PORT_COUNT 7 + +/*** BARO & MAG ***/ +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +/*** ADC ***/ +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 +#define ADC_CHANNEL_3_PIN PC2 + +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 +#define VBAT_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 + + +/*** PINIO ***/ +/* +#define USE_PINIO +#define PINIO1_PIN PB0 // VTX power switcher +#define PINIO2_PIN PB9 // 2xCamera switcher +#define USE_PINIOBOX +*/ + +/*** LED STRIP ***/ +#define USE_LED_STRIP +#define WS2811_PIN PA8 + +/*** Default settings ***/ +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT +#define CURRENT_METER_SCALE_DEFAULT 170 +#define SERIALRX_UART SERIAL_PORT_USART1 +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS + +/*** Timer/PWM output ***/ +#define USE_SERIAL_4WAY_BLHELI_INTERFACE +#define MAX_PWM_OUTPUT_PORTS 6 +#define USE_DSHOT +#define USE_ESC_SENSOR + +/*** Used pins ***/ +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) diff --git a/src/main/target/FLYWOOF7DUAL/target.mk b/src/main/target/FLYWOOF7DUAL/target.mk new file mode 100644 index 00000000000..2cadc1ff2f8 --- /dev/null +++ b/src/main/target/FLYWOOF7DUAL/target.mk @@ -0,0 +1,19 @@ +F7X2RE_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH MSC + +TARGET_SRC = \ + drivers/accgyro/accgyro_mpu6000.c \ + drivers/accgyro/accgyro_mpu6500.c \ + drivers/accgyro/accgyro_icm20689.c \ + drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_bmp085.c \ + drivers/barometer/barometer_ms56xx.c \ + drivers/compass/compass_hmc5883l.c \ + drivers/compass/compass_qmc5883l.c \ + drivers/compass/compass_ist8310.c \ + drivers/compass/compass_ist8308.c \ + drivers/compass/compass_mag3110.c \ + drivers/compass/compass_lis3mdl.c \ + drivers/light_ws2811strip.c \ + drivers/flash_m25p16.c \ + drivers/max7456.c From 17948896d750b9829f92fecf18d7c23bf749a459 Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Tue, 21 Jul 2020 17:26:58 +0200 Subject: [PATCH 086/248] [TARGET] Enable PINIO on FLYWOOF7DUAL target; Add FLYWOOF411 and F7DUAL to release targets --- make/release.mk | 2 ++ src/main/target/FLYWOOF7DUAL/target.c | 8 ++++++++ src/main/target/FLYWOOF7DUAL/target.h | 6 ++---- 3 files changed, 12 insertions(+), 4 deletions(-) diff --git a/make/release.mk b/make/release.mk index 1ca0439bdab..7eb829efa8a 100644 --- a/make/release.mk +++ b/make/release.mk @@ -35,3 +35,5 @@ RELEASE_TARGETS += IFLIGHTF7_TWING IFLIGHTF4_TWING IFLIGHTF4_SUCCEXD RELEASE_TARGETS += AIKONF4 RELEASE_TARGETS += ZEEZF7 HGLRCF722 + +RELEASE_TARGETS += FLYWOOF7DUAL FLYWOOF411 diff --git a/src/main/target/FLYWOOF7DUAL/target.c b/src/main/target/FLYWOOF7DUAL/target.c index 6d49f5a5897..d9dc7ccc9bc 100644 --- a/src/main/target/FLYWOOF7DUAL/target.c +++ b/src/main/target/FLYWOOF7DUAL/target.c @@ -15,6 +15,7 @@ * along with INAV. If not, see . */ +#include #include #include #include "drivers/io.h" @@ -22,6 +23,7 @@ #include "drivers/timer.h" #include "drivers/sensor.h" #include "drivers/pwm_mapping.h" +#include "io/piniobox.h" // IMU 1 BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000_1, DEVHW_MPU6000, GYRO_1_SPI_BUS, GYRO_1_CS_PIN, GYRO_1_EXTI_PIN, 0, DEVFLAGS_NONE, GYRO_1_ALIGN); @@ -45,3 +47,9 @@ const timerHardware_t timerHardware[] = { }; const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); + +void targetConfiguration(void) +{ + pinioBoxConfigMutable()->permanentId[0] = 47; + pinioBoxConfigMutable()->permanentId[1] = 48; +} diff --git a/src/main/target/FLYWOOF7DUAL/target.h b/src/main/target/FLYWOOF7DUAL/target.h index faad1abbaee..419d5ba9e48 100644 --- a/src/main/target/FLYWOOF7DUAL/target.h +++ b/src/main/target/FLYWOOF7DUAL/target.h @@ -133,12 +133,10 @@ /*** PINIO ***/ -/* #define USE_PINIO -#define PINIO1_PIN PB0 // VTX power switcher -#define PINIO2_PIN PB9 // 2xCamera switcher #define USE_PINIOBOX -*/ +#define PINIO1_PIN PB0 +#define PINIO2_PIN PB9 /*** LED STRIP ***/ #define USE_LED_STRIP From d2f05b7e23cd6a825385cb42d8ead221dcefec55 Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Thu, 23 Jul 2020 13:19:04 +0200 Subject: [PATCH 087/248] [NAV] Cleanup pos/vel controllers --- src/main/navigation/navigation_fixedwing.c | 46 +------ src/main/navigation/navigation_multicopter.c | 120 +++++++------------ 2 files changed, 51 insertions(+), 115 deletions(-) diff --git a/src/main/navigation/navigation_fixedwing.c b/src/main/navigation/navigation_fixedwing.c index 389d934b57f..ae700e3c1fd 100755 --- a/src/main/navigation/navigation_fixedwing.c +++ b/src/main/navigation/navigation_fixedwing.c @@ -158,19 +158,7 @@ static void updateAltitudeVelocityAndPitchController_FW(timeDelta_t deltaMicros) void applyFixedWingAltitudeAndThrottleController(timeUs_t currentTimeUs) { - static timeUs_t previousTimePositionUpdate; // Occurs @ altitude sensor update rate (max MAX_ALTITUDE_UPDATE_RATE_HZ) - static timeUs_t previousTimeUpdate; // Occurs @ looptime rate - - const timeDelta_t deltaMicros = currentTimeUs - previousTimeUpdate; - previousTimeUpdate = currentTimeUs; - - // If last time Z-controller was called is too far in the past - ignore it (likely restarting altitude controller) - if (deltaMicros > HZ2US(MIN_POSITION_UPDATE_RATE_HZ)) { - previousTimeUpdate = currentTimeUs; - previousTimePositionUpdate = currentTimeUs; - resetFixedWingAltitudeController(); - return; - } + static timeUs_t previousTimePositionUpdate = 0; // Occurs @ altitude sensor update rate (max MAX_ALTITUDE_UPDATE_RATE_HZ) if ((posControl.flags.estAltStatus >= EST_USABLE)) { if (posControl.flags.verticalPositionDataNew) { @@ -182,7 +170,7 @@ void applyFixedWingAltitudeAndThrottleController(timeUs_t currentTimeUs) updateAltitudeVelocityAndPitchController_FW(deltaMicrosPositionUpdate); } else { - // due to some glitch position update has not occurred in time, reset altitude controller + // Position update has not occurred in time (first iteration or glitch), reset altitude controller resetFixedWingAltitudeController(); } @@ -398,19 +386,7 @@ static void updatePositionHeadingController_FW(timeUs_t currentTimeUs, timeDelta void applyFixedWingPositionController(timeUs_t currentTimeUs) { - static timeUs_t previousTimePositionUpdate; // Occurs @ GPS update rate - static timeUs_t previousTimeUpdate; // Occurs @ looptime rate - - const timeDelta_t deltaMicros = currentTimeUs - previousTimeUpdate; - previousTimeUpdate = currentTimeUs; - - // If last position update was too long in the past - ignore it (likely restarting altitude controller) - if (deltaMicros > HZ2US(MIN_POSITION_UPDATE_RATE_HZ)) { - previousTimeUpdate = currentTimeUs; - previousTimePositionUpdate = currentTimeUs; - resetFixedWingPositionController(); - return; - } + static timeUs_t previousTimePositionUpdate = 0; // Occurs @ GPS update rate // Apply controller only if position source is valid. In absence of valid pos sensor (GPS loss), we'd stick in forced ANGLE mode if ((posControl.flags.estPosStatus >= EST_USABLE)) { @@ -429,6 +405,7 @@ void applyFixedWingPositionController(timeUs_t currentTimeUs) updatePositionHeadingController_FW(currentTimeUs, deltaMicrosPositionUpdate); } else { + // Position update has not occurred in time (first iteration or glitch), reset altitude controller resetFixedWingPositionController(); } @@ -448,19 +425,7 @@ void applyFixedWingPositionController(timeUs_t currentTimeUs) int16_t applyFixedWingMinSpeedController(timeUs_t currentTimeUs) { - static timeUs_t previousTimePositionUpdate; // Occurs @ GPS update rate - static timeUs_t previousTimeUpdate; // Occurs @ looptime rate - - const timeDelta_t deltaMicros = currentTimeUs - previousTimeUpdate; - previousTimeUpdate = currentTimeUs; - - // If last position update was too long in the past - ignore it (likely restarting altitude controller) - if (deltaMicros > HZ2US(MIN_POSITION_UPDATE_RATE_HZ)) { - previousTimeUpdate = currentTimeUs; - previousTimePositionUpdate = currentTimeUs; - throttleSpeedAdjustment = 0; - return 0; - } + static timeUs_t previousTimePositionUpdate = 0; // Occurs @ GPS update rate // Apply controller only if position source is valid if ((posControl.flags.estPosStatus >= EST_USABLE)) { @@ -480,6 +445,7 @@ int16_t applyFixedWingMinSpeedController(timeUs_t currentTimeUs) throttleSpeedAdjustment = constrainf(throttleSpeedAdjustment, 0.0f, 500.0f); } else { + // Position update has not occurred in time (first iteration or glitch), reset altitude controller throttleSpeedAdjustment = 0; } diff --git a/src/main/navigation/navigation_multicopter.c b/src/main/navigation/navigation_multicopter.c index 964cb980fef..52235c59309 100755 --- a/src/main/navigation/navigation_multicopter.c +++ b/src/main/navigation/navigation_multicopter.c @@ -199,35 +199,13 @@ void resetMulticopterAltitudeController(void) navPidReset(&posControl.pids.surface); posControl.rcAdjustment[THROTTLE] = 0; - if (prepareForTakeoffOnReset) { - /* If we are preparing for takeoff - start with lowset possible climb rate, adjust alt target and make sure throttle doesn't jump */ - posControl.desiredState.vel.z = -navConfig()->general.max_manual_climb_rate; - posControl.desiredState.pos.z = posToUse->pos.z - (navConfig()->general.max_manual_climb_rate / posControl.pids.pos[Z].param.kP); - posControl.pids.vel[Z].integrator = -500.0f; - pt1FilterReset(&altholdThrottleFilterState, -500.0f); - prepareForTakeoffOnReset = false; - } - else { - posControl.desiredState.vel.z = posToUse->vel.z; // Gradually transition from current climb - pt1FilterReset(&altholdThrottleFilterState, 0.0f); - } + posControl.desiredState.vel.z = posToUse->vel.z; // Gradually transition from current climb + pt1FilterReset(&altholdThrottleFilterState, 0.0f); } static void applyMulticopterAltitudeController(timeUs_t currentTimeUs) { - static timeUs_t previousTimePositionUpdate; // Occurs @ altitude sensor update rate (max MAX_ALTITUDE_UPDATE_RATE_HZ) - static timeUs_t previousTimeUpdate; // Occurs @ looptime rate - - const timeDelta_t deltaMicros = currentTimeUs - previousTimeUpdate; - previousTimeUpdate = currentTimeUs; - - // If last position update was too long in the past - ignore it (likely restarting altitude controller) - if (deltaMicros > HZ2US(MIN_POSITION_UPDATE_RATE_HZ)) { - previousTimeUpdate = currentTimeUs; - previousTimePositionUpdate = currentTimeUs; - resetMulticopterAltitudeController(); - return; - } + static timeUs_t previousTimePositionUpdate = 0; // Occurs @ altitude sensor update rate (max MAX_ALTITUDE_UPDATE_RATE_HZ) // If we have an update on vertical position data - update velocity and accel targets if (posControl.flags.verticalPositionDataNew) { @@ -236,11 +214,23 @@ static void applyMulticopterAltitudeController(timeUs_t currentTimeUs) // Check if last correction was too log ago - ignore this update if (deltaMicrosPositionUpdate < HZ2US(MIN_POSITION_UPDATE_RATE_HZ)) { + // If we are preparing for takeoff - start with lowset possible climb rate, adjust alt target and make sure throttle doesn't jump + if (prepareForTakeoffOnReset) { + const navEstimatedPosVel_t * posToUse = navGetCurrentActualPositionAndVelocity(); + + posControl.desiredState.vel.z = -navConfig()->general.max_manual_climb_rate; + posControl.desiredState.pos.z = posToUse->pos.z - (navConfig()->general.max_manual_climb_rate / posControl.pids.pos[Z].param.kP); + posControl.pids.vel[Z].integrator = -500.0f; + pt1FilterReset(&altholdThrottleFilterState, -500.0f); + prepareForTakeoffOnReset = false; + } + + // Execute actual altitude controllers updateAltitudeVelocityController_MC(deltaMicrosPositionUpdate); updateAltitudeThrottleController_MC(deltaMicrosPositionUpdate); } else { - // due to some glitch position update has not occurred in time, reset altitude controller + // Position update has not occurred in time (first start or glitch), reset altitude controller resetMulticopterAltitudeController(); } @@ -625,24 +615,12 @@ static void updatePositionAccelController_MC(timeDelta_t deltaMicros, float maxA static void applyMulticopterPositionController(timeUs_t currentTimeUs) { - static timeUs_t previousTimePositionUpdate; // Occurs @ GPS update rate - static timeUs_t previousTimeUpdate; // Occurs @ looptime rate - - const timeDelta_t deltaMicros = currentTimeUs - previousTimeUpdate; - previousTimeUpdate = currentTimeUs; + static timeUs_t previousTimePositionUpdate = 0; // Occurs @ GPS update rate bool bypassPositionController; // We should passthrough rcCommand is adjusting position in GPS_ATTI mode bypassPositionController = (navConfig()->general.flags.user_control_mode == NAV_GPS_ATTI) && posControl.flags.isAdjustingPosition; - // If last call to controller was too long in the past - ignore it (likely restarting position controller) - if (deltaMicros > HZ2US(MIN_POSITION_UPDATE_RATE_HZ)) { - previousTimeUpdate = currentTimeUs; - previousTimePositionUpdate = currentTimeUs; - resetMulticopterPositionController(); - return; - } - // Apply controller only if position source is valid. In absence of valid pos sensor (GPS loss), we'd stick in forced ANGLE mode // and pilots input would be passed thru to PID controller if ((posControl.flags.estPosStatus >= EST_USABLE)) { @@ -660,6 +638,7 @@ static void applyMulticopterPositionController(timeUs_t currentTimeUs) updatePositionAccelController_MC(deltaMicrosPositionUpdate, NAV_ACCELERATION_XY_MAX, maxSpeed); } else { + // Position update has not occurred in time (first start or glitch), reset altitude controller resetMulticopterPositionController(); } } @@ -749,48 +728,14 @@ bool isMulticopterLandingDetected(void) *-----------------------------------------------------------*/ static void applyMulticopterEmergencyLandingController(timeUs_t currentTimeUs) { - static timeUs_t previousTimeUpdate; - static timeUs_t previousTimePositionUpdate; - const timeDelta_t deltaMicros = currentTimeUs - previousTimeUpdate; - previousTimeUpdate = currentTimeUs; + static timeUs_t previousTimePositionUpdate = 0; /* Attempt to stabilise */ rcCommand[ROLL] = 0; rcCommand[PITCH] = 0; rcCommand[YAW] = 0; - if ((posControl.flags.estAltStatus >= EST_USABLE)) { - // If last position update was too long in the past - ignore it (likely restarting altitude controller) - if (deltaMicros > HZ2US(MIN_POSITION_UPDATE_RATE_HZ)) { - previousTimeUpdate = currentTimeUs; - previousTimePositionUpdate = currentTimeUs; - resetMulticopterAltitudeController(); - return; - } - - if (posControl.flags.verticalPositionDataNew) { - const timeDelta_t deltaMicrosPositionUpdate = currentTimeUs - previousTimePositionUpdate; - previousTimePositionUpdate = currentTimeUs; - - // Check if last correction was too log ago - ignore this update - if (deltaMicrosPositionUpdate < HZ2US(MIN_POSITION_UPDATE_RATE_HZ)) { - updateClimbRateToAltitudeController(-1.0f * navConfig()->general.emerg_descent_rate, ROC_TO_ALT_NORMAL); - updateAltitudeVelocityController_MC(deltaMicrosPositionUpdate); - updateAltitudeThrottleController_MC(deltaMicrosPositionUpdate); - } - else { - // due to some glitch position update has not occurred in time, reset altitude controller - resetMulticopterAltitudeController(); - } - - // Indicate that information is no longer usable - posControl.flags.verticalPositionDataConsumed = 1; - } - - // Update throttle controller - rcCommand[THROTTLE] = constrain((int16_t)navConfig()->mc.hover_throttle + posControl.rcAdjustment[THROTTLE], getThrottleIdleValue(), motorConfig()->maxthrottle); - } - else { + if ((posControl.flags.estAltStatus < EST_USABLE)) { /* Sensors has gone haywire, attempt to land regardless */ if (failsafeConfig()->failsafe_procedure == FAILSAFE_PROCEDURE_DROP_IT) { rcCommand[THROTTLE] = getThrottleIdleValue(); @@ -798,7 +743,32 @@ static void applyMulticopterEmergencyLandingController(timeUs_t currentTimeUs) else { rcCommand[THROTTLE] = failsafeConfig()->failsafe_throttle; } + + return; } + + // Normal sensor data + if (posControl.flags.verticalPositionDataNew) { + const timeDelta_t deltaMicrosPositionUpdate = currentTimeUs - previousTimePositionUpdate; + previousTimePositionUpdate = currentTimeUs; + + // Check if last correction was too log ago - ignore this update + if (deltaMicrosPositionUpdate < HZ2US(MIN_POSITION_UPDATE_RATE_HZ)) { + updateClimbRateToAltitudeController(-1.0f * navConfig()->general.emerg_descent_rate, ROC_TO_ALT_NORMAL); + updateAltitudeVelocityController_MC(deltaMicrosPositionUpdate); + updateAltitudeThrottleController_MC(deltaMicrosPositionUpdate); + } + else { + // due to some glitch position update has not occurred in time, reset altitude controller + resetMulticopterAltitudeController(); + } + + // Indicate that information is no longer usable + posControl.flags.verticalPositionDataConsumed = 1; + } + + // Update throttle controller + rcCommand[THROTTLE] = constrain((int16_t)navConfig()->mc.hover_throttle + posControl.rcAdjustment[THROTTLE], getThrottleIdleValue(), motorConfig()->maxthrottle); } /*----------------------------------------------------------- From 3bdc3dd501313e603abb92ab384baf1dc9ea27e1 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 24 Jul 2020 18:28:44 +0200 Subject: [PATCH 088/248] Add magGain to MSP frame --- src/main/fc/fc_msp.c | 24 ++++++++++++++++++++++++ src/main/sensors/compass.c | 5 ++++- 2 files changed, 28 insertions(+), 1 deletion(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 076b7077f1d..716e3ad49b3 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -1283,6 +1283,17 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF #else sbufWriteU16(dst, 0); #endif + + #ifdef USE_MAG + sbufWriteU16(dst, compassConfig()->magGain[X]); + sbufWriteU16(dst, compassConfig()->magGain[Y]); + sbufWriteU16(dst, compassConfig()->magGain[Z]); + #else + sbufWriteU16(dst, 0); + sbufWriteU16(dst, 0); + sbufWriteU16(dst, 0); + #endif + break; case MSP_POSITION_ESTIMATION_CONFIG: @@ -2190,6 +2201,19 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) if (dataSize >= 20) { opticalFlowConfigMutable()->opflow_scale = sbufReadU16(src) / 256.0f; } +#endif +#ifdef USE_MAG + if (dataSize >= 22) { + compassConfigMutable()->magGain[X] = sbufReadU16(src); + compassConfigMutable()->magGain[Y] = sbufReadU16(src); + compassConfigMutable()->magGain[Z] = sbufReadU16(src); + } +#else + if (dataSize >= 22) { + sbufReadU16(src); + sbufReadU16(src); + sbufReadU16(src); + } #endif } else return MSP_RESULT_ERROR; diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index 90fb2c5ac0c..87841fecd8f 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -337,7 +337,10 @@ void compassUpdate(timeUs_t currentTimeUs) static int magGain[XYZ_AXIS_COUNT] = {-4096, -4096, -4096}; // Check magZero - if ((compassConfig()->magZero.raw[X] == 0) && (compassConfig()->magZero.raw[Y] == 0) && (compassConfig()->magZero.raw[Z] == 0)) { + if ( + (compassConfig()->magZero.raw[X] == 0 && compassConfig()->magZero.raw[Y] == 0 && compassConfig()->magZero.raw[Z] == 0) || + compassConfig()->magGain[X] == 0 || compassConfig()->magGain[Y] == 0 || compassConfig()->magGain[Z] == 0 + ) { DISABLE_STATE(COMPASS_CALIBRATED); } else { From cf3db04fda6fd289f65764056d0f0d9d890dd35b Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 24 Jul 2020 18:57:21 +0200 Subject: [PATCH 089/248] Zero gain on mag calibration start --- src/main/sensors/compass.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index 87841fecd8f..37314601bd5 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -363,6 +363,7 @@ void compassUpdate(timeUs_t currentTimeUs) for (int axis = 0; axis < 3; axis++) { compassConfigMutable()->magZero.raw[axis] = 0; + compassConfigMutable()->magGain[axis] = 0; magPrev[axis] = 0; } From e520db67f8215b072ab6b0e0e95e0b704c5ffe50 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 24 Jul 2020 19:19:51 +0200 Subject: [PATCH 090/248] Target for Foxeer F722 V2 --- docs/Board - FOXEERF722DUAL.md | 4 ++-- make/release.mk | 2 +- make/targets.mk | 2 +- src/main/target/FOXEERF722DUAL/FOXEERF722V2.mk | 1 + src/main/target/FOXEERF722DUAL/target.h | 5 +++++ 5 files changed, 10 insertions(+), 4 deletions(-) create mode 100644 src/main/target/FOXEERF722DUAL/FOXEERF722V2.mk diff --git a/docs/Board - FOXEERF722DUAL.md b/docs/Board - FOXEERF722DUAL.md index 1a548febda4..f62dc3722bf 100644 --- a/docs/Board - FOXEERF722DUAL.md +++ b/docs/Board - FOXEERF722DUAL.md @@ -1,6 +1,6 @@ -# Board - FOXEERF722DUAL +# Board - FOXEERF722DUAL, Foxeer F722 V2 and Foxeer F722 Mini -The FOXEERF722DUAL described here: +The Foxeer F722 DUAL, Foxeer F722 V2 and Foxeer F722 Mini described here: This board use the STM32F722RET6 microcontroller and have the following features: * High-performance and DSP with FPU, ARM Cortex-M7 MCU with 512 Kbytes Flash diff --git a/make/release.mk b/make/release.mk index 7eb829efa8a..a8806f99a73 100644 --- a/make/release.mk +++ b/make/release.mk @@ -19,7 +19,7 @@ RELEASE_TARGETS += OMNIBUSF7 OMNIBUSF7V2 OMNIBUSF7NXT YUPIF7 RELEASE_TARGETS += MATEKF405 MATEKF405_SERVOS6 MATEKF405OSD MATEKF722 MATEKF722_HEXSERVO MATEKF722SE MATEKF722MINI MATEKF405SE MATEKF411 MATEKF411_SFTSRL2 MATEKF411_FD_SFTSRL MATEKF411_RSSI MATEKF411SE MATEKF765 MATEKF722PX RELEASE_TARGETS += MATEKF765 -RELEASE_TARGETS += FOXEERF405 FOXEERF722DUAL +RELEASE_TARGETS += FOXEERF405 FOXEERF722DUAL FOXEERF722V2 RELEASE_TARGETS += SPEEDYBEEF4 FRSKYF3 FRSKYF4 diff --git a/make/targets.mk b/make/targets.mk index c111ddb75c0..fcec9980457 100644 --- a/make/targets.mk +++ b/make/targets.mk @@ -78,7 +78,7 @@ GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ALIENFLIGHTNGF7 PIXRACER GROUP_5_TARGETS := ASGARD32F7 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF3 FURYF3_SPIFLASH FURYF4OSD GROUP_6_TARGETS := MAMBAF405 OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS AIKONF4 GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KFC32F3_INAV MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO -GROUP_8_TARGETS := MATEKF765 MATEKF722PX KAKUTEF7HDV ZEEZF7 +GROUP_8_TARGETS := MATEKF765 MATEKF722PX KAKUTEF7HDV ZEEZF7 FOXEERF722V2 GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS) $(GROUP_3_TARGETS) $(GROUP_4_TARGETS) $(GROUP_5_TARGETS) $(GROUP_6_TARGETS) $(GROUP_7_TARGETS) $(GROUP_8_TARGETS), $(VALID_TARGETS)) ## targets-group-1 : build some targets diff --git a/src/main/target/FOXEERF722DUAL/FOXEERF722V2.mk b/src/main/target/FOXEERF722DUAL/FOXEERF722V2.mk new file mode 100644 index 00000000000..2effcd76873 --- /dev/null +++ b/src/main/target/FOXEERF722DUAL/FOXEERF722V2.mk @@ -0,0 +1 @@ +#FOXEERF722V2 \ No newline at end of file diff --git a/src/main/target/FOXEERF722DUAL/target.h b/src/main/target/FOXEERF722DUAL/target.h index 75eec081ff5..e1ac91c2716 100644 --- a/src/main/target/FOXEERF722DUAL/target.h +++ b/src/main/target/FOXEERF722DUAL/target.h @@ -31,7 +31,10 @@ // We use dual IMU sensors, they have to be described in the target file #define USE_TARGET_IMU_HARDWARE_DESCRIPTORS #define USE_MPU_DATA_READY_SIGNAL + +#ifdef FOXEERF722DUAL #define USE_DUAL_GYRO +#endif // MPU6000 #define USE_IMU_MPU6000 @@ -41,11 +44,13 @@ #define MPU6000_EXTI_PIN PC4 // ICM20602 - handled by MPU6500 driver +#ifdef FOXEERF722DUAL #define USE_IMU_MPU6500 #define IMU_MPU6500_ALIGN CW180_DEG #define MPU6500_CS_PIN PB1 #define MPU6500_SPI_BUS BUS_SPI1 #define MPU6500_EXTI_PIN PB0 +#endif /*** SPI/I2C bus ***/ #define USE_SPI From d21706e7e385658b4b094ba58642067ee2dc17b9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Thu, 14 May 2020 17:14:50 +0100 Subject: [PATCH 091/248] [TESTS] Make sure all test cases run on its own Some of the test cases were relying on some setup by a previous test case in the same file. --- src/test/unit/rcdevice_unittest.cc | 4 ++++ src/test/unit/sensor_gyro_unittest.cc | 3 ++- 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/src/test/unit/rcdevice_unittest.cc b/src/test/unit/rcdevice_unittest.cc index fcaf5c94436..7968233c9f5 100644 --- a/src/test/unit/rcdevice_unittest.cc +++ b/src/test/unit/rcdevice_unittest.cc @@ -314,6 +314,7 @@ TEST(RCDeviceTest, TestWifiModeChangeWithDeviceUnready) rcData[modeActivationConditions(1)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 900; rcData[modeActivationConditions(2)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 900; + updateUsedModeActivationConditionFlags(); updateActivatedModes(); // runn process loop @@ -375,6 +376,7 @@ TEST(RCDeviceTest, TestWifiModeChangeWithDeviceReady) rcData[modeActivationConditions(1)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 2000; rcData[modeActivationConditions(2)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 1700; + updateUsedModeActivationConditionFlags(); updateActivatedModes(); // runn process loop @@ -435,6 +437,8 @@ TEST(RCDeviceTest, TestWifiModeChangeCombine) rcData[modeActivationConditions(0)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 1700; rcData[modeActivationConditions(1)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 2000; rcData[modeActivationConditions(2)->auxChannelIndex + NON_AUX_CHANNEL_COUNT] = 1700; + + updateUsedModeActivationConditionFlags(); updateActivatedModes(); // runn process loop diff --git a/src/test/unit/sensor_gyro_unittest.cc b/src/test/unit/sensor_gyro_unittest.cc index 0e49751519c..7eb0418397f 100644 --- a/src/test/unit/sensor_gyro_unittest.cc +++ b/src/test/unit/sensor_gyro_unittest.cc @@ -75,8 +75,8 @@ TEST(SensorGyro, Read) TEST(SensorGyro, Calibrate) { - gyroStartCalibration(); gyroInit(); + gyroStartCalibration(); fakeGyroSet(5, 6, 7); const bool read = gyroDev[0].readFn(&gyroDev[0]); EXPECT_EQ(true, read); @@ -101,6 +101,7 @@ TEST(SensorGyro, Calibrate) TEST(SensorGyro, Update) { + gyroInit(); gyroStartCalibration(); EXPECT_EQ(false, gyroIsCalibrationComplete()); gyroInit(); From 074c4dec1c534b7bd9888260c4f8b5aa80d7ae11 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Thu, 14 May 2020 18:46:16 +0100 Subject: [PATCH 092/248] [TESTS] Use CMake to build and run tests Tests are now managed with cmake, with the intention of eventually moving the whole build system to it. The root Makefile still has a test target that has been adjusted to call into the appropriate cmake commands. Also, GTest library is now downloaded on demand the first time the tests are run, so we can delete it from the repository. --- Makefile | 4 +- lib/test/gtest/inc/gtest/gtest.h | 20061 ------------------------ lib/test/gtest/src/gtest-all.cc | 9592 ----------- lib/test/gtest/src/gtest_main.cc | 38 - src/test/.gitignore | 1 + src/test/CMakeLists.txt | 17 + src/test/Makefile | 769 - src/test/cmake/CMakeListsGTest.txt.in | 15 + src/test/cmake/gtest.cmake | 31 + src/test/unit/CMakeLists.txt | 58 + src/test/unit/platform.h | 4 +- 11 files changed, 127 insertions(+), 30463 deletions(-) delete mode 100644 lib/test/gtest/inc/gtest/gtest.h delete mode 100644 lib/test/gtest/src/gtest-all.cc delete mode 100644 lib/test/gtest/src/gtest_main.cc create mode 100644 src/test/.gitignore create mode 100644 src/test/CMakeLists.txt delete mode 100644 src/test/Makefile create mode 100644 src/test/cmake/CMakeListsGTest.txt.in create mode 100644 src/test/cmake/gtest.cmake create mode 100644 src/test/unit/CMakeLists.txt diff --git a/Makefile b/Makefile index 7ea9a13b6a0..5b95e5a6acb 100644 --- a/Makefile +++ b/Makefile @@ -465,7 +465,7 @@ clean: ## clean_test : clean up all temporary / machine-generated files (tests) clean_test: - $(V0) cd src/test && $(MAKE) clean + $(V0) $(RM) -r src/test/build ## clean_ : clean up one specific target $(CLEAN_TARGETS) : @@ -533,7 +533,7 @@ help: Makefile ## test : run the cleanflight test suite test: - $(V0) cd src/test && $(MAKE) test + $(V0) mkdir -p src/test/build && cd src/test/build && cmake .. && $(MAKE) check # rebuild everything when makefile changes # Make the generated files and the build stamp order only prerequisites, diff --git a/lib/test/gtest/inc/gtest/gtest.h b/lib/test/gtest/inc/gtest/gtest.h deleted file mode 100644 index 4f3804f703c..00000000000 --- a/lib/test/gtest/inc/gtest/gtest.h +++ /dev/null @@ -1,20061 +0,0 @@ -// Copyright 2005, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: wan@google.com (Zhanyong Wan) -// -// The Google C++ Testing Framework (Google Test) -// -// This header file defines the public API for Google Test. It should be -// included by any test program that uses Google Test. -// -// IMPORTANT NOTE: Due to limitation of the C++ language, we have to -// leave some internal implementation details in this header file. -// They are clearly marked by comments like this: -// -// // INTERNAL IMPLEMENTATION - DO NOT USE IN A USER PROGRAM. -// -// Such code is NOT meant to be used by a user directly, and is subject -// to CHANGE WITHOUT NOTICE. Therefore DO NOT DEPEND ON IT in a user -// program! -// -// Acknowledgment: Google Test borrowed the idea of automatic test -// registration from Barthelemy Dagenais' (barthelemy@prologique.com) -// easyUnit framework. - -#ifndef GTEST_INCLUDE_GTEST_GTEST_H_ -#define GTEST_INCLUDE_GTEST_GTEST_H_ - -#include -#include -#include - -// Copyright 2005, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Authors: wan@google.com (Zhanyong Wan), eefacm@gmail.com (Sean Mcafee) -// -// The Google C++ Testing Framework (Google Test) -// -// This header file declares functions and macros used internally by -// Google Test. They are subject to change without notice. - -#ifndef GTEST_INCLUDE_GTEST_INTERNAL_GTEST_INTERNAL_H_ -#define GTEST_INCLUDE_GTEST_INTERNAL_GTEST_INTERNAL_H_ - -// Copyright 2005, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Authors: wan@google.com (Zhanyong Wan) -// -// Low-level types and utilities for porting Google Test to various -// platforms. They are subject to change without notice. DO NOT USE -// THEM IN USER CODE. -// -// This file is fundamental to Google Test. All other Google Test source -// files are expected to #include this. Therefore, it cannot #include -// any other Google Test header. - -#ifndef GTEST_INCLUDE_GTEST_INTERNAL_GTEST_PORT_H_ -#define GTEST_INCLUDE_GTEST_INTERNAL_GTEST_PORT_H_ - -// The user can define the following macros in the build script to -// control Google Test's behavior. If the user doesn't define a macro -// in this list, Google Test will define it. -// -// GTEST_HAS_CLONE - Define it to 1/0 to indicate that clone(2) -// is/isn't available. -// GTEST_HAS_EXCEPTIONS - Define it to 1/0 to indicate that exceptions -// are enabled. -// GTEST_HAS_GLOBAL_STRING - Define it to 1/0 to indicate that ::string -// is/isn't available (some systems define -// ::string, which is different to std::string). -// GTEST_HAS_GLOBAL_WSTRING - Define it to 1/0 to indicate that ::string -// is/isn't available (some systems define -// ::wstring, which is different to std::wstring). -// GTEST_HAS_POSIX_RE - Define it to 1/0 to indicate that POSIX regular -// expressions are/aren't available. -// GTEST_HAS_PTHREAD - Define it to 1/0 to indicate that -// is/isn't available. -// GTEST_HAS_RTTI - Define it to 1/0 to indicate that RTTI is/isn't -// enabled. -// GTEST_HAS_STD_WSTRING - Define it to 1/0 to indicate that -// std::wstring does/doesn't work (Google Test can -// be used where std::wstring is unavailable). -// GTEST_HAS_TR1_TUPLE - Define it to 1/0 to indicate tr1::tuple -// is/isn't available. -// GTEST_HAS_SEH - Define it to 1/0 to indicate whether the -// compiler supports Microsoft's "Structured -// Exception Handling". -// GTEST_HAS_STREAM_REDIRECTION -// - Define it to 1/0 to indicate whether the -// platform supports I/O stream redirection using -// dup() and dup2(). -// GTEST_USE_OWN_TR1_TUPLE - Define it to 1/0 to indicate whether Google -// Test's own tr1 tuple implementation should be -// used. Unused when the user sets -// GTEST_HAS_TR1_TUPLE to 0. -// GTEST_LANG_CXX11 - Define it to 1/0 to indicate that Google Test -// is building in C++11/C++98 mode. -// GTEST_LINKED_AS_SHARED_LIBRARY -// - Define to 1 when compiling tests that use -// Google Test as a shared library (known as -// DLL on Windows). -// GTEST_CREATE_SHARED_LIBRARY -// - Define to 1 when compiling Google Test itself -// as a shared library. - -// This header defines the following utilities: -// -// Macros indicating the current platform (defined to 1 if compiled on -// the given platform; otherwise undefined): -// GTEST_OS_AIX - IBM AIX -// GTEST_OS_CYGWIN - Cygwin -// GTEST_OS_HPUX - HP-UX -// GTEST_OS_LINUX - Linux -// GTEST_OS_LINUX_ANDROID - Google Android -// GTEST_OS_MAC - Mac OS X -// GTEST_OS_IOS - iOS -// GTEST_OS_IOS_SIMULATOR - iOS simulator -// GTEST_OS_NACL - Google Native Client (NaCl) -// GTEST_OS_OPENBSD - OpenBSD -// GTEST_OS_QNX - QNX -// GTEST_OS_SOLARIS - Sun Solaris -// GTEST_OS_SYMBIAN - Symbian -// GTEST_OS_WINDOWS - Windows (Desktop, MinGW, or Mobile) -// GTEST_OS_WINDOWS_DESKTOP - Windows Desktop -// GTEST_OS_WINDOWS_MINGW - MinGW -// GTEST_OS_WINDOWS_MOBILE - Windows Mobile -// GTEST_OS_ZOS - z/OS -// -// Among the platforms, Cygwin, Linux, Max OS X, and Windows have the -// most stable support. Since core members of the Google Test project -// don't have access to other platforms, support for them may be less -// stable. If you notice any problems on your platform, please notify -// googletestframework@googlegroups.com (patches for fixing them are -// even more welcome!). -// -// Note that it is possible that none of the GTEST_OS_* macros are defined. -// -// Macros indicating available Google Test features (defined to 1 if -// the corresponding feature is supported; otherwise undefined): -// GTEST_HAS_COMBINE - the Combine() function (for value-parameterized -// tests) -// GTEST_HAS_DEATH_TEST - death tests -// GTEST_HAS_PARAM_TEST - value-parameterized tests -// GTEST_HAS_TYPED_TEST - typed tests -// GTEST_HAS_TYPED_TEST_P - type-parameterized tests -// GTEST_USES_POSIX_RE - enhanced POSIX regex is used. Do not confuse with -// GTEST_HAS_POSIX_RE (see above) which users can -// define themselves. -// GTEST_USES_SIMPLE_RE - our own simple regex is used; -// the above two are mutually exclusive. -// GTEST_CAN_COMPARE_NULL - accepts untyped NULL in EXPECT_EQ(). -// -// Macros for basic C++ coding: -// GTEST_AMBIGUOUS_ELSE_BLOCKER_ - for disabling a gcc warning. -// GTEST_ATTRIBUTE_UNUSED_ - declares that a class' instances or a -// variable don't have to be used. -// GTEST_DISALLOW_ASSIGN_ - disables operator=. -// GTEST_DISALLOW_COPY_AND_ASSIGN_ - disables copy ctor and operator=. -// GTEST_MUST_USE_RESULT_ - declares that a function's result must be used. -// -// Synchronization: -// Mutex, MutexLock, ThreadLocal, GetThreadCount() -// - synchronization primitives. -// GTEST_IS_THREADSAFE - defined to 1 to indicate that the above -// synchronization primitives have real implementations -// and Google Test is thread-safe; or 0 otherwise. -// -// Template meta programming: -// is_pointer - as in TR1; needed on Symbian and IBM XL C/C++ only. -// IteratorTraits - partial implementation of std::iterator_traits, which -// is not available in libCstd when compiled with Sun C++. -// -// Smart pointers: -// scoped_ptr - as in TR2. -// -// Regular expressions: -// RE - a simple regular expression class using the POSIX -// Extended Regular Expression syntax on UNIX-like -// platforms, or a reduced regular exception syntax on -// other platforms, including Windows. -// -// Logging: -// GTEST_LOG_() - logs messages at the specified severity level. -// LogToStderr() - directs all log messages to stderr. -// FlushInfoLog() - flushes informational log messages. -// -// Stdout and stderr capturing: -// CaptureStdout() - starts capturing stdout. -// GetCapturedStdout() - stops capturing stdout and returns the captured -// string. -// CaptureStderr() - starts capturing stderr. -// GetCapturedStderr() - stops capturing stderr and returns the captured -// string. -// -// Integer types: -// TypeWithSize - maps an integer to a int type. -// Int32, UInt32, Int64, UInt64, TimeInMillis -// - integers of known sizes. -// BiggestInt - the biggest signed integer type. -// -// Command-line utilities: -// GTEST_FLAG() - references a flag. -// GTEST_DECLARE_*() - declares a flag. -// GTEST_DEFINE_*() - defines a flag. -// GetInjectableArgvs() - returns the command line as a vector of strings. -// -// Environment variable utilities: -// GetEnv() - gets the value of an environment variable. -// BoolFromGTestEnv() - parses a bool environment variable. -// Int32FromGTestEnv() - parses an Int32 environment variable. -// StringFromGTestEnv() - parses a string environment variable. - -#include // for isspace, etc -#include // for ptrdiff_t -#include -#include -#include -#ifndef _WIN32_WCE -# include -# include -#endif // !_WIN32_WCE - -#if defined __APPLE__ -# include -# include -#endif - -#include // NOLINT -#include // NOLINT -#include // NOLINT - -#define GTEST_DEV_EMAIL_ "googletestframework@@googlegroups.com" -#define GTEST_FLAG_PREFIX_ "gtest_" -#define GTEST_FLAG_PREFIX_DASH_ "gtest-" -#define GTEST_FLAG_PREFIX_UPPER_ "GTEST_" -#define GTEST_NAME_ "Google Test" -#define GTEST_PROJECT_URL_ "http://code.google.com/p/googletest/" - -// Determines the version of gcc that is used to compile this. -#ifdef __GNUC__ -// 40302 means version 4.3.2. -# define GTEST_GCC_VER_ \ - (__GNUC__*10000 + __GNUC_MINOR__*100 + __GNUC_PATCHLEVEL__) -#endif // __GNUC__ - -// Determines the platform on which Google Test is compiled. -#ifdef __CYGWIN__ -# define GTEST_OS_CYGWIN 1 -#elif defined __SYMBIAN32__ -# define GTEST_OS_SYMBIAN 1 -#elif defined _WIN32 -# define GTEST_OS_WINDOWS 1 -# ifdef _WIN32_WCE -# define GTEST_OS_WINDOWS_MOBILE 1 -# elif defined(__MINGW__) || defined(__MINGW32__) -# define GTEST_OS_WINDOWS_MINGW 1 -# else -# define GTEST_OS_WINDOWS_DESKTOP 1 -# endif // _WIN32_WCE -#elif defined __APPLE__ -# define GTEST_OS_MAC 1 -# if TARGET_OS_IPHONE -# define GTEST_OS_IOS 1 -# if TARGET_IPHONE_SIMULATOR -# define GTEST_OS_IOS_SIMULATOR 1 -# endif -# endif -#elif defined __linux__ -# define GTEST_OS_LINUX 1 -# if defined __ANDROID__ -# define GTEST_OS_LINUX_ANDROID 1 -# endif -#elif defined __MVS__ -# define GTEST_OS_ZOS 1 -#elif defined(__sun) && defined(__SVR4) -# define GTEST_OS_SOLARIS 1 -#elif defined(_AIX) -# define GTEST_OS_AIX 1 -#elif defined(__hpux) -# define GTEST_OS_HPUX 1 -#elif defined __native_client__ -# define GTEST_OS_NACL 1 -#elif defined __OpenBSD__ -# define GTEST_OS_OPENBSD 1 -#elif defined __QNX__ -# define GTEST_OS_QNX 1 -#endif // __CYGWIN__ - -#ifndef GTEST_LANG_CXX11 -// gcc and clang define __GXX_EXPERIMENTAL_CXX0X__ when -// -std={c,gnu}++{0x,11} is passed. The C++11 standard specifies a -// value for __cplusplus, and recent versions of clang, gcc, and -// probably other compilers set that too in C++11 mode. -# if __GXX_EXPERIMENTAL_CXX0X__ || __cplusplus >= 201103L -// Compiling in at least C++11 mode. -# define GTEST_LANG_CXX11 1 -# else -# define GTEST_LANG_CXX11 0 -# endif -#endif - -// Brings in definitions for functions used in the testing::internal::posix -// namespace (read, write, close, chdir, isatty, stat). We do not currently -// use them on Windows Mobile. -#if !GTEST_OS_WINDOWS -// This assumes that non-Windows OSes provide unistd.h. For OSes where this -// is not the case, we need to include headers that provide the functions -// mentioned above. -# include -# include -#elif !GTEST_OS_WINDOWS_MOBILE -# include -# include -#endif - -#if GTEST_OS_LINUX_ANDROID -// Used to define __ANDROID_API__ matching the target NDK API level. -# include // NOLINT -#endif - -// Defines this to true iff Google Test can use POSIX regular expressions. -#ifndef GTEST_HAS_POSIX_RE -# if GTEST_OS_LINUX_ANDROID -// On Android, is only available starting with Gingerbread. -# define GTEST_HAS_POSIX_RE (__ANDROID_API__ >= 9) -# else -# define GTEST_HAS_POSIX_RE (!GTEST_OS_WINDOWS) -# endif -#endif - -#if GTEST_HAS_POSIX_RE - -// On some platforms, needs someone to define size_t, and -// won't compile otherwise. We can #include it here as we already -// included , which is guaranteed to define size_t through -// . -# include // NOLINT - -# define GTEST_USES_POSIX_RE 1 - -#elif GTEST_OS_WINDOWS - -// is not available on Windows. Use our own simple regex -// implementation instead. -# define GTEST_USES_SIMPLE_RE 1 - -#else - -// may not be available on this platform. Use our own -// simple regex implementation instead. -# define GTEST_USES_SIMPLE_RE 1 - -#endif // GTEST_HAS_POSIX_RE - -#ifndef GTEST_HAS_EXCEPTIONS -// The user didn't tell us whether exceptions are enabled, so we need -// to figure it out. -# if defined(_MSC_VER) || defined(__BORLANDC__) -// MSVC's and C++Builder's implementations of the STL use the _HAS_EXCEPTIONS -// macro to enable exceptions, so we'll do the same. -// Assumes that exceptions are enabled by default. -# ifndef _HAS_EXCEPTIONS -# define _HAS_EXCEPTIONS 1 -# endif // _HAS_EXCEPTIONS -# define GTEST_HAS_EXCEPTIONS _HAS_EXCEPTIONS -# elif defined(__GNUC__) && __EXCEPTIONS -// gcc defines __EXCEPTIONS to 1 iff exceptions are enabled. -# define GTEST_HAS_EXCEPTIONS 1 -# elif defined(__SUNPRO_CC) -// Sun Pro CC supports exceptions. However, there is no compile-time way of -// detecting whether they are enabled or not. Therefore, we assume that -// they are enabled unless the user tells us otherwise. -# define GTEST_HAS_EXCEPTIONS 1 -# elif defined(__IBMCPP__) && __EXCEPTIONS -// xlC defines __EXCEPTIONS to 1 iff exceptions are enabled. -# define GTEST_HAS_EXCEPTIONS 1 -# elif defined(__HP_aCC) -// Exception handling is in effect by default in HP aCC compiler. It has to -// be turned of by +noeh compiler option if desired. -# define GTEST_HAS_EXCEPTIONS 1 -# else -// For other compilers, we assume exceptions are disabled to be -// conservative. -# define GTEST_HAS_EXCEPTIONS 0 -# endif // defined(_MSC_VER) || defined(__BORLANDC__) -#endif // GTEST_HAS_EXCEPTIONS - -#if !defined(GTEST_HAS_STD_STRING) -// Even though we don't use this macro any longer, we keep it in case -// some clients still depend on it. -# define GTEST_HAS_STD_STRING 1 -#elif !GTEST_HAS_STD_STRING -// The user told us that ::std::string isn't available. -# error "Google Test cannot be used where ::std::string isn't available." -#endif // !defined(GTEST_HAS_STD_STRING) - -#ifndef GTEST_HAS_GLOBAL_STRING -// The user didn't tell us whether ::string is available, so we need -// to figure it out. - -# define GTEST_HAS_GLOBAL_STRING 0 - -#endif // GTEST_HAS_GLOBAL_STRING - -#ifndef GTEST_HAS_STD_WSTRING -// The user didn't tell us whether ::std::wstring is available, so we need -// to figure it out. -// TODO(wan@google.com): uses autoconf to detect whether ::std::wstring -// is available. - -// Cygwin 1.7 and below doesn't support ::std::wstring. -// Solaris' libc++ doesn't support it either. Android has -// no support for it at least as recent as Froyo (2.2). -# define GTEST_HAS_STD_WSTRING \ - (!(GTEST_OS_LINUX_ANDROID || GTEST_OS_CYGWIN || GTEST_OS_SOLARIS)) - -#endif // GTEST_HAS_STD_WSTRING - -#ifndef GTEST_HAS_GLOBAL_WSTRING -// The user didn't tell us whether ::wstring is available, so we need -// to figure it out. -# define GTEST_HAS_GLOBAL_WSTRING \ - (GTEST_HAS_STD_WSTRING && GTEST_HAS_GLOBAL_STRING) -#endif // GTEST_HAS_GLOBAL_WSTRING - -// Determines whether RTTI is available. -#ifndef GTEST_HAS_RTTI -// The user didn't tell us whether RTTI is enabled, so we need to -// figure it out. - -# ifdef _MSC_VER - -# ifdef _CPPRTTI // MSVC defines this macro iff RTTI is enabled. -# define GTEST_HAS_RTTI 1 -# else -# define GTEST_HAS_RTTI 0 -# endif - -// Starting with version 4.3.2, gcc defines __GXX_RTTI iff RTTI is enabled. -# elif defined(__GNUC__) && (GTEST_GCC_VER_ >= 40302) - -# ifdef __GXX_RTTI -// When building against STLport with the Android NDK and with -// -frtti -fno-exceptions, the build fails at link time with undefined -// references to __cxa_bad_typeid. Note sure if STL or toolchain bug, -// so disable RTTI when detected. -# if GTEST_OS_LINUX_ANDROID && defined(_STLPORT_MAJOR) && \ - !defined(__EXCEPTIONS) -# define GTEST_HAS_RTTI 0 -# else -# define GTEST_HAS_RTTI 1 -# endif // GTEST_OS_LINUX_ANDROID && __STLPORT_MAJOR && !__EXCEPTIONS -# else -# define GTEST_HAS_RTTI 0 -# endif // __GXX_RTTI - -// Clang defines __GXX_RTTI starting with version 3.0, but its manual recommends -// using has_feature instead. has_feature(cxx_rtti) is supported since 2.7, the -// first version with C++ support. -# elif defined(__clang__) - -# define GTEST_HAS_RTTI __has_feature(cxx_rtti) - -// Starting with version 9.0 IBM Visual Age defines __RTTI_ALL__ to 1 if -// both the typeid and dynamic_cast features are present. -# elif defined(__IBMCPP__) && (__IBMCPP__ >= 900) - -# ifdef __RTTI_ALL__ -# define GTEST_HAS_RTTI 1 -# else -# define GTEST_HAS_RTTI 0 -# endif - -# else - -// For all other compilers, we assume RTTI is enabled. -# define GTEST_HAS_RTTI 1 - -# endif // _MSC_VER - -#endif // GTEST_HAS_RTTI - -// It's this header's responsibility to #include when RTTI -// is enabled. -#if GTEST_HAS_RTTI -# include -#endif - -// Determines whether Google Test can use the pthreads library. -#ifndef GTEST_HAS_PTHREAD -// The user didn't tell us explicitly, so we assume pthreads support is -// available on Linux and Mac. -// -// To disable threading support in Google Test, add -DGTEST_HAS_PTHREAD=0 -// to your compiler flags. -# define GTEST_HAS_PTHREAD (GTEST_OS_LINUX || GTEST_OS_MAC || GTEST_OS_HPUX \ - || GTEST_OS_QNX) -#endif // GTEST_HAS_PTHREAD - -#if GTEST_HAS_PTHREAD -// gtest-port.h guarantees to #include when GTEST_HAS_PTHREAD is -// true. -# include // NOLINT - -// For timespec and nanosleep, used below. -# include // NOLINT -#endif - -// Determines whether Google Test can use tr1/tuple. You can define -// this macro to 0 to prevent Google Test from using tuple (any -// feature depending on tuple with be disabled in this mode). -#ifndef GTEST_HAS_TR1_TUPLE -# if GTEST_OS_LINUX_ANDROID && defined(_STLPORT_MAJOR) -// STLport, provided with the Android NDK, has neither or . -# define GTEST_HAS_TR1_TUPLE 0 -# else -// The user didn't tell us not to do it, so we assume it's OK. -# define GTEST_HAS_TR1_TUPLE 1 -# endif -#endif // GTEST_HAS_TR1_TUPLE - -// Determines whether Google Test's own tr1 tuple implementation -// should be used. -#ifndef GTEST_USE_OWN_TR1_TUPLE -// The user didn't tell us, so we need to figure it out. - -// We use our own TR1 tuple if we aren't sure the user has an -// implementation of it already. At this time, libstdc++ 4.0.0+ and -// MSVC 2010 are the only mainstream standard libraries that come -// with a TR1 tuple implementation. NVIDIA's CUDA NVCC compiler -// pretends to be GCC by defining __GNUC__ and friends, but cannot -// compile GCC's tuple implementation. MSVC 2008 (9.0) provides TR1 -// tuple in a 323 MB Feature Pack download, which we cannot assume the -// user has. QNX's QCC compiler is a modified GCC but it doesn't -// support TR1 tuple. libc++ only provides std::tuple, in C++11 mode, -// and it can be used with some compilers that define __GNUC__. -# if (defined(__GNUC__) && !defined(__CUDACC__) && (GTEST_GCC_VER_ >= 40000) \ - && !GTEST_OS_QNX && !defined(_LIBCPP_VERSION)) || _MSC_VER >= 1600 -# define GTEST_ENV_HAS_TR1_TUPLE_ 1 -# endif - -// C++11 specifies that provides std::tuple. Use that if gtest is used -// in C++11 mode and libstdc++ isn't very old (binaries targeting OS X 10.6 -// can build with clang but need to use gcc4.2's libstdc++). -# if GTEST_LANG_CXX11 && (!defined(__GLIBCXX__) || __GLIBCXX__ > 20110325) -# define GTEST_ENV_HAS_STD_TUPLE_ 1 -# endif - -# if GTEST_ENV_HAS_TR1_TUPLE_ || GTEST_ENV_HAS_STD_TUPLE_ -# define GTEST_USE_OWN_TR1_TUPLE 0 -# else -# define GTEST_USE_OWN_TR1_TUPLE 1 -# endif - -#endif // GTEST_USE_OWN_TR1_TUPLE - -// To avoid conditional compilation everywhere, we make it -// gtest-port.h's responsibility to #include the header implementing -// tr1/tuple. -#if GTEST_HAS_TR1_TUPLE - -# if GTEST_USE_OWN_TR1_TUPLE -// This file was GENERATED by command: -// pump.py gtest-tuple.h.pump -// DO NOT EDIT BY HAND!!! - -// Copyright 2009 Google Inc. -// All Rights Reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: wan@google.com (Zhanyong Wan) - -// Implements a subset of TR1 tuple needed by Google Test and Google Mock. - -#ifndef GTEST_INCLUDE_GTEST_INTERNAL_GTEST_TUPLE_H_ -#define GTEST_INCLUDE_GTEST_INTERNAL_GTEST_TUPLE_H_ - -#include // For ::std::pair. - -// The compiler used in Symbian has a bug that prevents us from declaring the -// tuple template as a friend (it complains that tuple is redefined). This -// hack bypasses the bug by declaring the members that should otherwise be -// private as public. -// Sun Studio versions < 12 also have the above bug. -#if defined(__SYMBIAN32__) || (defined(__SUNPRO_CC) && __SUNPRO_CC < 0x590) -# define GTEST_DECLARE_TUPLE_AS_FRIEND_ public: -#else -# define GTEST_DECLARE_TUPLE_AS_FRIEND_ \ - template friend class tuple; \ - private: -#endif - -// GTEST_n_TUPLE_(T) is the type of an n-tuple. -#define GTEST_0_TUPLE_(T) tuple<> -#define GTEST_1_TUPLE_(T) tuple -#define GTEST_2_TUPLE_(T) tuple -#define GTEST_3_TUPLE_(T) tuple -#define GTEST_4_TUPLE_(T) tuple -#define GTEST_5_TUPLE_(T) tuple -#define GTEST_6_TUPLE_(T) tuple -#define GTEST_7_TUPLE_(T) tuple -#define GTEST_8_TUPLE_(T) tuple -#define GTEST_9_TUPLE_(T) tuple -#define GTEST_10_TUPLE_(T) tuple - -// GTEST_n_TYPENAMES_(T) declares a list of n typenames. -#define GTEST_0_TYPENAMES_(T) -#define GTEST_1_TYPENAMES_(T) typename T##0 -#define GTEST_2_TYPENAMES_(T) typename T##0, typename T##1 -#define GTEST_3_TYPENAMES_(T) typename T##0, typename T##1, typename T##2 -#define GTEST_4_TYPENAMES_(T) typename T##0, typename T##1, typename T##2, \ - typename T##3 -#define GTEST_5_TYPENAMES_(T) typename T##0, typename T##1, typename T##2, \ - typename T##3, typename T##4 -#define GTEST_6_TYPENAMES_(T) typename T##0, typename T##1, typename T##2, \ - typename T##3, typename T##4, typename T##5 -#define GTEST_7_TYPENAMES_(T) typename T##0, typename T##1, typename T##2, \ - typename T##3, typename T##4, typename T##5, typename T##6 -#define GTEST_8_TYPENAMES_(T) typename T##0, typename T##1, typename T##2, \ - typename T##3, typename T##4, typename T##5, typename T##6, typename T##7 -#define GTEST_9_TYPENAMES_(T) typename T##0, typename T##1, typename T##2, \ - typename T##3, typename T##4, typename T##5, typename T##6, \ - typename T##7, typename T##8 -#define GTEST_10_TYPENAMES_(T) typename T##0, typename T##1, typename T##2, \ - typename T##3, typename T##4, typename T##5, typename T##6, \ - typename T##7, typename T##8, typename T##9 - -// In theory, defining stuff in the ::std namespace is undefined -// behavior. We can do this as we are playing the role of a standard -// library vendor. -namespace std { -namespace tr1 { - -template -class tuple; - -// Anything in namespace gtest_internal is Google Test's INTERNAL -// IMPLEMENTATION DETAIL and MUST NOT BE USED DIRECTLY in user code. -namespace gtest_internal { - -// ByRef::type is T if T is a reference; otherwise it's const T&. -template -struct ByRef { typedef const T& type; }; // NOLINT -template -struct ByRef { typedef T& type; }; // NOLINT - -// A handy wrapper for ByRef. -#define GTEST_BY_REF_(T) typename ::std::tr1::gtest_internal::ByRef::type - -// AddRef::type is T if T is a reference; otherwise it's T&. This -// is the same as tr1::add_reference::type. -template -struct AddRef { typedef T& type; }; // NOLINT -template -struct AddRef { typedef T& type; }; // NOLINT - -// A handy wrapper for AddRef. -#define GTEST_ADD_REF_(T) typename ::std::tr1::gtest_internal::AddRef::type - -// A helper for implementing get(). -template class Get; - -// A helper for implementing tuple_element. kIndexValid is true -// iff k < the number of fields in tuple type T. -template -struct TupleElement; - -template -struct TupleElement { - typedef T0 type; -}; - -template -struct TupleElement { - typedef T1 type; -}; - -template -struct TupleElement { - typedef T2 type; -}; - -template -struct TupleElement { - typedef T3 type; -}; - -template -struct TupleElement { - typedef T4 type; -}; - -template -struct TupleElement { - typedef T5 type; -}; - -template -struct TupleElement { - typedef T6 type; -}; - -template -struct TupleElement { - typedef T7 type; -}; - -template -struct TupleElement { - typedef T8 type; -}; - -template -struct TupleElement { - typedef T9 type; -}; - -} // namespace gtest_internal - -template <> -class tuple<> { - public: - tuple() {} - tuple(const tuple& /* t */) {} - tuple& operator=(const tuple& /* t */) { return *this; } -}; - -template -class GTEST_1_TUPLE_(T) { - public: - template friend class gtest_internal::Get; - - tuple() : f0_() {} - - explicit tuple(GTEST_BY_REF_(T0) f0) : f0_(f0) {} - - tuple(const tuple& t) : f0_(t.f0_) {} - - template - tuple(const GTEST_1_TUPLE_(U)& t) : f0_(t.f0_) {} - - tuple& operator=(const tuple& t) { return CopyFrom(t); } - - template - tuple& operator=(const GTEST_1_TUPLE_(U)& t) { - return CopyFrom(t); - } - - GTEST_DECLARE_TUPLE_AS_FRIEND_ - - template - tuple& CopyFrom(const GTEST_1_TUPLE_(U)& t) { - f0_ = t.f0_; - return *this; - } - - T0 f0_; -}; - -template -class GTEST_2_TUPLE_(T) { - public: - template friend class gtest_internal::Get; - - tuple() : f0_(), f1_() {} - - explicit tuple(GTEST_BY_REF_(T0) f0, GTEST_BY_REF_(T1) f1) : f0_(f0), - f1_(f1) {} - - tuple(const tuple& t) : f0_(t.f0_), f1_(t.f1_) {} - - template - tuple(const GTEST_2_TUPLE_(U)& t) : f0_(t.f0_), f1_(t.f1_) {} - template - tuple(const ::std::pair& p) : f0_(p.first), f1_(p.second) {} - - tuple& operator=(const tuple& t) { return CopyFrom(t); } - - template - tuple& operator=(const GTEST_2_TUPLE_(U)& t) { - return CopyFrom(t); - } - template - tuple& operator=(const ::std::pair& p) { - f0_ = p.first; - f1_ = p.second; - return *this; - } - - GTEST_DECLARE_TUPLE_AS_FRIEND_ - - template - tuple& CopyFrom(const GTEST_2_TUPLE_(U)& t) { - f0_ = t.f0_; - f1_ = t.f1_; - return *this; - } - - T0 f0_; - T1 f1_; -}; - -template -class GTEST_3_TUPLE_(T) { - public: - template friend class gtest_internal::Get; - - tuple() : f0_(), f1_(), f2_() {} - - explicit tuple(GTEST_BY_REF_(T0) f0, GTEST_BY_REF_(T1) f1, - GTEST_BY_REF_(T2) f2) : f0_(f0), f1_(f1), f2_(f2) {} - - tuple(const tuple& t) : f0_(t.f0_), f1_(t.f1_), f2_(t.f2_) {} - - template - tuple(const GTEST_3_TUPLE_(U)& t) : f0_(t.f0_), f1_(t.f1_), f2_(t.f2_) {} - - tuple& operator=(const tuple& t) { return CopyFrom(t); } - - template - tuple& operator=(const GTEST_3_TUPLE_(U)& t) { - return CopyFrom(t); - } - - GTEST_DECLARE_TUPLE_AS_FRIEND_ - - template - tuple& CopyFrom(const GTEST_3_TUPLE_(U)& t) { - f0_ = t.f0_; - f1_ = t.f1_; - f2_ = t.f2_; - return *this; - } - - T0 f0_; - T1 f1_; - T2 f2_; -}; - -template -class GTEST_4_TUPLE_(T) { - public: - template friend class gtest_internal::Get; - - tuple() : f0_(), f1_(), f2_(), f3_() {} - - explicit tuple(GTEST_BY_REF_(T0) f0, GTEST_BY_REF_(T1) f1, - GTEST_BY_REF_(T2) f2, GTEST_BY_REF_(T3) f3) : f0_(f0), f1_(f1), f2_(f2), - f3_(f3) {} - - tuple(const tuple& t) : f0_(t.f0_), f1_(t.f1_), f2_(t.f2_), f3_(t.f3_) {} - - template - tuple(const GTEST_4_TUPLE_(U)& t) : f0_(t.f0_), f1_(t.f1_), f2_(t.f2_), - f3_(t.f3_) {} - - tuple& operator=(const tuple& t) { return CopyFrom(t); } - - template - tuple& operator=(const GTEST_4_TUPLE_(U)& t) { - return CopyFrom(t); - } - - GTEST_DECLARE_TUPLE_AS_FRIEND_ - - template - tuple& CopyFrom(const GTEST_4_TUPLE_(U)& t) { - f0_ = t.f0_; - f1_ = t.f1_; - f2_ = t.f2_; - f3_ = t.f3_; - return *this; - } - - T0 f0_; - T1 f1_; - T2 f2_; - T3 f3_; -}; - -template -class GTEST_5_TUPLE_(T) { - public: - template friend class gtest_internal::Get; - - tuple() : f0_(), f1_(), f2_(), f3_(), f4_() {} - - explicit tuple(GTEST_BY_REF_(T0) f0, GTEST_BY_REF_(T1) f1, - GTEST_BY_REF_(T2) f2, GTEST_BY_REF_(T3) f3, - GTEST_BY_REF_(T4) f4) : f0_(f0), f1_(f1), f2_(f2), f3_(f3), f4_(f4) {} - - tuple(const tuple& t) : f0_(t.f0_), f1_(t.f1_), f2_(t.f2_), f3_(t.f3_), - f4_(t.f4_) {} - - template - tuple(const GTEST_5_TUPLE_(U)& t) : f0_(t.f0_), f1_(t.f1_), f2_(t.f2_), - f3_(t.f3_), f4_(t.f4_) {} - - tuple& operator=(const tuple& t) { return CopyFrom(t); } - - template - tuple& operator=(const GTEST_5_TUPLE_(U)& t) { - return CopyFrom(t); - } - - GTEST_DECLARE_TUPLE_AS_FRIEND_ - - template - tuple& CopyFrom(const GTEST_5_TUPLE_(U)& t) { - f0_ = t.f0_; - f1_ = t.f1_; - f2_ = t.f2_; - f3_ = t.f3_; - f4_ = t.f4_; - return *this; - } - - T0 f0_; - T1 f1_; - T2 f2_; - T3 f3_; - T4 f4_; -}; - -template -class GTEST_6_TUPLE_(T) { - public: - template friend class gtest_internal::Get; - - tuple() : f0_(), f1_(), f2_(), f3_(), f4_(), f5_() {} - - explicit tuple(GTEST_BY_REF_(T0) f0, GTEST_BY_REF_(T1) f1, - GTEST_BY_REF_(T2) f2, GTEST_BY_REF_(T3) f3, GTEST_BY_REF_(T4) f4, - GTEST_BY_REF_(T5) f5) : f0_(f0), f1_(f1), f2_(f2), f3_(f3), f4_(f4), - f5_(f5) {} - - tuple(const tuple& t) : f0_(t.f0_), f1_(t.f1_), f2_(t.f2_), f3_(t.f3_), - f4_(t.f4_), f5_(t.f5_) {} - - template - tuple(const GTEST_6_TUPLE_(U)& t) : f0_(t.f0_), f1_(t.f1_), f2_(t.f2_), - f3_(t.f3_), f4_(t.f4_), f5_(t.f5_) {} - - tuple& operator=(const tuple& t) { return CopyFrom(t); } - - template - tuple& operator=(const GTEST_6_TUPLE_(U)& t) { - return CopyFrom(t); - } - - GTEST_DECLARE_TUPLE_AS_FRIEND_ - - template - tuple& CopyFrom(const GTEST_6_TUPLE_(U)& t) { - f0_ = t.f0_; - f1_ = t.f1_; - f2_ = t.f2_; - f3_ = t.f3_; - f4_ = t.f4_; - f5_ = t.f5_; - return *this; - } - - T0 f0_; - T1 f1_; - T2 f2_; - T3 f3_; - T4 f4_; - T5 f5_; -}; - -template -class GTEST_7_TUPLE_(T) { - public: - template friend class gtest_internal::Get; - - tuple() : f0_(), f1_(), f2_(), f3_(), f4_(), f5_(), f6_() {} - - explicit tuple(GTEST_BY_REF_(T0) f0, GTEST_BY_REF_(T1) f1, - GTEST_BY_REF_(T2) f2, GTEST_BY_REF_(T3) f3, GTEST_BY_REF_(T4) f4, - GTEST_BY_REF_(T5) f5, GTEST_BY_REF_(T6) f6) : f0_(f0), f1_(f1), f2_(f2), - f3_(f3), f4_(f4), f5_(f5), f6_(f6) {} - - tuple(const tuple& t) : f0_(t.f0_), f1_(t.f1_), f2_(t.f2_), f3_(t.f3_), - f4_(t.f4_), f5_(t.f5_), f6_(t.f6_) {} - - template - tuple(const GTEST_7_TUPLE_(U)& t) : f0_(t.f0_), f1_(t.f1_), f2_(t.f2_), - f3_(t.f3_), f4_(t.f4_), f5_(t.f5_), f6_(t.f6_) {} - - tuple& operator=(const tuple& t) { return CopyFrom(t); } - - template - tuple& operator=(const GTEST_7_TUPLE_(U)& t) { - return CopyFrom(t); - } - - GTEST_DECLARE_TUPLE_AS_FRIEND_ - - template - tuple& CopyFrom(const GTEST_7_TUPLE_(U)& t) { - f0_ = t.f0_; - f1_ = t.f1_; - f2_ = t.f2_; - f3_ = t.f3_; - f4_ = t.f4_; - f5_ = t.f5_; - f6_ = t.f6_; - return *this; - } - - T0 f0_; - T1 f1_; - T2 f2_; - T3 f3_; - T4 f4_; - T5 f5_; - T6 f6_; -}; - -template -class GTEST_8_TUPLE_(T) { - public: - template friend class gtest_internal::Get; - - tuple() : f0_(), f1_(), f2_(), f3_(), f4_(), f5_(), f6_(), f7_() {} - - explicit tuple(GTEST_BY_REF_(T0) f0, GTEST_BY_REF_(T1) f1, - GTEST_BY_REF_(T2) f2, GTEST_BY_REF_(T3) f3, GTEST_BY_REF_(T4) f4, - GTEST_BY_REF_(T5) f5, GTEST_BY_REF_(T6) f6, - GTEST_BY_REF_(T7) f7) : f0_(f0), f1_(f1), f2_(f2), f3_(f3), f4_(f4), - f5_(f5), f6_(f6), f7_(f7) {} - - tuple(const tuple& t) : f0_(t.f0_), f1_(t.f1_), f2_(t.f2_), f3_(t.f3_), - f4_(t.f4_), f5_(t.f5_), f6_(t.f6_), f7_(t.f7_) {} - - template - tuple(const GTEST_8_TUPLE_(U)& t) : f0_(t.f0_), f1_(t.f1_), f2_(t.f2_), - f3_(t.f3_), f4_(t.f4_), f5_(t.f5_), f6_(t.f6_), f7_(t.f7_) {} - - tuple& operator=(const tuple& t) { return CopyFrom(t); } - - template - tuple& operator=(const GTEST_8_TUPLE_(U)& t) { - return CopyFrom(t); - } - - GTEST_DECLARE_TUPLE_AS_FRIEND_ - - template - tuple& CopyFrom(const GTEST_8_TUPLE_(U)& t) { - f0_ = t.f0_; - f1_ = t.f1_; - f2_ = t.f2_; - f3_ = t.f3_; - f4_ = t.f4_; - f5_ = t.f5_; - f6_ = t.f6_; - f7_ = t.f7_; - return *this; - } - - T0 f0_; - T1 f1_; - T2 f2_; - T3 f3_; - T4 f4_; - T5 f5_; - T6 f6_; - T7 f7_; -}; - -template -class GTEST_9_TUPLE_(T) { - public: - template friend class gtest_internal::Get; - - tuple() : f0_(), f1_(), f2_(), f3_(), f4_(), f5_(), f6_(), f7_(), f8_() {} - - explicit tuple(GTEST_BY_REF_(T0) f0, GTEST_BY_REF_(T1) f1, - GTEST_BY_REF_(T2) f2, GTEST_BY_REF_(T3) f3, GTEST_BY_REF_(T4) f4, - GTEST_BY_REF_(T5) f5, GTEST_BY_REF_(T6) f6, GTEST_BY_REF_(T7) f7, - GTEST_BY_REF_(T8) f8) : f0_(f0), f1_(f1), f2_(f2), f3_(f3), f4_(f4), - f5_(f5), f6_(f6), f7_(f7), f8_(f8) {} - - tuple(const tuple& t) : f0_(t.f0_), f1_(t.f1_), f2_(t.f2_), f3_(t.f3_), - f4_(t.f4_), f5_(t.f5_), f6_(t.f6_), f7_(t.f7_), f8_(t.f8_) {} - - template - tuple(const GTEST_9_TUPLE_(U)& t) : f0_(t.f0_), f1_(t.f1_), f2_(t.f2_), - f3_(t.f3_), f4_(t.f4_), f5_(t.f5_), f6_(t.f6_), f7_(t.f7_), f8_(t.f8_) {} - - tuple& operator=(const tuple& t) { return CopyFrom(t); } - - template - tuple& operator=(const GTEST_9_TUPLE_(U)& t) { - return CopyFrom(t); - } - - GTEST_DECLARE_TUPLE_AS_FRIEND_ - - template - tuple& CopyFrom(const GTEST_9_TUPLE_(U)& t) { - f0_ = t.f0_; - f1_ = t.f1_; - f2_ = t.f2_; - f3_ = t.f3_; - f4_ = t.f4_; - f5_ = t.f5_; - f6_ = t.f6_; - f7_ = t.f7_; - f8_ = t.f8_; - return *this; - } - - T0 f0_; - T1 f1_; - T2 f2_; - T3 f3_; - T4 f4_; - T5 f5_; - T6 f6_; - T7 f7_; - T8 f8_; -}; - -template -class tuple { - public: - template friend class gtest_internal::Get; - - tuple() : f0_(), f1_(), f2_(), f3_(), f4_(), f5_(), f6_(), f7_(), f8_(), - f9_() {} - - explicit tuple(GTEST_BY_REF_(T0) f0, GTEST_BY_REF_(T1) f1, - GTEST_BY_REF_(T2) f2, GTEST_BY_REF_(T3) f3, GTEST_BY_REF_(T4) f4, - GTEST_BY_REF_(T5) f5, GTEST_BY_REF_(T6) f6, GTEST_BY_REF_(T7) f7, - GTEST_BY_REF_(T8) f8, GTEST_BY_REF_(T9) f9) : f0_(f0), f1_(f1), f2_(f2), - f3_(f3), f4_(f4), f5_(f5), f6_(f6), f7_(f7), f8_(f8), f9_(f9) {} - - tuple(const tuple& t) : f0_(t.f0_), f1_(t.f1_), f2_(t.f2_), f3_(t.f3_), - f4_(t.f4_), f5_(t.f5_), f6_(t.f6_), f7_(t.f7_), f8_(t.f8_), f9_(t.f9_) {} - - template - tuple(const GTEST_10_TUPLE_(U)& t) : f0_(t.f0_), f1_(t.f1_), f2_(t.f2_), - f3_(t.f3_), f4_(t.f4_), f5_(t.f5_), f6_(t.f6_), f7_(t.f7_), f8_(t.f8_), - f9_(t.f9_) {} - - tuple& operator=(const tuple& t) { return CopyFrom(t); } - - template - tuple& operator=(const GTEST_10_TUPLE_(U)& t) { - return CopyFrom(t); - } - - GTEST_DECLARE_TUPLE_AS_FRIEND_ - - template - tuple& CopyFrom(const GTEST_10_TUPLE_(U)& t) { - f0_ = t.f0_; - f1_ = t.f1_; - f2_ = t.f2_; - f3_ = t.f3_; - f4_ = t.f4_; - f5_ = t.f5_; - f6_ = t.f6_; - f7_ = t.f7_; - f8_ = t.f8_; - f9_ = t.f9_; - return *this; - } - - T0 f0_; - T1 f1_; - T2 f2_; - T3 f3_; - T4 f4_; - T5 f5_; - T6 f6_; - T7 f7_; - T8 f8_; - T9 f9_; -}; - -// 6.1.3.2 Tuple creation functions. - -// Known limitations: we don't support passing an -// std::tr1::reference_wrapper to make_tuple(). And we don't -// implement tie(). - -inline tuple<> make_tuple() { return tuple<>(); } - -template -inline GTEST_1_TUPLE_(T) make_tuple(const T0& f0) { - return GTEST_1_TUPLE_(T)(f0); -} - -template -inline GTEST_2_TUPLE_(T) make_tuple(const T0& f0, const T1& f1) { - return GTEST_2_TUPLE_(T)(f0, f1); -} - -template -inline GTEST_3_TUPLE_(T) make_tuple(const T0& f0, const T1& f1, const T2& f2) { - return GTEST_3_TUPLE_(T)(f0, f1, f2); -} - -template -inline GTEST_4_TUPLE_(T) make_tuple(const T0& f0, const T1& f1, const T2& f2, - const T3& f3) { - return GTEST_4_TUPLE_(T)(f0, f1, f2, f3); -} - -template -inline GTEST_5_TUPLE_(T) make_tuple(const T0& f0, const T1& f1, const T2& f2, - const T3& f3, const T4& f4) { - return GTEST_5_TUPLE_(T)(f0, f1, f2, f3, f4); -} - -template -inline GTEST_6_TUPLE_(T) make_tuple(const T0& f0, const T1& f1, const T2& f2, - const T3& f3, const T4& f4, const T5& f5) { - return GTEST_6_TUPLE_(T)(f0, f1, f2, f3, f4, f5); -} - -template -inline GTEST_7_TUPLE_(T) make_tuple(const T0& f0, const T1& f1, const T2& f2, - const T3& f3, const T4& f4, const T5& f5, const T6& f6) { - return GTEST_7_TUPLE_(T)(f0, f1, f2, f3, f4, f5, f6); -} - -template -inline GTEST_8_TUPLE_(T) make_tuple(const T0& f0, const T1& f1, const T2& f2, - const T3& f3, const T4& f4, const T5& f5, const T6& f6, const T7& f7) { - return GTEST_8_TUPLE_(T)(f0, f1, f2, f3, f4, f5, f6, f7); -} - -template -inline GTEST_9_TUPLE_(T) make_tuple(const T0& f0, const T1& f1, const T2& f2, - const T3& f3, const T4& f4, const T5& f5, const T6& f6, const T7& f7, - const T8& f8) { - return GTEST_9_TUPLE_(T)(f0, f1, f2, f3, f4, f5, f6, f7, f8); -} - -template -inline GTEST_10_TUPLE_(T) make_tuple(const T0& f0, const T1& f1, const T2& f2, - const T3& f3, const T4& f4, const T5& f5, const T6& f6, const T7& f7, - const T8& f8, const T9& f9) { - return GTEST_10_TUPLE_(T)(f0, f1, f2, f3, f4, f5, f6, f7, f8, f9); -} - -// 6.1.3.3 Tuple helper classes. - -template struct tuple_size; - -template -struct tuple_size { - static const int value = 0; -}; - -template -struct tuple_size { - static const int value = 1; -}; - -template -struct tuple_size { - static const int value = 2; -}; - -template -struct tuple_size { - static const int value = 3; -}; - -template -struct tuple_size { - static const int value = 4; -}; - -template -struct tuple_size { - static const int value = 5; -}; - -template -struct tuple_size { - static const int value = 6; -}; - -template -struct tuple_size { - static const int value = 7; -}; - -template -struct tuple_size { - static const int value = 8; -}; - -template -struct tuple_size { - static const int value = 9; -}; - -template -struct tuple_size { - static const int value = 10; -}; - -template -struct tuple_element { - typedef typename gtest_internal::TupleElement< - k < (tuple_size::value), k, Tuple>::type type; -}; - -#define GTEST_TUPLE_ELEMENT_(k, Tuple) typename tuple_element::type - -// 6.1.3.4 Element access. - -namespace gtest_internal { - -template <> -class Get<0> { - public: - template - static GTEST_ADD_REF_(GTEST_TUPLE_ELEMENT_(0, Tuple)) - Field(Tuple& t) { return t.f0_; } // NOLINT - - template - static GTEST_BY_REF_(GTEST_TUPLE_ELEMENT_(0, Tuple)) - ConstField(const Tuple& t) { return t.f0_; } -}; - -template <> -class Get<1> { - public: - template - static GTEST_ADD_REF_(GTEST_TUPLE_ELEMENT_(1, Tuple)) - Field(Tuple& t) { return t.f1_; } // NOLINT - - template - static GTEST_BY_REF_(GTEST_TUPLE_ELEMENT_(1, Tuple)) - ConstField(const Tuple& t) { return t.f1_; } -}; - -template <> -class Get<2> { - public: - template - static GTEST_ADD_REF_(GTEST_TUPLE_ELEMENT_(2, Tuple)) - Field(Tuple& t) { return t.f2_; } // NOLINT - - template - static GTEST_BY_REF_(GTEST_TUPLE_ELEMENT_(2, Tuple)) - ConstField(const Tuple& t) { return t.f2_; } -}; - -template <> -class Get<3> { - public: - template - static GTEST_ADD_REF_(GTEST_TUPLE_ELEMENT_(3, Tuple)) - Field(Tuple& t) { return t.f3_; } // NOLINT - - template - static GTEST_BY_REF_(GTEST_TUPLE_ELEMENT_(3, Tuple)) - ConstField(const Tuple& t) { return t.f3_; } -}; - -template <> -class Get<4> { - public: - template - static GTEST_ADD_REF_(GTEST_TUPLE_ELEMENT_(4, Tuple)) - Field(Tuple& t) { return t.f4_; } // NOLINT - - template - static GTEST_BY_REF_(GTEST_TUPLE_ELEMENT_(4, Tuple)) - ConstField(const Tuple& t) { return t.f4_; } -}; - -template <> -class Get<5> { - public: - template - static GTEST_ADD_REF_(GTEST_TUPLE_ELEMENT_(5, Tuple)) - Field(Tuple& t) { return t.f5_; } // NOLINT - - template - static GTEST_BY_REF_(GTEST_TUPLE_ELEMENT_(5, Tuple)) - ConstField(const Tuple& t) { return t.f5_; } -}; - -template <> -class Get<6> { - public: - template - static GTEST_ADD_REF_(GTEST_TUPLE_ELEMENT_(6, Tuple)) - Field(Tuple& t) { return t.f6_; } // NOLINT - - template - static GTEST_BY_REF_(GTEST_TUPLE_ELEMENT_(6, Tuple)) - ConstField(const Tuple& t) { return t.f6_; } -}; - -template <> -class Get<7> { - public: - template - static GTEST_ADD_REF_(GTEST_TUPLE_ELEMENT_(7, Tuple)) - Field(Tuple& t) { return t.f7_; } // NOLINT - - template - static GTEST_BY_REF_(GTEST_TUPLE_ELEMENT_(7, Tuple)) - ConstField(const Tuple& t) { return t.f7_; } -}; - -template <> -class Get<8> { - public: - template - static GTEST_ADD_REF_(GTEST_TUPLE_ELEMENT_(8, Tuple)) - Field(Tuple& t) { return t.f8_; } // NOLINT - - template - static GTEST_BY_REF_(GTEST_TUPLE_ELEMENT_(8, Tuple)) - ConstField(const Tuple& t) { return t.f8_; } -}; - -template <> -class Get<9> { - public: - template - static GTEST_ADD_REF_(GTEST_TUPLE_ELEMENT_(9, Tuple)) - Field(Tuple& t) { return t.f9_; } // NOLINT - - template - static GTEST_BY_REF_(GTEST_TUPLE_ELEMENT_(9, Tuple)) - ConstField(const Tuple& t) { return t.f9_; } -}; - -} // namespace gtest_internal - -template -GTEST_ADD_REF_(GTEST_TUPLE_ELEMENT_(k, GTEST_10_TUPLE_(T))) -get(GTEST_10_TUPLE_(T)& t) { - return gtest_internal::Get::Field(t); -} - -template -GTEST_BY_REF_(GTEST_TUPLE_ELEMENT_(k, GTEST_10_TUPLE_(T))) -get(const GTEST_10_TUPLE_(T)& t) { - return gtest_internal::Get::ConstField(t); -} - -// 6.1.3.5 Relational operators - -// We only implement == and !=, as we don't have a need for the rest yet. - -namespace gtest_internal { - -// SameSizeTuplePrefixComparator::Eq(t1, t2) returns true if the -// first k fields of t1 equals the first k fields of t2. -// SameSizeTuplePrefixComparator(k1, k2) would be a compiler error if -// k1 != k2. -template -struct SameSizeTuplePrefixComparator; - -template <> -struct SameSizeTuplePrefixComparator<0, 0> { - template - static bool Eq(const Tuple1& /* t1 */, const Tuple2& /* t2 */) { - return true; - } -}; - -template -struct SameSizeTuplePrefixComparator { - template - static bool Eq(const Tuple1& t1, const Tuple2& t2) { - return SameSizeTuplePrefixComparator::Eq(t1, t2) && - ::std::tr1::get(t1) == ::std::tr1::get(t2); - } -}; - -} // namespace gtest_internal - -template -inline bool operator==(const GTEST_10_TUPLE_(T)& t, - const GTEST_10_TUPLE_(U)& u) { - return gtest_internal::SameSizeTuplePrefixComparator< - tuple_size::value, - tuple_size::value>::Eq(t, u); -} - -template -inline bool operator!=(const GTEST_10_TUPLE_(T)& t, - const GTEST_10_TUPLE_(U)& u) { return !(t == u); } - -// 6.1.4 Pairs. -// Unimplemented. - -} // namespace tr1 -} // namespace std - -#undef GTEST_0_TUPLE_ -#undef GTEST_1_TUPLE_ -#undef GTEST_2_TUPLE_ -#undef GTEST_3_TUPLE_ -#undef GTEST_4_TUPLE_ -#undef GTEST_5_TUPLE_ -#undef GTEST_6_TUPLE_ -#undef GTEST_7_TUPLE_ -#undef GTEST_8_TUPLE_ -#undef GTEST_9_TUPLE_ -#undef GTEST_10_TUPLE_ - -#undef GTEST_0_TYPENAMES_ -#undef GTEST_1_TYPENAMES_ -#undef GTEST_2_TYPENAMES_ -#undef GTEST_3_TYPENAMES_ -#undef GTEST_4_TYPENAMES_ -#undef GTEST_5_TYPENAMES_ -#undef GTEST_6_TYPENAMES_ -#undef GTEST_7_TYPENAMES_ -#undef GTEST_8_TYPENAMES_ -#undef GTEST_9_TYPENAMES_ -#undef GTEST_10_TYPENAMES_ - -#undef GTEST_DECLARE_TUPLE_AS_FRIEND_ -#undef GTEST_BY_REF_ -#undef GTEST_ADD_REF_ -#undef GTEST_TUPLE_ELEMENT_ - -#endif // GTEST_INCLUDE_GTEST_INTERNAL_GTEST_TUPLE_H_ -# elif GTEST_ENV_HAS_STD_TUPLE_ -# include -// C++11 puts its tuple into the ::std namespace rather than -// ::std::tr1. gtest expects tuple to live in ::std::tr1, so put it there. -// This causes undefined behavior, but supported compilers react in -// the way we intend. -namespace std { -namespace tr1 { -using ::std::get; -using ::std::make_tuple; -using ::std::tuple; -using ::std::tuple_element; -using ::std::tuple_size; -} -} - -# elif GTEST_OS_SYMBIAN - -// On Symbian, BOOST_HAS_TR1_TUPLE causes Boost's TR1 tuple library to -// use STLport's tuple implementation, which unfortunately doesn't -// work as the copy of STLport distributed with Symbian is incomplete. -// By making sure BOOST_HAS_TR1_TUPLE is undefined, we force Boost to -// use its own tuple implementation. -# ifdef BOOST_HAS_TR1_TUPLE -# undef BOOST_HAS_TR1_TUPLE -# endif // BOOST_HAS_TR1_TUPLE - -// This prevents , which defines -// BOOST_HAS_TR1_TUPLE, from being #included by Boost's . -# define BOOST_TR1_DETAIL_CONFIG_HPP_INCLUDED -# include - -# elif defined(__GNUC__) && (GTEST_GCC_VER_ >= 40000) -// GCC 4.0+ implements tr1/tuple in the header. This does -// not conform to the TR1 spec, which requires the header to be . - -# if !GTEST_HAS_RTTI && GTEST_GCC_VER_ < 40302 -// Until version 4.3.2, gcc has a bug that causes , -// which is #included by , to not compile when RTTI is -// disabled. _TR1_FUNCTIONAL is the header guard for -// . Hence the following #define is a hack to prevent -// from being included. -# define _TR1_FUNCTIONAL 1 -# include -# undef _TR1_FUNCTIONAL // Allows the user to #include - // if he chooses to. -# else -# include // NOLINT -# endif // !GTEST_HAS_RTTI && GTEST_GCC_VER_ < 40302 - -# else -// If the compiler is not GCC 4.0+, we assume the user is using a -// spec-conforming TR1 implementation. -# include // NOLINT -# endif // GTEST_USE_OWN_TR1_TUPLE - -#endif // GTEST_HAS_TR1_TUPLE - -// Determines whether clone(2) is supported. -// Usually it will only be available on Linux, excluding -// Linux on the Itanium architecture. -// Also see http://linux.die.net/man/2/clone. -#ifndef GTEST_HAS_CLONE -// The user didn't tell us, so we need to figure it out. - -# if GTEST_OS_LINUX && !defined(__ia64__) -# if GTEST_OS_LINUX_ANDROID -// On Android, clone() is only available on ARM starting with Gingerbread. -# if defined(__arm__) && __ANDROID_API__ >= 9 -# define GTEST_HAS_CLONE 1 -# else -# define GTEST_HAS_CLONE 0 -# endif -# else -# define GTEST_HAS_CLONE 1 -# endif -# else -# define GTEST_HAS_CLONE 0 -# endif // GTEST_OS_LINUX && !defined(__ia64__) - -#endif // GTEST_HAS_CLONE - -// Determines whether to support stream redirection. This is used to test -// output correctness and to implement death tests. -#ifndef GTEST_HAS_STREAM_REDIRECTION -// By default, we assume that stream redirection is supported on all -// platforms except known mobile ones. -# if GTEST_OS_WINDOWS_MOBILE || GTEST_OS_SYMBIAN -# define GTEST_HAS_STREAM_REDIRECTION 0 -# else -# define GTEST_HAS_STREAM_REDIRECTION 1 -# endif // !GTEST_OS_WINDOWS_MOBILE && !GTEST_OS_SYMBIAN -#endif // GTEST_HAS_STREAM_REDIRECTION - -// Determines whether to support death tests. -// Google Test does not support death tests for VC 7.1 and earlier as -// abort() in a VC 7.1 application compiled as GUI in debug config -// pops up a dialog window that cannot be suppressed programmatically. -#if (GTEST_OS_LINUX || GTEST_OS_CYGWIN || GTEST_OS_SOLARIS || \ - (GTEST_OS_MAC && !GTEST_OS_IOS) || GTEST_OS_IOS_SIMULATOR || \ - (GTEST_OS_WINDOWS_DESKTOP && _MSC_VER >= 1400) || \ - GTEST_OS_WINDOWS_MINGW || GTEST_OS_AIX || GTEST_OS_HPUX || \ - GTEST_OS_OPENBSD || GTEST_OS_QNX) -# define GTEST_HAS_DEATH_TEST 1 -# include // NOLINT -#endif - -// We don't support MSVC 7.1 with exceptions disabled now. Therefore -// all the compilers we care about are adequate for supporting -// value-parameterized tests. -#define GTEST_HAS_PARAM_TEST 1 - -// Determines whether to support type-driven tests. - -// Typed tests need and variadic macros, which GCC, VC++ 8.0, -// Sun Pro CC, IBM Visual Age, and HP aCC support. -#if defined(__GNUC__) || (_MSC_VER >= 1400) || defined(__SUNPRO_CC) || \ - defined(__IBMCPP__) || defined(__HP_aCC) -# define GTEST_HAS_TYPED_TEST 1 -# define GTEST_HAS_TYPED_TEST_P 1 -#endif - -// Determines whether to support Combine(). This only makes sense when -// value-parameterized tests are enabled. The implementation doesn't -// work on Sun Studio since it doesn't understand templated conversion -// operators. -#if GTEST_HAS_PARAM_TEST && GTEST_HAS_TR1_TUPLE && !defined(__SUNPRO_CC) -# define GTEST_HAS_COMBINE 1 -#endif - -// Determines whether the system compiler uses UTF-16 for encoding wide strings. -#define GTEST_WIDE_STRING_USES_UTF16_ \ - (GTEST_OS_WINDOWS || GTEST_OS_CYGWIN || GTEST_OS_SYMBIAN || GTEST_OS_AIX) - -// Determines whether test results can be streamed to a socket. -#if GTEST_OS_LINUX -# define GTEST_CAN_STREAM_RESULTS_ 1 -#endif - -// Defines some utility macros. - -// The GNU compiler emits a warning if nested "if" statements are followed by -// an "else" statement and braces are not used to explicitly disambiguate the -// "else" binding. This leads to problems with code like: -// -// if (gate) -// ASSERT_*(condition) << "Some message"; -// -// The "switch (0) case 0:" idiom is used to suppress this. -#ifdef __INTEL_COMPILER -# define GTEST_AMBIGUOUS_ELSE_BLOCKER_ -#else -# define GTEST_AMBIGUOUS_ELSE_BLOCKER_ switch (0) case 0: default: // NOLINT -#endif - -// Use this annotation at the end of a struct/class definition to -// prevent the compiler from optimizing away instances that are never -// used. This is useful when all interesting logic happens inside the -// c'tor and / or d'tor. Example: -// -// struct Foo { -// Foo() { ... } -// } GTEST_ATTRIBUTE_UNUSED_; -// -// Also use it after a variable or parameter declaration to tell the -// compiler the variable/parameter does not have to be used. -#if defined(__GNUC__) && !defined(COMPILER_ICC) -# define GTEST_ATTRIBUTE_UNUSED_ __attribute__ ((unused)) -#else -# define GTEST_ATTRIBUTE_UNUSED_ -#endif - -// A macro to disallow operator= -// This should be used in the private: declarations for a class. -#define GTEST_DISALLOW_ASSIGN_(type)\ - void operator=(type const &) - -// A macro to disallow copy constructor and operator= -// This should be used in the private: declarations for a class. -#define GTEST_DISALLOW_COPY_AND_ASSIGN_(type)\ - type(type const &);\ - GTEST_DISALLOW_ASSIGN_(type) - -// Tell the compiler to warn about unused return values for functions declared -// with this macro. The macro should be used on function declarations -// following the argument list: -// -// Sprocket* AllocateSprocket() GTEST_MUST_USE_RESULT_; -#if defined(__GNUC__) && (GTEST_GCC_VER_ >= 30400) && !defined(COMPILER_ICC) -# define GTEST_MUST_USE_RESULT_ __attribute__ ((warn_unused_result)) -#else -# define GTEST_MUST_USE_RESULT_ -#endif // __GNUC__ && (GTEST_GCC_VER_ >= 30400) && !COMPILER_ICC - -// Determine whether the compiler supports Microsoft's Structured Exception -// Handling. This is supported by several Windows compilers but generally -// does not exist on any other system. -#ifndef GTEST_HAS_SEH -// The user didn't tell us, so we need to figure it out. - -# if defined(_MSC_VER) || defined(__BORLANDC__) -// These two compilers are known to support SEH. -# define GTEST_HAS_SEH 1 -# else -// Assume no SEH. -# define GTEST_HAS_SEH 0 -# endif - -#endif // GTEST_HAS_SEH - -#ifdef _MSC_VER - -# if GTEST_LINKED_AS_SHARED_LIBRARY -# define GTEST_API_ __declspec(dllimport) -# elif GTEST_CREATE_SHARED_LIBRARY -# define GTEST_API_ __declspec(dllexport) -# endif - -#endif // _MSC_VER - -#ifndef GTEST_API_ -# define GTEST_API_ -#endif - -#ifdef __GNUC__ -// Ask the compiler to never inline a given function. -# define GTEST_NO_INLINE_ __attribute__((noinline)) -#else -# define GTEST_NO_INLINE_ -#endif - -// _LIBCPP_VERSION is defined by the libc++ library from the LLVM project. -#if defined(__GLIBCXX__) || defined(_LIBCPP_VERSION) -# define GTEST_HAS_CXXABI_H_ 1 -#else -# define GTEST_HAS_CXXABI_H_ 0 -#endif - -namespace testing { - -class Message; - -namespace internal { - -// A secret type that Google Test users don't know about. It has no -// definition on purpose. Therefore it's impossible to create a -// Secret object, which is what we want. -class Secret; - -// The GTEST_COMPILE_ASSERT_ macro can be used to verify that a compile time -// expression is true. For example, you could use it to verify the -// size of a static array: -// -// GTEST_COMPILE_ASSERT_(ARRAYSIZE(content_type_names) == CONTENT_NUM_TYPES, -// content_type_names_incorrect_size); -// -// or to make sure a struct is smaller than a certain size: -// -// GTEST_COMPILE_ASSERT_(sizeof(foo) < 128, foo_too_large); -// -// The second argument to the macro is the name of the variable. If -// the expression is false, most compilers will issue a warning/error -// containing the name of the variable. - -template -struct CompileAssert { -}; - -#define GTEST_COMPILE_ASSERT_(expr, msg) \ - typedef ::testing::internal::CompileAssert<(static_cast(expr))> \ - msg[static_cast(expr) ? 1 : -1] GTEST_ATTRIBUTE_UNUSED_ - -// Implementation details of GTEST_COMPILE_ASSERT_: -// -// - GTEST_COMPILE_ASSERT_ works by defining an array type that has -1 -// elements (and thus is invalid) when the expression is false. -// -// - The simpler definition -// -// #define GTEST_COMPILE_ASSERT_(expr, msg) typedef char msg[(expr) ? 1 : -1] -// -// does not work, as gcc supports variable-length arrays whose sizes -// are determined at run-time (this is gcc's extension and not part -// of the C++ standard). As a result, gcc fails to reject the -// following code with the simple definition: -// -// int foo; -// GTEST_COMPILE_ASSERT_(foo, msg); // not supposed to compile as foo is -// // not a compile-time constant. -// -// - By using the type CompileAssert<(bool(expr))>, we ensures that -// expr is a compile-time constant. (Template arguments must be -// determined at compile-time.) -// -// - The outter parentheses in CompileAssert<(bool(expr))> are necessary -// to work around a bug in gcc 3.4.4 and 4.0.1. If we had written -// -// CompileAssert -// -// instead, these compilers will refuse to compile -// -// GTEST_COMPILE_ASSERT_(5 > 0, some_message); -// -// (They seem to think the ">" in "5 > 0" marks the end of the -// template argument list.) -// -// - The array size is (bool(expr) ? 1 : -1), instead of simply -// -// ((expr) ? 1 : -1). -// -// This is to avoid running into a bug in MS VC 7.1, which -// causes ((0.0) ? 1 : -1) to incorrectly evaluate to 1. - -// StaticAssertTypeEqHelper is used by StaticAssertTypeEq defined in gtest.h. -// -// This template is declared, but intentionally undefined. -template -struct StaticAssertTypeEqHelper; - -template -struct StaticAssertTypeEqHelper {}; - -#if GTEST_HAS_GLOBAL_STRING -typedef ::string string; -#else -typedef ::std::string string; -#endif // GTEST_HAS_GLOBAL_STRING - -#if GTEST_HAS_GLOBAL_WSTRING -typedef ::wstring wstring; -#elif GTEST_HAS_STD_WSTRING -typedef ::std::wstring wstring; -#endif // GTEST_HAS_GLOBAL_WSTRING - -// A helper for suppressing warnings on constant condition. It just -// returns 'condition'. -GTEST_API_ bool IsTrue(bool condition); - -// Defines scoped_ptr. - -// This implementation of scoped_ptr is PARTIAL - it only contains -// enough stuff to satisfy Google Test's need. -template -class scoped_ptr { - public: - typedef T element_type; - - explicit scoped_ptr(T* p = NULL) : ptr_(p) {} - ~scoped_ptr() { reset(); } - - T& operator*() const { return *ptr_; } - T* operator->() const { return ptr_; } - T* get() const { return ptr_; } - - T* release() { - T* const ptr = ptr_; - ptr_ = NULL; - return ptr; - } - - void reset(T* p = NULL) { - if (p != ptr_) { - if (IsTrue(sizeof(T) > 0)) { // Makes sure T is a complete type. - delete ptr_; - } - ptr_ = p; - } - } - - private: - T* ptr_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(scoped_ptr); -}; - -// Defines RE. - -// A simple C++ wrapper for . It uses the POSIX Extended -// Regular Expression syntax. -class GTEST_API_ RE { - public: - // A copy constructor is required by the Standard to initialize object - // references from r-values. - RE(const RE& other) { Init(other.pattern()); } - - // Constructs an RE from a string. - RE(const ::std::string& regex) { Init(regex.c_str()); } // NOLINT - -#if GTEST_HAS_GLOBAL_STRING - - RE(const ::string& regex) { Init(regex.c_str()); } // NOLINT - -#endif // GTEST_HAS_GLOBAL_STRING - - RE(const char* regex) { Init(regex); } // NOLINT - ~RE(); - - // Returns the string representation of the regex. - const char* pattern() const { return pattern_; } - - // FullMatch(str, re) returns true iff regular expression re matches - // the entire str. - // PartialMatch(str, re) returns true iff regular expression re - // matches a substring of str (including str itself). - // - // TODO(wan@google.com): make FullMatch() and PartialMatch() work - // when str contains NUL characters. - static bool FullMatch(const ::std::string& str, const RE& re) { - return FullMatch(str.c_str(), re); - } - static bool PartialMatch(const ::std::string& str, const RE& re) { - return PartialMatch(str.c_str(), re); - } - -#if GTEST_HAS_GLOBAL_STRING - - static bool FullMatch(const ::string& str, const RE& re) { - return FullMatch(str.c_str(), re); - } - static bool PartialMatch(const ::string& str, const RE& re) { - return PartialMatch(str.c_str(), re); - } - -#endif // GTEST_HAS_GLOBAL_STRING - - static bool FullMatch(const char* str, const RE& re); - static bool PartialMatch(const char* str, const RE& re); - - private: - void Init(const char* regex); - - // We use a const char* instead of an std::string, as Google Test used to be - // used where std::string is not available. TODO(wan@google.com): change to - // std::string. - const char* pattern_; - bool is_valid_; - -#if GTEST_USES_POSIX_RE - - regex_t full_regex_; // For FullMatch(). - regex_t partial_regex_; // For PartialMatch(). - -#else // GTEST_USES_SIMPLE_RE - - const char* full_pattern_; // For FullMatch(); - -#endif - - GTEST_DISALLOW_ASSIGN_(RE); -}; - -// Formats a source file path and a line number as they would appear -// in an error message from the compiler used to compile this code. -GTEST_API_ ::std::string FormatFileLocation(const char* file, int line); - -// Formats a file location for compiler-independent XML output. -// Although this function is not platform dependent, we put it next to -// FormatFileLocation in order to contrast the two functions. -GTEST_API_ ::std::string FormatCompilerIndependentFileLocation(const char* file, - int line); - -// Defines logging utilities: -// GTEST_LOG_(severity) - logs messages at the specified severity level. The -// message itself is streamed into the macro. -// LogToStderr() - directs all log messages to stderr. -// FlushInfoLog() - flushes informational log messages. - -enum GTestLogSeverity { - GTEST_INFO, - GTEST_WARNING, - GTEST_ERROR, - GTEST_FATAL -}; - -// Formats log entry severity, provides a stream object for streaming the -// log message, and terminates the message with a newline when going out of -// scope. -class GTEST_API_ GTestLog { - public: - GTestLog(GTestLogSeverity severity, const char* file, int line); - - // Flushes the buffers and, if severity is GTEST_FATAL, aborts the program. - ~GTestLog(); - - ::std::ostream& GetStream() { return ::std::cerr; } - - private: - const GTestLogSeverity severity_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(GTestLog); -}; - -#define GTEST_LOG_(severity) \ - ::testing::internal::GTestLog(::testing::internal::GTEST_##severity, \ - __FILE__, __LINE__).GetStream() - -inline void LogToStderr() {} -inline void FlushInfoLog() { fflush(NULL); } - -// INTERNAL IMPLEMENTATION - DO NOT USE. -// -// GTEST_CHECK_ is an all-mode assert. It aborts the program if the condition -// is not satisfied. -// Synopsys: -// GTEST_CHECK_(boolean_condition); -// or -// GTEST_CHECK_(boolean_condition) << "Additional message"; -// -// This checks the condition and if the condition is not satisfied -// it prints message about the condition violation, including the -// condition itself, plus additional message streamed into it, if any, -// and then it aborts the program. It aborts the program irrespective of -// whether it is built in the debug mode or not. -#define GTEST_CHECK_(condition) \ - GTEST_AMBIGUOUS_ELSE_BLOCKER_ \ - if (::testing::internal::IsTrue(condition)) \ - ; \ - else \ - GTEST_LOG_(FATAL) << "Condition " #condition " failed. " - -// An all-mode assert to verify that the given POSIX-style function -// call returns 0 (indicating success). Known limitation: this -// doesn't expand to a balanced 'if' statement, so enclose the macro -// in {} if you need to use it as the only statement in an 'if' -// branch. -#define GTEST_CHECK_POSIX_SUCCESS_(posix_call) \ - if (const int gtest_error = (posix_call)) \ - GTEST_LOG_(FATAL) << #posix_call << "failed with error " \ - << gtest_error - -// INTERNAL IMPLEMENTATION - DO NOT USE IN USER CODE. -// -// Use ImplicitCast_ as a safe version of static_cast for upcasting in -// the type hierarchy (e.g. casting a Foo* to a SuperclassOfFoo* or a -// const Foo*). When you use ImplicitCast_, the compiler checks that -// the cast is safe. Such explicit ImplicitCast_s are necessary in -// surprisingly many situations where C++ demands an exact type match -// instead of an argument type convertable to a target type. -// -// The syntax for using ImplicitCast_ is the same as for static_cast: -// -// ImplicitCast_(expr) -// -// ImplicitCast_ would have been part of the C++ standard library, -// but the proposal was submitted too late. It will probably make -// its way into the language in the future. -// -// This relatively ugly name is intentional. It prevents clashes with -// similar functions users may have (e.g., implicit_cast). The internal -// namespace alone is not enough because the function can be found by ADL. -template -inline To ImplicitCast_(To x) { return x; } - -// When you upcast (that is, cast a pointer from type Foo to type -// SuperclassOfFoo), it's fine to use ImplicitCast_<>, since upcasts -// always succeed. When you downcast (that is, cast a pointer from -// type Foo to type SubclassOfFoo), static_cast<> isn't safe, because -// how do you know the pointer is really of type SubclassOfFoo? It -// could be a bare Foo, or of type DifferentSubclassOfFoo. Thus, -// when you downcast, you should use this macro. In debug mode, we -// use dynamic_cast<> to double-check the downcast is legal (we die -// if it's not). In normal mode, we do the efficient static_cast<> -// instead. Thus, it's important to test in debug mode to make sure -// the cast is legal! -// This is the only place in the code we should use dynamic_cast<>. -// In particular, you SHOULDN'T be using dynamic_cast<> in order to -// do RTTI (eg code like this: -// if (dynamic_cast(foo)) HandleASubclass1Object(foo); -// if (dynamic_cast(foo)) HandleASubclass2Object(foo); -// You should design the code some other way not to need this. -// -// This relatively ugly name is intentional. It prevents clashes with -// similar functions users may have (e.g., down_cast). The internal -// namespace alone is not enough because the function can be found by ADL. -template // use like this: DownCast_(foo); -inline To DownCast_(From* f) { // so we only accept pointers - // Ensures that To is a sub-type of From *. This test is here only - // for compile-time type checking, and has no overhead in an - // optimized build at run-time, as it will be optimized away - // completely. - if (false) { - const To to = NULL; - ::testing::internal::ImplicitCast_(to); - } - -#if GTEST_HAS_RTTI - // RTTI: debug mode only! - GTEST_CHECK_(f == NULL || dynamic_cast(f) != NULL); -#endif - return static_cast(f); -} - -// Downcasts the pointer of type Base to Derived. -// Derived must be a subclass of Base. The parameter MUST -// point to a class of type Derived, not any subclass of it. -// When RTTI is available, the function performs a runtime -// check to enforce this. -template -Derived* CheckedDowncastToActualType(Base* base) { -#if GTEST_HAS_RTTI - GTEST_CHECK_(typeid(*base) == typeid(Derived)); - return dynamic_cast(base); // NOLINT -#else - return static_cast(base); // Poor man's downcast. -#endif -} - -#if GTEST_HAS_STREAM_REDIRECTION - -// Defines the stderr capturer: -// CaptureStdout - starts capturing stdout. -// GetCapturedStdout - stops capturing stdout and returns the captured string. -// CaptureStderr - starts capturing stderr. -// GetCapturedStderr - stops capturing stderr and returns the captured string. -// -GTEST_API_ void CaptureStdout(); -GTEST_API_ std::string GetCapturedStdout(); -GTEST_API_ void CaptureStderr(); -GTEST_API_ std::string GetCapturedStderr(); - -#endif // GTEST_HAS_STREAM_REDIRECTION - - -#if GTEST_HAS_DEATH_TEST - -const ::std::vector& GetInjectableArgvs(); -void SetInjectableArgvs(const ::std::vector* - new_argvs); - -// A copy of all command line arguments. Set by InitGoogleTest(). -extern ::std::vector g_argvs; - -#endif // GTEST_HAS_DEATH_TEST - -// Defines synchronization primitives. - -#if GTEST_HAS_PTHREAD - -// Sleeps for (roughly) n milli-seconds. This function is only for -// testing Google Test's own constructs. Don't use it in user tests, -// either directly or indirectly. -inline void SleepMilliseconds(int n) { - const timespec time = { - 0, // 0 seconds. - n * 1000L * 1000L, // And n ms. - }; - nanosleep(&time, NULL); -} - -// Allows a controller thread to pause execution of newly created -// threads until notified. Instances of this class must be created -// and destroyed in the controller thread. -// -// This class is only for testing Google Test's own constructs. Do not -// use it in user tests, either directly or indirectly. -class Notification { - public: - Notification() : notified_(false) { - GTEST_CHECK_POSIX_SUCCESS_(pthread_mutex_init(&mutex_, NULL)); - } - ~Notification() { - pthread_mutex_destroy(&mutex_); - } - - // Notifies all threads created with this notification to start. Must - // be called from the controller thread. - void Notify() { - pthread_mutex_lock(&mutex_); - notified_ = true; - pthread_mutex_unlock(&mutex_); - } - - // Blocks until the controller thread notifies. Must be called from a test - // thread. - void WaitForNotification() { - for (;;) { - pthread_mutex_lock(&mutex_); - const bool notified = notified_; - pthread_mutex_unlock(&mutex_); - if (notified) - break; - SleepMilliseconds(10); - } - } - - private: - pthread_mutex_t mutex_; - bool notified_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(Notification); -}; - -// As a C-function, ThreadFuncWithCLinkage cannot be templated itself. -// Consequently, it cannot select a correct instantiation of ThreadWithParam -// in order to call its Run(). Introducing ThreadWithParamBase as a -// non-templated base class for ThreadWithParam allows us to bypass this -// problem. -class ThreadWithParamBase { - public: - virtual ~ThreadWithParamBase() {} - virtual void Run() = 0; -}; - -// pthread_create() accepts a pointer to a function type with the C linkage. -// According to the Standard (7.5/1), function types with different linkages -// are different even if they are otherwise identical. Some compilers (for -// example, SunStudio) treat them as different types. Since class methods -// cannot be defined with C-linkage we need to define a free C-function to -// pass into pthread_create(). -extern "C" inline void* ThreadFuncWithCLinkage(void* thread) { - static_cast(thread)->Run(); - return NULL; -} - -// Helper class for testing Google Test's multi-threading constructs. -// To use it, write: -// -// void ThreadFunc(int param) { /* Do things with param */ } -// Notification thread_can_start; -// ... -// // The thread_can_start parameter is optional; you can supply NULL. -// ThreadWithParam thread(&ThreadFunc, 5, &thread_can_start); -// thread_can_start.Notify(); -// -// These classes are only for testing Google Test's own constructs. Do -// not use them in user tests, either directly or indirectly. -template -class ThreadWithParam : public ThreadWithParamBase { - public: - typedef void (*UserThreadFunc)(T); - - ThreadWithParam( - UserThreadFunc func, T param, Notification* thread_can_start) - : func_(func), - param_(param), - thread_can_start_(thread_can_start), - finished_(false) { - ThreadWithParamBase* const base = this; - // The thread can be created only after all fields except thread_ - // have been initialized. - GTEST_CHECK_POSIX_SUCCESS_( - pthread_create(&thread_, 0, &ThreadFuncWithCLinkage, base)); - } - ~ThreadWithParam() { Join(); } - - void Join() { - if (!finished_) { - GTEST_CHECK_POSIX_SUCCESS_(pthread_join(thread_, 0)); - finished_ = true; - } - } - - virtual void Run() { - if (thread_can_start_ != NULL) - thread_can_start_->WaitForNotification(); - func_(param_); - } - - private: - const UserThreadFunc func_; // User-supplied thread function. - const T param_; // User-supplied parameter to the thread function. - // When non-NULL, used to block execution until the controller thread - // notifies. - Notification* const thread_can_start_; - bool finished_; // true iff we know that the thread function has finished. - pthread_t thread_; // The native thread object. - - GTEST_DISALLOW_COPY_AND_ASSIGN_(ThreadWithParam); -}; - -// MutexBase and Mutex implement mutex on pthreads-based platforms. They -// are used in conjunction with class MutexLock: -// -// Mutex mutex; -// ... -// MutexLock lock(&mutex); // Acquires the mutex and releases it at the end -// // of the current scope. -// -// MutexBase implements behavior for both statically and dynamically -// allocated mutexes. Do not use MutexBase directly. Instead, write -// the following to define a static mutex: -// -// GTEST_DEFINE_STATIC_MUTEX_(g_some_mutex); -// -// You can forward declare a static mutex like this: -// -// GTEST_DECLARE_STATIC_MUTEX_(g_some_mutex); -// -// To create a dynamic mutex, just define an object of type Mutex. -class MutexBase { - public: - // Acquires this mutex. - void Lock() { - GTEST_CHECK_POSIX_SUCCESS_(pthread_mutex_lock(&mutex_)); - owner_ = pthread_self(); - has_owner_ = true; - } - - // Releases this mutex. - void Unlock() { - // Since the lock is being released the owner_ field should no longer be - // considered valid. We don't protect writing to has_owner_ here, as it's - // the caller's responsibility to ensure that the current thread holds the - // mutex when this is called. - has_owner_ = false; - GTEST_CHECK_POSIX_SUCCESS_(pthread_mutex_unlock(&mutex_)); - } - - // Does nothing if the current thread holds the mutex. Otherwise, crashes - // with high probability. - void AssertHeld() const { - GTEST_CHECK_(has_owner_ && pthread_equal(owner_, pthread_self())) - << "The current thread is not holding the mutex @" << this; - } - - // A static mutex may be used before main() is entered. It may even - // be used before the dynamic initialization stage. Therefore we - // must be able to initialize a static mutex object at link time. - // This means MutexBase has to be a POD and its member variables - // have to be public. - public: - pthread_mutex_t mutex_; // The underlying pthread mutex. - // has_owner_ indicates whether the owner_ field below contains a valid thread - // ID and is therefore safe to inspect (e.g., to use in pthread_equal()). All - // accesses to the owner_ field should be protected by a check of this field. - // An alternative might be to memset() owner_ to all zeros, but there's no - // guarantee that a zero'd pthread_t is necessarily invalid or even different - // from pthread_self(). - bool has_owner_; - pthread_t owner_; // The thread holding the mutex. -}; - -// Forward-declares a static mutex. -# define GTEST_DECLARE_STATIC_MUTEX_(mutex) \ - extern ::testing::internal::MutexBase mutex - -// Defines and statically (i.e. at link time) initializes a static mutex. -// The initialization list here does not explicitly initialize each field, -// instead relying on default initialization for the unspecified fields. In -// particular, the owner_ field (a pthread_t) is not explicitly initialized. -// This allows initialization to work whether pthread_t is a scalar or struct. -// The flag -Wmissing-field-initializers must not be specified for this to work. -# define GTEST_DEFINE_STATIC_MUTEX_(mutex) \ - ::testing::internal::MutexBase mutex = { PTHREAD_MUTEX_INITIALIZER, false } - -// The Mutex class can only be used for mutexes created at runtime. It -// shares its API with MutexBase otherwise. -class Mutex : public MutexBase { - public: - Mutex() { - GTEST_CHECK_POSIX_SUCCESS_(pthread_mutex_init(&mutex_, NULL)); - has_owner_ = false; - } - ~Mutex() { - GTEST_CHECK_POSIX_SUCCESS_(pthread_mutex_destroy(&mutex_)); - } - - private: - GTEST_DISALLOW_COPY_AND_ASSIGN_(Mutex); -}; - -// We cannot name this class MutexLock as the ctor declaration would -// conflict with a macro named MutexLock, which is defined on some -// platforms. Hence the typedef trick below. -class GTestMutexLock { - public: - explicit GTestMutexLock(MutexBase* mutex) - : mutex_(mutex) { mutex_->Lock(); } - - ~GTestMutexLock() { mutex_->Unlock(); } - - private: - MutexBase* const mutex_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(GTestMutexLock); -}; - -typedef GTestMutexLock MutexLock; - -// Helpers for ThreadLocal. - -// pthread_key_create() requires DeleteThreadLocalValue() to have -// C-linkage. Therefore it cannot be templatized to access -// ThreadLocal. Hence the need for class -// ThreadLocalValueHolderBase. -class ThreadLocalValueHolderBase { - public: - virtual ~ThreadLocalValueHolderBase() {} -}; - -// Called by pthread to delete thread-local data stored by -// pthread_setspecific(). -extern "C" inline void DeleteThreadLocalValue(void* value_holder) { - delete static_cast(value_holder); -} - -// Implements thread-local storage on pthreads-based systems. -// -// // Thread 1 -// ThreadLocal tl(100); // 100 is the default value for each thread. -// -// // Thread 2 -// tl.set(150); // Changes the value for thread 2 only. -// EXPECT_EQ(150, tl.get()); -// -// // Thread 1 -// EXPECT_EQ(100, tl.get()); // In thread 1, tl has the original value. -// tl.set(200); -// EXPECT_EQ(200, tl.get()); -// -// The template type argument T must have a public copy constructor. -// In addition, the default ThreadLocal constructor requires T to have -// a public default constructor. -// -// An object managed for a thread by a ThreadLocal instance is deleted -// when the thread exits. Or, if the ThreadLocal instance dies in -// that thread, when the ThreadLocal dies. It's the user's -// responsibility to ensure that all other threads using a ThreadLocal -// have exited when it dies, or the per-thread objects for those -// threads will not be deleted. -// -// Google Test only uses global ThreadLocal objects. That means they -// will die after main() has returned. Therefore, no per-thread -// object managed by Google Test will be leaked as long as all threads -// using Google Test have exited when main() returns. -template -class ThreadLocal { - public: - ThreadLocal() : key_(CreateKey()), - default_() {} - explicit ThreadLocal(const T& value) : key_(CreateKey()), - default_(value) {} - - ~ThreadLocal() { - // Destroys the managed object for the current thread, if any. - DeleteThreadLocalValue(pthread_getspecific(key_)); - - // Releases resources associated with the key. This will *not* - // delete managed objects for other threads. - GTEST_CHECK_POSIX_SUCCESS_(pthread_key_delete(key_)); - } - - T* pointer() { return GetOrCreateValue(); } - const T* pointer() const { return GetOrCreateValue(); } - const T& get() const { return *pointer(); } - void set(const T& value) { *pointer() = value; } - - private: - // Holds a value of type T. - class ValueHolder : public ThreadLocalValueHolderBase { - public: - explicit ValueHolder(const T& value) : value_(value) {} - - T* pointer() { return &value_; } - - private: - T value_; - GTEST_DISALLOW_COPY_AND_ASSIGN_(ValueHolder); - }; - - static pthread_key_t CreateKey() { - pthread_key_t key; - // When a thread exits, DeleteThreadLocalValue() will be called on - // the object managed for that thread. - GTEST_CHECK_POSIX_SUCCESS_( - pthread_key_create(&key, &DeleteThreadLocalValue)); - return key; - } - - T* GetOrCreateValue() const { - ThreadLocalValueHolderBase* const holder = - static_cast(pthread_getspecific(key_)); - if (holder != NULL) { - return CheckedDowncastToActualType(holder)->pointer(); - } - - ValueHolder* const new_holder = new ValueHolder(default_); - ThreadLocalValueHolderBase* const holder_base = new_holder; - GTEST_CHECK_POSIX_SUCCESS_(pthread_setspecific(key_, holder_base)); - return new_holder->pointer(); - } - - // A key pthreads uses for looking up per-thread values. - const pthread_key_t key_; - const T default_; // The default value for each thread. - - GTEST_DISALLOW_COPY_AND_ASSIGN_(ThreadLocal); -}; - -# define GTEST_IS_THREADSAFE 1 - -#else // GTEST_HAS_PTHREAD - -// A dummy implementation of synchronization primitives (mutex, lock, -// and thread-local variable). Necessary for compiling Google Test where -// mutex is not supported - using Google Test in multiple threads is not -// supported on such platforms. - -class Mutex { - public: - Mutex() {} - void Lock() {} - void Unlock() {} - void AssertHeld() const {} -}; - -# define GTEST_DECLARE_STATIC_MUTEX_(mutex) \ - extern ::testing::internal::Mutex mutex - -# define GTEST_DEFINE_STATIC_MUTEX_(mutex) ::testing::internal::Mutex mutex - -class GTestMutexLock { - public: - explicit GTestMutexLock(Mutex*) {} // NOLINT -}; - -typedef GTestMutexLock MutexLock; - -template -class ThreadLocal { - public: - ThreadLocal() : value_() {} - explicit ThreadLocal(const T& value) : value_(value) {} - T* pointer() { return &value_; } - const T* pointer() const { return &value_; } - const T& get() const { return value_; } - void set(const T& value) { value_ = value; } - private: - T value_; -}; - -// The above synchronization primitives have dummy implementations. -// Therefore Google Test is not thread-safe. -# define GTEST_IS_THREADSAFE 0 - -#endif // GTEST_HAS_PTHREAD - -// Returns the number of threads running in the process, or 0 to indicate that -// we cannot detect it. -GTEST_API_ size_t GetThreadCount(); - -// Passing non-POD classes through ellipsis (...) crashes the ARM -// compiler and generates a warning in Sun Studio. The Nokia Symbian -// and the IBM XL C/C++ compiler try to instantiate a copy constructor -// for objects passed through ellipsis (...), failing for uncopyable -// objects. We define this to ensure that only POD is passed through -// ellipsis on these systems. -#if defined(__SYMBIAN32__) || defined(__IBMCPP__) || defined(__SUNPRO_CC) -// We lose support for NULL detection where the compiler doesn't like -// passing non-POD classes through ellipsis (...). -# define GTEST_ELLIPSIS_NEEDS_POD_ 1 -#else -# define GTEST_CAN_COMPARE_NULL 1 -#endif - -// The Nokia Symbian and IBM XL C/C++ compilers cannot decide between -// const T& and const T* in a function template. These compilers -// _can_ decide between class template specializations for T and T*, -// so a tr1::type_traits-like is_pointer works. -#if defined(__SYMBIAN32__) || defined(__IBMCPP__) -# define GTEST_NEEDS_IS_POINTER_ 1 -#endif - -template -struct bool_constant { - typedef bool_constant type; - static const bool value = bool_value; -}; -template const bool bool_constant::value; - -typedef bool_constant false_type; -typedef bool_constant true_type; - -template -struct is_pointer : public false_type {}; - -template -struct is_pointer : public true_type {}; - -template -struct IteratorTraits { - typedef typename Iterator::value_type value_type; -}; - -template -struct IteratorTraits { - typedef T value_type; -}; - -template -struct IteratorTraits { - typedef T value_type; -}; - -#if GTEST_OS_WINDOWS -# define GTEST_PATH_SEP_ "\\" -# define GTEST_HAS_ALT_PATH_SEP_ 1 -// The biggest signed integer type the compiler supports. -typedef __int64 BiggestInt; -#else -# define GTEST_PATH_SEP_ "/" -# define GTEST_HAS_ALT_PATH_SEP_ 0 -typedef long long BiggestInt; // NOLINT -#endif // GTEST_OS_WINDOWS - -// Utilities for char. - -// isspace(int ch) and friends accept an unsigned char or EOF. char -// may be signed, depending on the compiler (or compiler flags). -// Therefore we need to cast a char to unsigned char before calling -// isspace(), etc. - -inline bool IsAlpha(char ch) { - return isalpha(static_cast(ch)) != 0; -} -inline bool IsAlNum(char ch) { - return isalnum(static_cast(ch)) != 0; -} -inline bool IsDigit(char ch) { - return isdigit(static_cast(ch)) != 0; -} -inline bool IsLower(char ch) { - return islower(static_cast(ch)) != 0; -} -inline bool IsSpace(char ch) { - return isspace(static_cast(ch)) != 0; -} -inline bool IsUpper(char ch) { - return isupper(static_cast(ch)) != 0; -} -inline bool IsXDigit(char ch) { - return isxdigit(static_cast(ch)) != 0; -} -inline bool IsXDigit(wchar_t ch) { - const unsigned char low_byte = static_cast(ch); - return ch == low_byte && isxdigit(low_byte) != 0; -} - -inline char ToLower(char ch) { - return static_cast(tolower(static_cast(ch))); -} -inline char ToUpper(char ch) { - return static_cast(toupper(static_cast(ch))); -} - -// The testing::internal::posix namespace holds wrappers for common -// POSIX functions. These wrappers hide the differences between -// Windows/MSVC and POSIX systems. Since some compilers define these -// standard functions as macros, the wrapper cannot have the same name -// as the wrapped function. - -namespace posix { - -// Functions with a different name on Windows. - -#if GTEST_OS_WINDOWS - -typedef struct _stat StatStruct; - -# ifdef __BORLANDC__ -inline int IsATTY(int fd) { return isatty(fd); } -inline int StrCaseCmp(const char* s1, const char* s2) { - return stricmp(s1, s2); -} -inline char* StrDup(const char* src) { return strdup(src); } -# else // !__BORLANDC__ -# if GTEST_OS_WINDOWS_MOBILE -inline int IsATTY(int /* fd */) { return 0; } -# else -inline int IsATTY(int fd) { return _isatty(fd); } -# endif // GTEST_OS_WINDOWS_MOBILE -inline int StrCaseCmp(const char* s1, const char* s2) { - return _stricmp(s1, s2); -} -inline char* StrDup(const char* src) { return _strdup(src); } -# endif // __BORLANDC__ - -# if GTEST_OS_WINDOWS_MOBILE -inline int FileNo(FILE* file) { return reinterpret_cast(_fileno(file)); } -// Stat(), RmDir(), and IsDir() are not needed on Windows CE at this -// time and thus not defined there. -# else -inline int FileNo(FILE* file) { return _fileno(file); } -inline int Stat(const char* path, StatStruct* buf) { return _stat(path, buf); } -inline int RmDir(const char* dir) { return _rmdir(dir); } -inline bool IsDir(const StatStruct& st) { - return (_S_IFDIR & st.st_mode) != 0; -} -# endif // GTEST_OS_WINDOWS_MOBILE - -#else - -typedef struct stat StatStruct; - -inline int FileNo(FILE* file) { return fileno(file); } -inline int IsATTY(int fd) { return isatty(fd); } -inline int Stat(const char* path, StatStruct* buf) { return stat(path, buf); } -inline int StrCaseCmp(const char* s1, const char* s2) { - return strcasecmp(s1, s2); -} -inline char* StrDup(const char* src) { return strdup(src); } -inline int RmDir(const char* dir) { return rmdir(dir); } -inline bool IsDir(const StatStruct& st) { return S_ISDIR(st.st_mode); } - -#endif // GTEST_OS_WINDOWS - -// Functions deprecated by MSVC 8.0. - -#ifdef _MSC_VER -// Temporarily disable warning 4996 (deprecated function). -# pragma warning(push) -# pragma warning(disable:4996) -#endif - -inline const char* StrNCpy(char* dest, const char* src, size_t n) { - return strncpy(dest, src, n); -} - -// ChDir(), FReopen(), FDOpen(), Read(), Write(), Close(), and -// StrError() aren't needed on Windows CE at this time and thus not -// defined there. - -#if !GTEST_OS_WINDOWS_MOBILE -inline int ChDir(const char* dir) { return chdir(dir); } -#endif -inline FILE* FOpen(const char* path, const char* mode) { - return fopen(path, mode); -} -#if !GTEST_OS_WINDOWS_MOBILE -inline FILE *FReopen(const char* path, const char* mode, FILE* stream) { - return freopen(path, mode, stream); -} -inline FILE* FDOpen(int fd, const char* mode) { return fdopen(fd, mode); } -#endif -inline int FClose(FILE* fp) { return fclose(fp); } -#if !GTEST_OS_WINDOWS_MOBILE -inline int Read(int fd, void* buf, unsigned int count) { - return static_cast(read(fd, buf, count)); -} -inline int Write(int fd, const void* buf, unsigned int count) { - return static_cast(write(fd, buf, count)); -} -inline int Close(int fd) { return close(fd); } -inline const char* StrError(int errnum) { return strerror(errnum); } -#endif -inline const char* GetEnv(const char* name) { -#if GTEST_OS_WINDOWS_MOBILE - // We are on Windows CE, which has no environment variables. - return NULL; -#elif defined(__BORLANDC__) || defined(__SunOS_5_8) || defined(__SunOS_5_9) - // Environment variables which we programmatically clear will be set to the - // empty string rather than unset (NULL). Handle that case. - const char* const env = getenv(name); - return (env != NULL && env[0] != '\0') ? env : NULL; -#else - return getenv(name); -#endif -} - -#ifdef _MSC_VER -# pragma warning(pop) // Restores the warning state. -#endif - -#if GTEST_OS_WINDOWS_MOBILE -// Windows CE has no C library. The abort() function is used in -// several places in Google Test. This implementation provides a reasonable -// imitation of standard behaviour. -void Abort(); -#else -inline void Abort() { abort(); } -#endif // GTEST_OS_WINDOWS_MOBILE - -} // namespace posix - -// MSVC "deprecates" snprintf and issues warnings wherever it is used. In -// order to avoid these warnings, we need to use _snprintf or _snprintf_s on -// MSVC-based platforms. We map the GTEST_SNPRINTF_ macro to the appropriate -// function in order to achieve that. We use macro definition here because -// snprintf is a variadic function. -#if _MSC_VER >= 1400 && !GTEST_OS_WINDOWS_MOBILE -// MSVC 2005 and above support variadic macros. -# define GTEST_SNPRINTF_(buffer, size, format, ...) \ - _snprintf_s(buffer, size, size, format, __VA_ARGS__) -#elif defined(_MSC_VER) -// Windows CE does not define _snprintf_s and MSVC prior to 2005 doesn't -// complain about _snprintf. -# define GTEST_SNPRINTF_ _snprintf -#else -# define GTEST_SNPRINTF_ snprintf -#endif - -// The maximum number a BiggestInt can represent. This definition -// works no matter BiggestInt is represented in one's complement or -// two's complement. -// -// We cannot rely on numeric_limits in STL, as __int64 and long long -// are not part of standard C++ and numeric_limits doesn't need to be -// defined for them. -const BiggestInt kMaxBiggestInt = - ~(static_cast(1) << (8*sizeof(BiggestInt) - 1)); - -// This template class serves as a compile-time function from size to -// type. It maps a size in bytes to a primitive type with that -// size. e.g. -// -// TypeWithSize<4>::UInt -// -// is typedef-ed to be unsigned int (unsigned integer made up of 4 -// bytes). -// -// Such functionality should belong to STL, but I cannot find it -// there. -// -// Google Test uses this class in the implementation of floating-point -// comparison. -// -// For now it only handles UInt (unsigned int) as that's all Google Test -// needs. Other types can be easily added in the future if need -// arises. -template -class TypeWithSize { - public: - // This prevents the user from using TypeWithSize with incorrect - // values of N. - typedef void UInt; -}; - -// The specialization for size 4. -template <> -class TypeWithSize<4> { - public: - // unsigned int has size 4 in both gcc and MSVC. - // - // As base/basictypes.h doesn't compile on Windows, we cannot use - // uint32, uint64, and etc here. - typedef int Int; - typedef unsigned int UInt; -}; - -// The specialization for size 8. -template <> -class TypeWithSize<8> { - public: -#if GTEST_OS_WINDOWS - typedef __int64 Int; - typedef unsigned __int64 UInt; -#else - typedef long long Int; // NOLINT - typedef unsigned long long UInt; // NOLINT -#endif // GTEST_OS_WINDOWS -}; - -// Integer types of known sizes. -typedef TypeWithSize<4>::Int Int32; -typedef TypeWithSize<4>::UInt UInt32; -typedef TypeWithSize<8>::Int Int64; -typedef TypeWithSize<8>::UInt UInt64; -typedef TypeWithSize<8>::Int TimeInMillis; // Represents time in milliseconds. - -// Utilities for command line flags and environment variables. - -// Macro for referencing flags. -#define GTEST_FLAG(name) FLAGS_gtest_##name - -// Macros for declaring flags. -#define GTEST_DECLARE_bool_(name) GTEST_API_ extern bool GTEST_FLAG(name) -#define GTEST_DECLARE_int32_(name) \ - GTEST_API_ extern ::testing::internal::Int32 GTEST_FLAG(name) -#define GTEST_DECLARE_string_(name) \ - GTEST_API_ extern ::std::string GTEST_FLAG(name) - -// Macros for defining flags. -#define GTEST_DEFINE_bool_(name, default_val, doc) \ - GTEST_API_ bool GTEST_FLAG(name) = (default_val) -#define GTEST_DEFINE_int32_(name, default_val, doc) \ - GTEST_API_ ::testing::internal::Int32 GTEST_FLAG(name) = (default_val) -#define GTEST_DEFINE_string_(name, default_val, doc) \ - GTEST_API_ ::std::string GTEST_FLAG(name) = (default_val) - -// Thread annotations -#define GTEST_EXCLUSIVE_LOCK_REQUIRED_(locks) -#define GTEST_LOCK_EXCLUDED_(locks) - -// Parses 'str' for a 32-bit signed integer. If successful, writes the result -// to *value and returns true; otherwise leaves *value unchanged and returns -// false. -// TODO(chandlerc): Find a better way to refactor flag and environment parsing -// out of both gtest-port.cc and gtest.cc to avoid exporting this utility -// function. -bool ParseInt32(const Message& src_text, const char* str, Int32* value); - -// Parses a bool/Int32/string from the environment variable -// corresponding to the given Google Test flag. -bool BoolFromGTestEnv(const char* flag, bool default_val); -GTEST_API_ Int32 Int32FromGTestEnv(const char* flag, Int32 default_val); -const char* StringFromGTestEnv(const char* flag, const char* default_val); - -} // namespace internal -} // namespace testing - -#endif // GTEST_INCLUDE_GTEST_INTERNAL_GTEST_PORT_H_ - -#if GTEST_OS_LINUX -# include -# include -# include -# include -#endif // GTEST_OS_LINUX - -#if GTEST_HAS_EXCEPTIONS -# include -#endif - -#include -#include -#include -#include -#include -#include - -// Copyright 2005, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: wan@google.com (Zhanyong Wan) -// -// The Google C++ Testing Framework (Google Test) -// -// This header file defines the Message class. -// -// IMPORTANT NOTE: Due to limitation of the C++ language, we have to -// leave some internal implementation details in this header file. -// They are clearly marked by comments like this: -// -// // INTERNAL IMPLEMENTATION - DO NOT USE IN A USER PROGRAM. -// -// Such code is NOT meant to be used by a user directly, and is subject -// to CHANGE WITHOUT NOTICE. Therefore DO NOT DEPEND ON IT in a user -// program! - -#ifndef GTEST_INCLUDE_GTEST_GTEST_MESSAGE_H_ -#define GTEST_INCLUDE_GTEST_GTEST_MESSAGE_H_ - -#include - - -// Ensures that there is at least one operator<< in the global namespace. -// See Message& operator<<(...) below for why. -void operator<<(const testing::internal::Secret&, int); - -namespace testing { - -// The Message class works like an ostream repeater. -// -// Typical usage: -// -// 1. You stream a bunch of values to a Message object. -// It will remember the text in a stringstream. -// 2. Then you stream the Message object to an ostream. -// This causes the text in the Message to be streamed -// to the ostream. -// -// For example; -// -// testing::Message foo; -// foo << 1 << " != " << 2; -// std::cout << foo; -// -// will print "1 != 2". -// -// Message is not intended to be inherited from. In particular, its -// destructor is not virtual. -// -// Note that stringstream behaves differently in gcc and in MSVC. You -// can stream a NULL char pointer to it in the former, but not in the -// latter (it causes an access violation if you do). The Message -// class hides this difference by treating a NULL char pointer as -// "(null)". -class GTEST_API_ Message { - private: - // The type of basic IO manipulators (endl, ends, and flush) for - // narrow streams. - typedef std::ostream& (*BasicNarrowIoManip)(std::ostream&); - - public: - // Constructs an empty Message. - Message(); - - // Copy constructor. - Message(const Message& msg) : ss_(new ::std::stringstream) { // NOLINT - *ss_ << msg.GetString(); - } - - // Constructs a Message from a C-string. - explicit Message(const char* str) : ss_(new ::std::stringstream) { - *ss_ << str; - } - -#if GTEST_OS_SYMBIAN - // Streams a value (either a pointer or not) to this object. - template - inline Message& operator <<(const T& value) { - StreamHelper(typename internal::is_pointer::type(), value); - return *this; - } -#else - // Streams a non-pointer value to this object. - template - inline Message& operator <<(const T& val) { - // Some libraries overload << for STL containers. These - // overloads are defined in the global namespace instead of ::std. - // - // C++'s symbol lookup rule (i.e. Koenig lookup) says that these - // overloads are visible in either the std namespace or the global - // namespace, but not other namespaces, including the testing - // namespace which Google Test's Message class is in. - // - // To allow STL containers (and other types that has a << operator - // defined in the global namespace) to be used in Google Test - // assertions, testing::Message must access the custom << operator - // from the global namespace. With this using declaration, - // overloads of << defined in the global namespace and those - // visible via Koenig lookup are both exposed in this function. - using ::operator <<; - *ss_ << val; - return *this; - } - - // Streams a pointer value to this object. - // - // This function is an overload of the previous one. When you - // stream a pointer to a Message, this definition will be used as it - // is more specialized. (The C++ Standard, section - // [temp.func.order].) If you stream a non-pointer, then the - // previous definition will be used. - // - // The reason for this overload is that streaming a NULL pointer to - // ostream is undefined behavior. Depending on the compiler, you - // may get "0", "(nil)", "(null)", or an access violation. To - // ensure consistent result across compilers, we always treat NULL - // as "(null)". - template - inline Message& operator <<(T* const& pointer) { // NOLINT - if (pointer == NULL) { - *ss_ << "(null)"; - } else { - *ss_ << pointer; - } - return *this; - } -#endif // GTEST_OS_SYMBIAN - - // Since the basic IO manipulators are overloaded for both narrow - // and wide streams, we have to provide this specialized definition - // of operator <<, even though its body is the same as the - // templatized version above. Without this definition, streaming - // endl or other basic IO manipulators to Message will confuse the - // compiler. - Message& operator <<(BasicNarrowIoManip val) { - *ss_ << val; - return *this; - } - - // Instead of 1/0, we want to see true/false for bool values. - Message& operator <<(bool b) { - return *this << (b ? "true" : "false"); - } - - // These two overloads allow streaming a wide C string to a Message - // using the UTF-8 encoding. - Message& operator <<(const wchar_t* wide_c_str); - Message& operator <<(wchar_t* wide_c_str); - -#if GTEST_HAS_STD_WSTRING - // Converts the given wide string to a narrow string using the UTF-8 - // encoding, and streams the result to this Message object. - Message& operator <<(const ::std::wstring& wstr); -#endif // GTEST_HAS_STD_WSTRING - -#if GTEST_HAS_GLOBAL_WSTRING - // Converts the given wide string to a narrow string using the UTF-8 - // encoding, and streams the result to this Message object. - Message& operator <<(const ::wstring& wstr); -#endif // GTEST_HAS_GLOBAL_WSTRING - - // Gets the text streamed to this object so far as an std::string. - // Each '\0' character in the buffer is replaced with "\\0". - // - // INTERNAL IMPLEMENTATION - DO NOT USE IN A USER PROGRAM. - std::string GetString() const; - - private: - -#if GTEST_OS_SYMBIAN - // These are needed as the Nokia Symbian Compiler cannot decide between - // const T& and const T* in a function template. The Nokia compiler _can_ - // decide between class template specializations for T and T*, so a - // tr1::type_traits-like is_pointer works, and we can overload on that. - template - inline void StreamHelper(internal::true_type /*is_pointer*/, T* pointer) { - if (pointer == NULL) { - *ss_ << "(null)"; - } else { - *ss_ << pointer; - } - } - template - inline void StreamHelper(internal::false_type /*is_pointer*/, - const T& value) { - // See the comments in Message& operator <<(const T&) above for why - // we need this using statement. - using ::operator <<; - *ss_ << value; - } -#endif // GTEST_OS_SYMBIAN - - // We'll hold the text streamed to this object here. - const internal::scoped_ptr< ::std::stringstream> ss_; - - // We declare (but don't implement) this to prevent the compiler - // from implementing the assignment operator. - void operator=(const Message&); -}; - -// Streams a Message to an ostream. -inline std::ostream& operator <<(std::ostream& os, const Message& sb) { - return os << sb.GetString(); -} - -namespace internal { - -// Converts a streamable value to an std::string. A NULL pointer is -// converted to "(null)". When the input value is a ::string, -// ::std::string, ::wstring, or ::std::wstring object, each NUL -// character in it is replaced with "\\0". -template -std::string StreamableToString(const T& streamable) { - return (Message() << streamable).GetString(); -} - -} // namespace internal -} // namespace testing - -#endif // GTEST_INCLUDE_GTEST_GTEST_MESSAGE_H_ -// Copyright 2005, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Authors: wan@google.com (Zhanyong Wan), eefacm@gmail.com (Sean Mcafee) -// -// The Google C++ Testing Framework (Google Test) -// -// This header file declares the String class and functions used internally by -// Google Test. They are subject to change without notice. They should not used -// by code external to Google Test. -// -// This header file is #included by . -// It should not be #included by other files. - -#ifndef GTEST_INCLUDE_GTEST_INTERNAL_GTEST_STRING_H_ -#define GTEST_INCLUDE_GTEST_INTERNAL_GTEST_STRING_H_ - -#ifdef __BORLANDC__ -// string.h is not guaranteed to provide strcpy on C++ Builder. -# include -#endif - -#include -#include - - -namespace testing { -namespace internal { - -// String - an abstract class holding static string utilities. -class GTEST_API_ String { - public: - // Static utility methods - - // Clones a 0-terminated C string, allocating memory using new. The - // caller is responsible for deleting the return value using - // delete[]. Returns the cloned string, or NULL if the input is - // NULL. - // - // This is different from strdup() in string.h, which allocates - // memory using malloc(). - static const char* CloneCString(const char* c_str); - -#if GTEST_OS_WINDOWS_MOBILE - // Windows CE does not have the 'ANSI' versions of Win32 APIs. To be - // able to pass strings to Win32 APIs on CE we need to convert them - // to 'Unicode', UTF-16. - - // Creates a UTF-16 wide string from the given ANSI string, allocating - // memory using new. The caller is responsible for deleting the return - // value using delete[]. Returns the wide string, or NULL if the - // input is NULL. - // - // The wide string is created using the ANSI codepage (CP_ACP) to - // match the behaviour of the ANSI versions of Win32 calls and the - // C runtime. - static LPCWSTR AnsiToUtf16(const char* c_str); - - // Creates an ANSI string from the given wide string, allocating - // memory using new. The caller is responsible for deleting the return - // value using delete[]. Returns the ANSI string, or NULL if the - // input is NULL. - // - // The returned string is created using the ANSI codepage (CP_ACP) to - // match the behaviour of the ANSI versions of Win32 calls and the - // C runtime. - static const char* Utf16ToAnsi(LPCWSTR utf16_str); -#endif - - // Compares two C strings. Returns true iff they have the same content. - // - // Unlike strcmp(), this function can handle NULL argument(s). A - // NULL C string is considered different to any non-NULL C string, - // including the empty string. - static bool CStringEquals(const char* lhs, const char* rhs); - - // Converts a wide C string to a String using the UTF-8 encoding. - // NULL will be converted to "(null)". If an error occurred during - // the conversion, "(failed to convert from wide string)" is - // returned. - static std::string ShowWideCString(const wchar_t* wide_c_str); - - // Compares two wide C strings. Returns true iff they have the same - // content. - // - // Unlike wcscmp(), this function can handle NULL argument(s). A - // NULL C string is considered different to any non-NULL C string, - // including the empty string. - static bool WideCStringEquals(const wchar_t* lhs, const wchar_t* rhs); - - // Compares two C strings, ignoring case. Returns true iff they - // have the same content. - // - // Unlike strcasecmp(), this function can handle NULL argument(s). - // A NULL C string is considered different to any non-NULL C string, - // including the empty string. - static bool CaseInsensitiveCStringEquals(const char* lhs, - const char* rhs); - - // Compares two wide C strings, ignoring case. Returns true iff they - // have the same content. - // - // Unlike wcscasecmp(), this function can handle NULL argument(s). - // A NULL C string is considered different to any non-NULL wide C string, - // including the empty string. - // NB: The implementations on different platforms slightly differ. - // On windows, this method uses _wcsicmp which compares according to LC_CTYPE - // environment variable. On GNU platform this method uses wcscasecmp - // which compares according to LC_CTYPE category of the current locale. - // On MacOS X, it uses towlower, which also uses LC_CTYPE category of the - // current locale. - static bool CaseInsensitiveWideCStringEquals(const wchar_t* lhs, - const wchar_t* rhs); - - // Returns true iff the given string ends with the given suffix, ignoring - // case. Any string is considered to end with an empty suffix. - static bool EndsWithCaseInsensitive( - const std::string& str, const std::string& suffix); - - // Formats an int value as "%02d". - static std::string FormatIntWidth2(int value); // "%02d" for width == 2 - - // Formats an int value as "%X". - static std::string FormatHexInt(int value); - - // Formats a byte as "%02X". - static std::string FormatByte(unsigned char value); - - private: - String(); // Not meant to be instantiated. -}; // class String - -// Gets the content of the stringstream's buffer as an std::string. Each '\0' -// character in the buffer is replaced with "\\0". -GTEST_API_ std::string StringStreamToString(::std::stringstream* stream); - -} // namespace internal -} // namespace testing - -#endif // GTEST_INCLUDE_GTEST_INTERNAL_GTEST_STRING_H_ -// Copyright 2008, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: keith.ray@gmail.com (Keith Ray) -// -// Google Test filepath utilities -// -// This header file declares classes and functions used internally by -// Google Test. They are subject to change without notice. -// -// This file is #included in . -// Do not include this header file separately! - -#ifndef GTEST_INCLUDE_GTEST_INTERNAL_GTEST_FILEPATH_H_ -#define GTEST_INCLUDE_GTEST_INTERNAL_GTEST_FILEPATH_H_ - - -namespace testing { -namespace internal { - -// FilePath - a class for file and directory pathname manipulation which -// handles platform-specific conventions (like the pathname separator). -// Used for helper functions for naming files in a directory for xml output. -// Except for Set methods, all methods are const or static, which provides an -// "immutable value object" -- useful for peace of mind. -// A FilePath with a value ending in a path separator ("like/this/") represents -// a directory, otherwise it is assumed to represent a file. In either case, -// it may or may not represent an actual file or directory in the file system. -// Names are NOT checked for syntax correctness -- no checking for illegal -// characters, malformed paths, etc. - -class GTEST_API_ FilePath { - public: - FilePath() : pathname_("") { } - FilePath(const FilePath& rhs) : pathname_(rhs.pathname_) { } - - explicit FilePath(const std::string& pathname) : pathname_(pathname) { - Normalize(); - } - - FilePath& operator=(const FilePath& rhs) { - Set(rhs); - return *this; - } - - void Set(const FilePath& rhs) { - pathname_ = rhs.pathname_; - } - - const std::string& string() const { return pathname_; } - const char* c_str() const { return pathname_.c_str(); } - - // Returns the current working directory, or "" if unsuccessful. - static FilePath GetCurrentDir(); - - // Given directory = "dir", base_name = "test", number = 0, - // extension = "xml", returns "dir/test.xml". If number is greater - // than zero (e.g., 12), returns "dir/test_12.xml". - // On Windows platform, uses \ as the separator rather than /. - static FilePath MakeFileName(const FilePath& directory, - const FilePath& base_name, - int number, - const char* extension); - - // Given directory = "dir", relative_path = "test.xml", - // returns "dir/test.xml". - // On Windows, uses \ as the separator rather than /. - static FilePath ConcatPaths(const FilePath& directory, - const FilePath& relative_path); - - // Returns a pathname for a file that does not currently exist. The pathname - // will be directory/base_name.extension or - // directory/base_name_.extension if directory/base_name.extension - // already exists. The number will be incremented until a pathname is found - // that does not already exist. - // Examples: 'dir/foo_test.xml' or 'dir/foo_test_1.xml'. - // There could be a race condition if two or more processes are calling this - // function at the same time -- they could both pick the same filename. - static FilePath GenerateUniqueFileName(const FilePath& directory, - const FilePath& base_name, - const char* extension); - - // Returns true iff the path is "". - bool IsEmpty() const { return pathname_.empty(); } - - // If input name has a trailing separator character, removes it and returns - // the name, otherwise return the name string unmodified. - // On Windows platform, uses \ as the separator, other platforms use /. - FilePath RemoveTrailingPathSeparator() const; - - // Returns a copy of the FilePath with the directory part removed. - // Example: FilePath("path/to/file").RemoveDirectoryName() returns - // FilePath("file"). If there is no directory part ("just_a_file"), it returns - // the FilePath unmodified. If there is no file part ("just_a_dir/") it - // returns an empty FilePath (""). - // On Windows platform, '\' is the path separator, otherwise it is '/'. - FilePath RemoveDirectoryName() const; - - // RemoveFileName returns the directory path with the filename removed. - // Example: FilePath("path/to/file").RemoveFileName() returns "path/to/". - // If the FilePath is "a_file" or "/a_file", RemoveFileName returns - // FilePath("./") or, on Windows, FilePath(".\\"). If the filepath does - // not have a file, like "just/a/dir/", it returns the FilePath unmodified. - // On Windows platform, '\' is the path separator, otherwise it is '/'. - FilePath RemoveFileName() const; - - // Returns a copy of the FilePath with the case-insensitive extension removed. - // Example: FilePath("dir/file.exe").RemoveExtension("EXE") returns - // FilePath("dir/file"). If a case-insensitive extension is not - // found, returns a copy of the original FilePath. - FilePath RemoveExtension(const char* extension) const; - - // Creates directories so that path exists. Returns true if successful or if - // the directories already exist; returns false if unable to create - // directories for any reason. Will also return false if the FilePath does - // not represent a directory (that is, it doesn't end with a path separator). - bool CreateDirectoriesRecursively() const; - - // Create the directory so that path exists. Returns true if successful or - // if the directory already exists; returns false if unable to create the - // directory for any reason, including if the parent directory does not - // exist. Not named "CreateDirectory" because that's a macro on Windows. - bool CreateFolder() const; - - // Returns true if FilePath describes something in the file-system, - // either a file, directory, or whatever, and that something exists. - bool FileOrDirectoryExists() const; - - // Returns true if pathname describes a directory in the file-system - // that exists. - bool DirectoryExists() const; - - // Returns true if FilePath ends with a path separator, which indicates that - // it is intended to represent a directory. Returns false otherwise. - // This does NOT check that a directory (or file) actually exists. - bool IsDirectory() const; - - // Returns true if pathname describes a root directory. (Windows has one - // root directory per disk drive.) - bool IsRootDirectory() const; - - // Returns true if pathname describes an absolute path. - bool IsAbsolutePath() const; - - private: - // Replaces multiple consecutive separators with a single separator. - // For example, "bar///foo" becomes "bar/foo". Does not eliminate other - // redundancies that might be in a pathname involving "." or "..". - // - // A pathname with multiple consecutive separators may occur either through - // user error or as a result of some scripts or APIs that generate a pathname - // with a trailing separator. On other platforms the same API or script - // may NOT generate a pathname with a trailing "/". Then elsewhere that - // pathname may have another "/" and pathname components added to it, - // without checking for the separator already being there. - // The script language and operating system may allow paths like "foo//bar" - // but some of the functions in FilePath will not handle that correctly. In - // particular, RemoveTrailingPathSeparator() only removes one separator, and - // it is called in CreateDirectoriesRecursively() assuming that it will change - // a pathname from directory syntax (trailing separator) to filename syntax. - // - // On Windows this method also replaces the alternate path separator '/' with - // the primary path separator '\\', so that for example "bar\\/\\foo" becomes - // "bar\\foo". - - void Normalize(); - - // Returns a pointer to the last occurence of a valid path separator in - // the FilePath. On Windows, for example, both '/' and '\' are valid path - // separators. Returns NULL if no path separator was found. - const char* FindLastPathSeparator() const; - - std::string pathname_; -}; // class FilePath - -} // namespace internal -} // namespace testing - -#endif // GTEST_INCLUDE_GTEST_INTERNAL_GTEST_FILEPATH_H_ -// This file was GENERATED by command: -// pump.py gtest-type-util.h.pump -// DO NOT EDIT BY HAND!!! - -// Copyright 2008 Google Inc. -// All Rights Reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: wan@google.com (Zhanyong Wan) - -// Type utilities needed for implementing typed and type-parameterized -// tests. This file is generated by a SCRIPT. DO NOT EDIT BY HAND! -// -// Currently we support at most 50 types in a list, and at most 50 -// type-parameterized tests in one type-parameterized test case. -// Please contact googletestframework@googlegroups.com if you need -// more. - -#ifndef GTEST_INCLUDE_GTEST_INTERNAL_GTEST_TYPE_UTIL_H_ -#define GTEST_INCLUDE_GTEST_INTERNAL_GTEST_TYPE_UTIL_H_ - - -// #ifdef __GNUC__ is too general here. It is possible to use gcc without using -// libstdc++ (which is where cxxabi.h comes from). -# if GTEST_HAS_CXXABI_H_ -# include -# elif defined(__HP_aCC) -# include -# endif // GTEST_HASH_CXXABI_H_ - -namespace testing { -namespace internal { - -// GetTypeName() returns a human-readable name of type T. -// NB: This function is also used in Google Mock, so don't move it inside of -// the typed-test-only section below. -template -std::string GetTypeName() { -# if GTEST_HAS_RTTI - - const char* const name = typeid(T).name(); -# if GTEST_HAS_CXXABI_H_ || defined(__HP_aCC) - int status = 0; - // gcc's implementation of typeid(T).name() mangles the type name, - // so we have to demangle it. -# if GTEST_HAS_CXXABI_H_ - using abi::__cxa_demangle; -# endif // GTEST_HAS_CXXABI_H_ - char* const readable_name = __cxa_demangle(name, 0, 0, &status); - const std::string name_str(status == 0 ? readable_name : name); - free(readable_name); - return name_str; -# else - return name; -# endif // GTEST_HAS_CXXABI_H_ || __HP_aCC - -# else - - return ""; - -# endif // GTEST_HAS_RTTI -} - -#if GTEST_HAS_TYPED_TEST || GTEST_HAS_TYPED_TEST_P - -// AssertyTypeEq::type is defined iff T1 and T2 are the same -// type. This can be used as a compile-time assertion to ensure that -// two types are equal. - -template -struct AssertTypeEq; - -template -struct AssertTypeEq { - typedef bool type; -}; - -// A unique type used as the default value for the arguments of class -// template Types. This allows us to simulate variadic templates -// (e.g. Types, Type, and etc), which C++ doesn't -// support directly. -struct None {}; - -// The following family of struct and struct templates are used to -// represent type lists. In particular, TypesN -// represents a type list with N types (T1, T2, ..., and TN) in it. -// Except for Types0, every struct in the family has two member types: -// Head for the first type in the list, and Tail for the rest of the -// list. - -// The empty type list. -struct Types0 {}; - -// Type lists of length 1, 2, 3, and so on. - -template -struct Types1 { - typedef T1 Head; - typedef Types0 Tail; -}; -template -struct Types2 { - typedef T1 Head; - typedef Types1 Tail; -}; - -template -struct Types3 { - typedef T1 Head; - typedef Types2 Tail; -}; - -template -struct Types4 { - typedef T1 Head; - typedef Types3 Tail; -}; - -template -struct Types5 { - typedef T1 Head; - typedef Types4 Tail; -}; - -template -struct Types6 { - typedef T1 Head; - typedef Types5 Tail; -}; - -template -struct Types7 { - typedef T1 Head; - typedef Types6 Tail; -}; - -template -struct Types8 { - typedef T1 Head; - typedef Types7 Tail; -}; - -template -struct Types9 { - typedef T1 Head; - typedef Types8 Tail; -}; - -template -struct Types10 { - typedef T1 Head; - typedef Types9 Tail; -}; - -template -struct Types11 { - typedef T1 Head; - typedef Types10 Tail; -}; - -template -struct Types12 { - typedef T1 Head; - typedef Types11 Tail; -}; - -template -struct Types13 { - typedef T1 Head; - typedef Types12 Tail; -}; - -template -struct Types14 { - typedef T1 Head; - typedef Types13 Tail; -}; - -template -struct Types15 { - typedef T1 Head; - typedef Types14 Tail; -}; - -template -struct Types16 { - typedef T1 Head; - typedef Types15 Tail; -}; - -template -struct Types17 { - typedef T1 Head; - typedef Types16 Tail; -}; - -template -struct Types18 { - typedef T1 Head; - typedef Types17 Tail; -}; - -template -struct Types19 { - typedef T1 Head; - typedef Types18 Tail; -}; - -template -struct Types20 { - typedef T1 Head; - typedef Types19 Tail; -}; - -template -struct Types21 { - typedef T1 Head; - typedef Types20 Tail; -}; - -template -struct Types22 { - typedef T1 Head; - typedef Types21 Tail; -}; - -template -struct Types23 { - typedef T1 Head; - typedef Types22 Tail; -}; - -template -struct Types24 { - typedef T1 Head; - typedef Types23 Tail; -}; - -template -struct Types25 { - typedef T1 Head; - typedef Types24 Tail; -}; - -template -struct Types26 { - typedef T1 Head; - typedef Types25 Tail; -}; - -template -struct Types27 { - typedef T1 Head; - typedef Types26 Tail; -}; - -template -struct Types28 { - typedef T1 Head; - typedef Types27 Tail; -}; - -template -struct Types29 { - typedef T1 Head; - typedef Types28 Tail; -}; - -template -struct Types30 { - typedef T1 Head; - typedef Types29 Tail; -}; - -template -struct Types31 { - typedef T1 Head; - typedef Types30 Tail; -}; - -template -struct Types32 { - typedef T1 Head; - typedef Types31 Tail; -}; - -template -struct Types33 { - typedef T1 Head; - typedef Types32 Tail; -}; - -template -struct Types34 { - typedef T1 Head; - typedef Types33 Tail; -}; - -template -struct Types35 { - typedef T1 Head; - typedef Types34 Tail; -}; - -template -struct Types36 { - typedef T1 Head; - typedef Types35 Tail; -}; - -template -struct Types37 { - typedef T1 Head; - typedef Types36 Tail; -}; - -template -struct Types38 { - typedef T1 Head; - typedef Types37 Tail; -}; - -template -struct Types39 { - typedef T1 Head; - typedef Types38 Tail; -}; - -template -struct Types40 { - typedef T1 Head; - typedef Types39 Tail; -}; - -template -struct Types41 { - typedef T1 Head; - typedef Types40 Tail; -}; - -template -struct Types42 { - typedef T1 Head; - typedef Types41 Tail; -}; - -template -struct Types43 { - typedef T1 Head; - typedef Types42 Tail; -}; - -template -struct Types44 { - typedef T1 Head; - typedef Types43 Tail; -}; - -template -struct Types45 { - typedef T1 Head; - typedef Types44 Tail; -}; - -template -struct Types46 { - typedef T1 Head; - typedef Types45 Tail; -}; - -template -struct Types47 { - typedef T1 Head; - typedef Types46 Tail; -}; - -template -struct Types48 { - typedef T1 Head; - typedef Types47 Tail; -}; - -template -struct Types49 { - typedef T1 Head; - typedef Types48 Tail; -}; - -template -struct Types50 { - typedef T1 Head; - typedef Types49 Tail; -}; - - -} // namespace internal - -// We don't want to require the users to write TypesN<...> directly, -// as that would require them to count the length. Types<...> is much -// easier to write, but generates horrible messages when there is a -// compiler error, as gcc insists on printing out each template -// argument, even if it has the default value (this means Types -// will appear as Types in the compiler -// errors). -// -// Our solution is to combine the best part of the two approaches: a -// user would write Types, and Google Test will translate -// that to TypesN internally to make error messages -// readable. The translation is done by the 'type' member of the -// Types template. -template -struct Types { - typedef internal::Types50 type; -}; - -template <> -struct Types { - typedef internal::Types0 type; -}; -template -struct Types { - typedef internal::Types1 type; -}; -template -struct Types { - typedef internal::Types2 type; -}; -template -struct Types { - typedef internal::Types3 type; -}; -template -struct Types { - typedef internal::Types4 type; -}; -template -struct Types { - typedef internal::Types5 type; -}; -template -struct Types { - typedef internal::Types6 type; -}; -template -struct Types { - typedef internal::Types7 type; -}; -template -struct Types { - typedef internal::Types8 type; -}; -template -struct Types { - typedef internal::Types9 type; -}; -template -struct Types { - typedef internal::Types10 type; -}; -template -struct Types { - typedef internal::Types11 type; -}; -template -struct Types { - typedef internal::Types12 type; -}; -template -struct Types { - typedef internal::Types13 type; -}; -template -struct Types { - typedef internal::Types14 type; -}; -template -struct Types { - typedef internal::Types15 type; -}; -template -struct Types { - typedef internal::Types16 type; -}; -template -struct Types { - typedef internal::Types17 type; -}; -template -struct Types { - typedef internal::Types18 type; -}; -template -struct Types { - typedef internal::Types19 type; -}; -template -struct Types { - typedef internal::Types20 type; -}; -template -struct Types { - typedef internal::Types21 type; -}; -template -struct Types { - typedef internal::Types22 type; -}; -template -struct Types { - typedef internal::Types23 type; -}; -template -struct Types { - typedef internal::Types24 type; -}; -template -struct Types { - typedef internal::Types25 type; -}; -template -struct Types { - typedef internal::Types26 type; -}; -template -struct Types { - typedef internal::Types27 type; -}; -template -struct Types { - typedef internal::Types28 type; -}; -template -struct Types { - typedef internal::Types29 type; -}; -template -struct Types { - typedef internal::Types30 type; -}; -template -struct Types { - typedef internal::Types31 type; -}; -template -struct Types { - typedef internal::Types32 type; -}; -template -struct Types { - typedef internal::Types33 type; -}; -template -struct Types { - typedef internal::Types34 type; -}; -template -struct Types { - typedef internal::Types35 type; -}; -template -struct Types { - typedef internal::Types36 type; -}; -template -struct Types { - typedef internal::Types37 type; -}; -template -struct Types { - typedef internal::Types38 type; -}; -template -struct Types { - typedef internal::Types39 type; -}; -template -struct Types { - typedef internal::Types40 type; -}; -template -struct Types { - typedef internal::Types41 type; -}; -template -struct Types { - typedef internal::Types42 type; -}; -template -struct Types { - typedef internal::Types43 type; -}; -template -struct Types { - typedef internal::Types44 type; -}; -template -struct Types { - typedef internal::Types45 type; -}; -template -struct Types { - typedef internal::Types46 type; -}; -template -struct Types { - typedef internal::Types47 type; -}; -template -struct Types { - typedef internal::Types48 type; -}; -template -struct Types { - typedef internal::Types49 type; -}; - -namespace internal { - -# define GTEST_TEMPLATE_ template class - -// The template "selector" struct TemplateSel is used to -// represent Tmpl, which must be a class template with one type -// parameter, as a type. TemplateSel::Bind::type is defined -// as the type Tmpl. This allows us to actually instantiate the -// template "selected" by TemplateSel. -// -// This trick is necessary for simulating typedef for class templates, -// which C++ doesn't support directly. -template -struct TemplateSel { - template - struct Bind { - typedef Tmpl type; - }; -}; - -# define GTEST_BIND_(TmplSel, T) \ - TmplSel::template Bind::type - -// A unique struct template used as the default value for the -// arguments of class template Templates. This allows us to simulate -// variadic templates (e.g. Templates, Templates, -// and etc), which C++ doesn't support directly. -template -struct NoneT {}; - -// The following family of struct and struct templates are used to -// represent template lists. In particular, TemplatesN represents a list of N templates (T1, T2, ..., and TN). Except -// for Templates0, every struct in the family has two member types: -// Head for the selector of the first template in the list, and Tail -// for the rest of the list. - -// The empty template list. -struct Templates0 {}; - -// Template lists of length 1, 2, 3, and so on. - -template -struct Templates1 { - typedef TemplateSel Head; - typedef Templates0 Tail; -}; -template -struct Templates2 { - typedef TemplateSel Head; - typedef Templates1 Tail; -}; - -template -struct Templates3 { - typedef TemplateSel Head; - typedef Templates2 Tail; -}; - -template -struct Templates4 { - typedef TemplateSel Head; - typedef Templates3 Tail; -}; - -template -struct Templates5 { - typedef TemplateSel Head; - typedef Templates4 Tail; -}; - -template -struct Templates6 { - typedef TemplateSel Head; - typedef Templates5 Tail; -}; - -template -struct Templates7 { - typedef TemplateSel Head; - typedef Templates6 Tail; -}; - -template -struct Templates8 { - typedef TemplateSel Head; - typedef Templates7 Tail; -}; - -template -struct Templates9 { - typedef TemplateSel Head; - typedef Templates8 Tail; -}; - -template -struct Templates10 { - typedef TemplateSel Head; - typedef Templates9 Tail; -}; - -template -struct Templates11 { - typedef TemplateSel Head; - typedef Templates10 Tail; -}; - -template -struct Templates12 { - typedef TemplateSel Head; - typedef Templates11 Tail; -}; - -template -struct Templates13 { - typedef TemplateSel Head; - typedef Templates12 Tail; -}; - -template -struct Templates14 { - typedef TemplateSel Head; - typedef Templates13 Tail; -}; - -template -struct Templates15 { - typedef TemplateSel Head; - typedef Templates14 Tail; -}; - -template -struct Templates16 { - typedef TemplateSel Head; - typedef Templates15 Tail; -}; - -template -struct Templates17 { - typedef TemplateSel Head; - typedef Templates16 Tail; -}; - -template -struct Templates18 { - typedef TemplateSel Head; - typedef Templates17 Tail; -}; - -template -struct Templates19 { - typedef TemplateSel Head; - typedef Templates18 Tail; -}; - -template -struct Templates20 { - typedef TemplateSel Head; - typedef Templates19 Tail; -}; - -template -struct Templates21 { - typedef TemplateSel Head; - typedef Templates20 Tail; -}; - -template -struct Templates22 { - typedef TemplateSel Head; - typedef Templates21 Tail; -}; - -template -struct Templates23 { - typedef TemplateSel Head; - typedef Templates22 Tail; -}; - -template -struct Templates24 { - typedef TemplateSel Head; - typedef Templates23 Tail; -}; - -template -struct Templates25 { - typedef TemplateSel Head; - typedef Templates24 Tail; -}; - -template -struct Templates26 { - typedef TemplateSel Head; - typedef Templates25 Tail; -}; - -template -struct Templates27 { - typedef TemplateSel Head; - typedef Templates26 Tail; -}; - -template -struct Templates28 { - typedef TemplateSel Head; - typedef Templates27 Tail; -}; - -template -struct Templates29 { - typedef TemplateSel Head; - typedef Templates28 Tail; -}; - -template -struct Templates30 { - typedef TemplateSel Head; - typedef Templates29 Tail; -}; - -template -struct Templates31 { - typedef TemplateSel Head; - typedef Templates30 Tail; -}; - -template -struct Templates32 { - typedef TemplateSel Head; - typedef Templates31 Tail; -}; - -template -struct Templates33 { - typedef TemplateSel Head; - typedef Templates32 Tail; -}; - -template -struct Templates34 { - typedef TemplateSel Head; - typedef Templates33 Tail; -}; - -template -struct Templates35 { - typedef TemplateSel Head; - typedef Templates34 Tail; -}; - -template -struct Templates36 { - typedef TemplateSel Head; - typedef Templates35 Tail; -}; - -template -struct Templates37 { - typedef TemplateSel Head; - typedef Templates36 Tail; -}; - -template -struct Templates38 { - typedef TemplateSel Head; - typedef Templates37 Tail; -}; - -template -struct Templates39 { - typedef TemplateSel Head; - typedef Templates38 Tail; -}; - -template -struct Templates40 { - typedef TemplateSel Head; - typedef Templates39 Tail; -}; - -template -struct Templates41 { - typedef TemplateSel Head; - typedef Templates40 Tail; -}; - -template -struct Templates42 { - typedef TemplateSel Head; - typedef Templates41 Tail; -}; - -template -struct Templates43 { - typedef TemplateSel Head; - typedef Templates42 Tail; -}; - -template -struct Templates44 { - typedef TemplateSel Head; - typedef Templates43 Tail; -}; - -template -struct Templates45 { - typedef TemplateSel Head; - typedef Templates44 Tail; -}; - -template -struct Templates46 { - typedef TemplateSel Head; - typedef Templates45 Tail; -}; - -template -struct Templates47 { - typedef TemplateSel Head; - typedef Templates46 Tail; -}; - -template -struct Templates48 { - typedef TemplateSel Head; - typedef Templates47 Tail; -}; - -template -struct Templates49 { - typedef TemplateSel Head; - typedef Templates48 Tail; -}; - -template -struct Templates50 { - typedef TemplateSel Head; - typedef Templates49 Tail; -}; - - -// We don't want to require the users to write TemplatesN<...> directly, -// as that would require them to count the length. Templates<...> is much -// easier to write, but generates horrible messages when there is a -// compiler error, as gcc insists on printing out each template -// argument, even if it has the default value (this means Templates -// will appear as Templates in the compiler -// errors). -// -// Our solution is to combine the best part of the two approaches: a -// user would write Templates, and Google Test will translate -// that to TemplatesN internally to make error messages -// readable. The translation is done by the 'type' member of the -// Templates template. -template -struct Templates { - typedef Templates50 type; -}; - -template <> -struct Templates { - typedef Templates0 type; -}; -template -struct Templates { - typedef Templates1 type; -}; -template -struct Templates { - typedef Templates2 type; -}; -template -struct Templates { - typedef Templates3 type; -}; -template -struct Templates { - typedef Templates4 type; -}; -template -struct Templates { - typedef Templates5 type; -}; -template -struct Templates { - typedef Templates6 type; -}; -template -struct Templates { - typedef Templates7 type; -}; -template -struct Templates { - typedef Templates8 type; -}; -template -struct Templates { - typedef Templates9 type; -}; -template -struct Templates { - typedef Templates10 type; -}; -template -struct Templates { - typedef Templates11 type; -}; -template -struct Templates { - typedef Templates12 type; -}; -template -struct Templates { - typedef Templates13 type; -}; -template -struct Templates { - typedef Templates14 type; -}; -template -struct Templates { - typedef Templates15 type; -}; -template -struct Templates { - typedef Templates16 type; -}; -template -struct Templates { - typedef Templates17 type; -}; -template -struct Templates { - typedef Templates18 type; -}; -template -struct Templates { - typedef Templates19 type; -}; -template -struct Templates { - typedef Templates20 type; -}; -template -struct Templates { - typedef Templates21 type; -}; -template -struct Templates { - typedef Templates22 type; -}; -template -struct Templates { - typedef Templates23 type; -}; -template -struct Templates { - typedef Templates24 type; -}; -template -struct Templates { - typedef Templates25 type; -}; -template -struct Templates { - typedef Templates26 type; -}; -template -struct Templates { - typedef Templates27 type; -}; -template -struct Templates { - typedef Templates28 type; -}; -template -struct Templates { - typedef Templates29 type; -}; -template -struct Templates { - typedef Templates30 type; -}; -template -struct Templates { - typedef Templates31 type; -}; -template -struct Templates { - typedef Templates32 type; -}; -template -struct Templates { - typedef Templates33 type; -}; -template -struct Templates { - typedef Templates34 type; -}; -template -struct Templates { - typedef Templates35 type; -}; -template -struct Templates { - typedef Templates36 type; -}; -template -struct Templates { - typedef Templates37 type; -}; -template -struct Templates { - typedef Templates38 type; -}; -template -struct Templates { - typedef Templates39 type; -}; -template -struct Templates { - typedef Templates40 type; -}; -template -struct Templates { - typedef Templates41 type; -}; -template -struct Templates { - typedef Templates42 type; -}; -template -struct Templates { - typedef Templates43 type; -}; -template -struct Templates { - typedef Templates44 type; -}; -template -struct Templates { - typedef Templates45 type; -}; -template -struct Templates { - typedef Templates46 type; -}; -template -struct Templates { - typedef Templates47 type; -}; -template -struct Templates { - typedef Templates48 type; -}; -template -struct Templates { - typedef Templates49 type; -}; - -// The TypeList template makes it possible to use either a single type -// or a Types<...> list in TYPED_TEST_CASE() and -// INSTANTIATE_TYPED_TEST_CASE_P(). - -template -struct TypeList { - typedef Types1 type; -}; - -template -struct TypeList > { - typedef typename Types::type type; -}; - -#endif // GTEST_HAS_TYPED_TEST || GTEST_HAS_TYPED_TEST_P - -} // namespace internal -} // namespace testing - -#endif // GTEST_INCLUDE_GTEST_INTERNAL_GTEST_TYPE_UTIL_H_ - -// Due to C++ preprocessor weirdness, we need double indirection to -// concatenate two tokens when one of them is __LINE__. Writing -// -// foo ## __LINE__ -// -// will result in the token foo__LINE__, instead of foo followed by -// the current line number. For more details, see -// http://www.parashift.com/c++-faq-lite/misc-technical-issues.html#faq-39.6 -#define GTEST_CONCAT_TOKEN_(foo, bar) GTEST_CONCAT_TOKEN_IMPL_(foo, bar) -#define GTEST_CONCAT_TOKEN_IMPL_(foo, bar) foo ## bar - -class ProtocolMessage; -namespace proto2 { class Message; } - -namespace testing { - -// Forward declarations. - -class AssertionResult; // Result of an assertion. -class Message; // Represents a failure message. -class Test; // Represents a test. -class TestInfo; // Information about a test. -class TestPartResult; // Result of a test part. -class UnitTest; // A collection of test cases. - -template -::std::string PrintToString(const T& value); - -namespace internal { - -struct TraceInfo; // Information about a trace point. -class ScopedTrace; // Implements scoped trace. -class TestInfoImpl; // Opaque implementation of TestInfo -class UnitTestImpl; // Opaque implementation of UnitTest - -// How many times InitGoogleTest() has been called. -GTEST_API_ extern int g_init_gtest_count; - -// The text used in failure messages to indicate the start of the -// stack trace. -GTEST_API_ extern const char kStackTraceMarker[]; - -// Two overloaded helpers for checking at compile time whether an -// expression is a null pointer literal (i.e. NULL or any 0-valued -// compile-time integral constant). Their return values have -// different sizes, so we can use sizeof() to test which version is -// picked by the compiler. These helpers have no implementations, as -// we only need their signatures. -// -// Given IsNullLiteralHelper(x), the compiler will pick the first -// version if x can be implicitly converted to Secret*, and pick the -// second version otherwise. Since Secret is a secret and incomplete -// type, the only expression a user can write that has type Secret* is -// a null pointer literal. Therefore, we know that x is a null -// pointer literal if and only if the first version is picked by the -// compiler. -char IsNullLiteralHelper(Secret* p); -char (&IsNullLiteralHelper(...))[2]; // NOLINT - -// A compile-time bool constant that is true if and only if x is a -// null pointer literal (i.e. NULL or any 0-valued compile-time -// integral constant). -#ifdef GTEST_ELLIPSIS_NEEDS_POD_ -// We lose support for NULL detection where the compiler doesn't like -// passing non-POD classes through ellipsis (...). -# define GTEST_IS_NULL_LITERAL_(x) false -#else -# define GTEST_IS_NULL_LITERAL_(x) \ - (sizeof(::testing::internal::IsNullLiteralHelper(x)) == 1) -#endif // GTEST_ELLIPSIS_NEEDS_POD_ - -// Appends the user-supplied message to the Google-Test-generated message. -GTEST_API_ std::string AppendUserMessage( - const std::string& gtest_msg, const Message& user_msg); - -#if GTEST_HAS_EXCEPTIONS - -// This exception is thrown by (and only by) a failed Google Test -// assertion when GTEST_FLAG(throw_on_failure) is true (if exceptions -// are enabled). We derive it from std::runtime_error, which is for -// errors presumably detectable only at run time. Since -// std::runtime_error inherits from std::exception, many testing -// frameworks know how to extract and print the message inside it. -class GTEST_API_ GoogleTestFailureException : public ::std::runtime_error { - public: - explicit GoogleTestFailureException(const TestPartResult& failure); -}; - -#endif // GTEST_HAS_EXCEPTIONS - -// A helper class for creating scoped traces in user programs. -class GTEST_API_ ScopedTrace { - public: - // The c'tor pushes the given source file location and message onto - // a trace stack maintained by Google Test. - ScopedTrace(const char* file, int line, const Message& message); - - // The d'tor pops the info pushed by the c'tor. - // - // Note that the d'tor is not virtual in order to be efficient. - // Don't inherit from ScopedTrace! - ~ScopedTrace(); - - private: - GTEST_DISALLOW_COPY_AND_ASSIGN_(ScopedTrace); -} GTEST_ATTRIBUTE_UNUSED_; // A ScopedTrace object does its job in its - // c'tor and d'tor. Therefore it doesn't - // need to be used otherwise. - -// Constructs and returns the message for an equality assertion -// (e.g. ASSERT_EQ, EXPECT_STREQ, etc) failure. -// -// The first four parameters are the expressions used in the assertion -// and their values, as strings. For example, for ASSERT_EQ(foo, bar) -// where foo is 5 and bar is 6, we have: -// -// expected_expression: "foo" -// actual_expression: "bar" -// expected_value: "5" -// actual_value: "6" -// -// The ignoring_case parameter is true iff the assertion is a -// *_STRCASEEQ*. When it's true, the string " (ignoring case)" will -// be inserted into the message. -GTEST_API_ AssertionResult EqFailure(const char* expected_expression, - const char* actual_expression, - const std::string& expected_value, - const std::string& actual_value, - bool ignoring_case); - -// Constructs a failure message for Boolean assertions such as EXPECT_TRUE. -GTEST_API_ std::string GetBoolAssertionFailureMessage( - const AssertionResult& assertion_result, - const char* expression_text, - const char* actual_predicate_value, - const char* expected_predicate_value); - -// This template class represents an IEEE floating-point number -// (either single-precision or double-precision, depending on the -// template parameters). -// -// The purpose of this class is to do more sophisticated number -// comparison. (Due to round-off error, etc, it's very unlikely that -// two floating-points will be equal exactly. Hence a naive -// comparison by the == operation often doesn't work.) -// -// Format of IEEE floating-point: -// -// The most-significant bit being the leftmost, an IEEE -// floating-point looks like -// -// sign_bit exponent_bits fraction_bits -// -// Here, sign_bit is a single bit that designates the sign of the -// number. -// -// For float, there are 8 exponent bits and 23 fraction bits. -// -// For double, there are 11 exponent bits and 52 fraction bits. -// -// More details can be found at -// http://en.wikipedia.org/wiki/IEEE_floating-point_standard. -// -// Template parameter: -// -// RawType: the raw floating-point type (either float or double) -template -class FloatingPoint { - public: - // Defines the unsigned integer type that has the same size as the - // floating point number. - typedef typename TypeWithSize::UInt Bits; - - // Constants. - - // # of bits in a number. - static const size_t kBitCount = 8*sizeof(RawType); - - // # of fraction bits in a number. - static const size_t kFractionBitCount = - std::numeric_limits::digits - 1; - - // # of exponent bits in a number. - static const size_t kExponentBitCount = kBitCount - 1 - kFractionBitCount; - - // The mask for the sign bit. - static const Bits kSignBitMask = static_cast(1) << (kBitCount - 1); - - // The mask for the fraction bits. - static const Bits kFractionBitMask = - ~static_cast(0) >> (kExponentBitCount + 1); - - // The mask for the exponent bits. - static const Bits kExponentBitMask = ~(kSignBitMask | kFractionBitMask); - - // How many ULP's (Units in the Last Place) we want to tolerate when - // comparing two numbers. The larger the value, the more error we - // allow. A 0 value means that two numbers must be exactly the same - // to be considered equal. - // - // The maximum error of a single floating-point operation is 0.5 - // units in the last place. On Intel CPU's, all floating-point - // calculations are done with 80-bit precision, while double has 64 - // bits. Therefore, 4 should be enough for ordinary use. - // - // See the following article for more details on ULP: - // http://randomascii.wordpress.com/2012/02/25/comparing-floating-point-numbers-2012-edition/ - static const size_t kMaxUlps = 4; - - // Constructs a FloatingPoint from a raw floating-point number. - // - // On an Intel CPU, passing a non-normalized NAN (Not a Number) - // around may change its bits, although the new value is guaranteed - // to be also a NAN. Therefore, don't expect this constructor to - // preserve the bits in x when x is a NAN. - explicit FloatingPoint(const RawType& x) { u_.value_ = x; } - - // Static methods - - // Reinterprets a bit pattern as a floating-point number. - // - // This function is needed to test the AlmostEquals() method. - static RawType ReinterpretBits(const Bits bits) { - FloatingPoint fp(0); - fp.u_.bits_ = bits; - return fp.u_.value_; - } - - // Returns the floating-point number that represent positive infinity. - static RawType Infinity() { - return ReinterpretBits(kExponentBitMask); - } - - // Returns the maximum representable finite floating-point number. - static RawType Max(); - - // Non-static methods - - // Returns the bits that represents this number. - const Bits &bits() const { return u_.bits_; } - - // Returns the exponent bits of this number. - Bits exponent_bits() const { return kExponentBitMask & u_.bits_; } - - // Returns the fraction bits of this number. - Bits fraction_bits() const { return kFractionBitMask & u_.bits_; } - - // Returns the sign bit of this number. - Bits sign_bit() const { return kSignBitMask & u_.bits_; } - - // Returns true iff this is NAN (not a number). - bool is_nan() const { - // It's a NAN if the exponent bits are all ones and the fraction - // bits are not entirely zeros. - return (exponent_bits() == kExponentBitMask) && (fraction_bits() != 0); - } - - // Returns true iff this number is at most kMaxUlps ULP's away from - // rhs. In particular, this function: - // - // - returns false if either number is (or both are) NAN. - // - treats really large numbers as almost equal to infinity. - // - thinks +0.0 and -0.0 are 0 DLP's apart. - bool AlmostEquals(const FloatingPoint& rhs) const { - // The IEEE standard says that any comparison operation involving - // a NAN must return false. - if (is_nan() || rhs.is_nan()) return false; - - return DistanceBetweenSignAndMagnitudeNumbers(u_.bits_, rhs.u_.bits_) - <= kMaxUlps; - } - - private: - // The data type used to store the actual floating-point number. - union FloatingPointUnion { - RawType value_; // The raw floating-point number. - Bits bits_; // The bits that represent the number. - }; - - // Converts an integer from the sign-and-magnitude representation to - // the biased representation. More precisely, let N be 2 to the - // power of (kBitCount - 1), an integer x is represented by the - // unsigned number x + N. - // - // For instance, - // - // -N + 1 (the most negative number representable using - // sign-and-magnitude) is represented by 1; - // 0 is represented by N; and - // N - 1 (the biggest number representable using - // sign-and-magnitude) is represented by 2N - 1. - // - // Read http://en.wikipedia.org/wiki/Signed_number_representations - // for more details on signed number representations. - static Bits SignAndMagnitudeToBiased(const Bits &sam) { - if (kSignBitMask & sam) { - // sam represents a negative number. - return ~sam + 1; - } else { - // sam represents a positive number. - return kSignBitMask | sam; - } - } - - // Given two numbers in the sign-and-magnitude representation, - // returns the distance between them as an unsigned number. - static Bits DistanceBetweenSignAndMagnitudeNumbers(const Bits &sam1, - const Bits &sam2) { - const Bits biased1 = SignAndMagnitudeToBiased(sam1); - const Bits biased2 = SignAndMagnitudeToBiased(sam2); - return (biased1 >= biased2) ? (biased1 - biased2) : (biased2 - biased1); - } - - FloatingPointUnion u_; -}; - -// We cannot use std::numeric_limits::max() as it clashes with the max() -// macro defined by . -template <> -inline float FloatingPoint::Max() { return FLT_MAX; } -template <> -inline double FloatingPoint::Max() { return DBL_MAX; } - -// Typedefs the instances of the FloatingPoint template class that we -// care to use. -typedef FloatingPoint Float; -typedef FloatingPoint Double; - -// In order to catch the mistake of putting tests that use different -// test fixture classes in the same test case, we need to assign -// unique IDs to fixture classes and compare them. The TypeId type is -// used to hold such IDs. The user should treat TypeId as an opaque -// type: the only operation allowed on TypeId values is to compare -// them for equality using the == operator. -typedef const void* TypeId; - -template -class TypeIdHelper { - public: - // dummy_ must not have a const type. Otherwise an overly eager - // compiler (e.g. MSVC 7.1 & 8.0) may try to merge - // TypeIdHelper::dummy_ for different Ts as an "optimization". - static bool dummy_; -}; - -template -bool TypeIdHelper::dummy_ = false; - -// GetTypeId() returns the ID of type T. Different values will be -// returned for different types. Calling the function twice with the -// same type argument is guaranteed to return the same ID. -template -TypeId GetTypeId() { - // The compiler is required to allocate a different - // TypeIdHelper::dummy_ variable for each T used to instantiate - // the template. Therefore, the address of dummy_ is guaranteed to - // be unique. - return &(TypeIdHelper::dummy_); -} - -// Returns the type ID of ::testing::Test. Always call this instead -// of GetTypeId< ::testing::Test>() to get the type ID of -// ::testing::Test, as the latter may give the wrong result due to a -// suspected linker bug when compiling Google Test as a Mac OS X -// framework. -GTEST_API_ TypeId GetTestTypeId(); - -// Defines the abstract factory interface that creates instances -// of a Test object. -class TestFactoryBase { - public: - virtual ~TestFactoryBase() {} - - // Creates a test instance to run. The instance is both created and destroyed - // within TestInfoImpl::Run() - virtual Test* CreateTest() = 0; - - protected: - TestFactoryBase() {} - - private: - GTEST_DISALLOW_COPY_AND_ASSIGN_(TestFactoryBase); -}; - -// This class provides implementation of TeastFactoryBase interface. -// It is used in TEST and TEST_F macros. -template -class TestFactoryImpl : public TestFactoryBase { - public: - virtual Test* CreateTest() { return new TestClass; } -}; - -#if GTEST_OS_WINDOWS - -// Predicate-formatters for implementing the HRESULT checking macros -// {ASSERT|EXPECT}_HRESULT_{SUCCEEDED|FAILED} -// We pass a long instead of HRESULT to avoid causing an -// include dependency for the HRESULT type. -GTEST_API_ AssertionResult IsHRESULTSuccess(const char* expr, - long hr); // NOLINT -GTEST_API_ AssertionResult IsHRESULTFailure(const char* expr, - long hr); // NOLINT - -#endif // GTEST_OS_WINDOWS - -// Types of SetUpTestCase() and TearDownTestCase() functions. -typedef void (*SetUpTestCaseFunc)(); -typedef void (*TearDownTestCaseFunc)(); - -// Creates a new TestInfo object and registers it with Google Test; -// returns the created object. -// -// Arguments: -// -// test_case_name: name of the test case -// name: name of the test -// type_param the name of the test's type parameter, or NULL if -// this is not a typed or a type-parameterized test. -// value_param text representation of the test's value parameter, -// or NULL if this is not a type-parameterized test. -// fixture_class_id: ID of the test fixture class -// set_up_tc: pointer to the function that sets up the test case -// tear_down_tc: pointer to the function that tears down the test case -// factory: pointer to the factory that creates a test object. -// The newly created TestInfo instance will assume -// ownership of the factory object. -GTEST_API_ TestInfo* MakeAndRegisterTestInfo( - const char* test_case_name, - const char* name, - const char* type_param, - const char* value_param, - TypeId fixture_class_id, - SetUpTestCaseFunc set_up_tc, - TearDownTestCaseFunc tear_down_tc, - TestFactoryBase* factory); - -// If *pstr starts with the given prefix, modifies *pstr to be right -// past the prefix and returns true; otherwise leaves *pstr unchanged -// and returns false. None of pstr, *pstr, and prefix can be NULL. -GTEST_API_ bool SkipPrefix(const char* prefix, const char** pstr); - -#if GTEST_HAS_TYPED_TEST || GTEST_HAS_TYPED_TEST_P - -// State of the definition of a type-parameterized test case. -class GTEST_API_ TypedTestCasePState { - public: - TypedTestCasePState() : registered_(false) {} - - // Adds the given test name to defined_test_names_ and return true - // if the test case hasn't been registered; otherwise aborts the - // program. - bool AddTestName(const char* file, int line, const char* case_name, - const char* test_name) { - if (registered_) { - fprintf(stderr, "%s Test %s must be defined before " - "REGISTER_TYPED_TEST_CASE_P(%s, ...).\n", - FormatFileLocation(file, line).c_str(), test_name, case_name); - fflush(stderr); - posix::Abort(); - } - defined_test_names_.insert(test_name); - return true; - } - - // Verifies that registered_tests match the test names in - // defined_test_names_; returns registered_tests if successful, or - // aborts the program otherwise. - const char* VerifyRegisteredTestNames( - const char* file, int line, const char* registered_tests); - - private: - bool registered_; - ::std::set defined_test_names_; -}; - -// Skips to the first non-space char after the first comma in 'str'; -// returns NULL if no comma is found in 'str'. -inline const char* SkipComma(const char* str) { - const char* comma = strchr(str, ','); - if (comma == NULL) { - return NULL; - } - while (IsSpace(*(++comma))) {} - return comma; -} - -// Returns the prefix of 'str' before the first comma in it; returns -// the entire string if it contains no comma. -inline std::string GetPrefixUntilComma(const char* str) { - const char* comma = strchr(str, ','); - return comma == NULL ? str : std::string(str, comma); -} - -// TypeParameterizedTest::Register() -// registers a list of type-parameterized tests with Google Test. The -// return value is insignificant - we just need to return something -// such that we can call this function in a namespace scope. -// -// Implementation note: The GTEST_TEMPLATE_ macro declares a template -// template parameter. It's defined in gtest-type-util.h. -template -class TypeParameterizedTest { - public: - // 'index' is the index of the test in the type list 'Types' - // specified in INSTANTIATE_TYPED_TEST_CASE_P(Prefix, TestCase, - // Types). Valid values for 'index' are [0, N - 1] where N is the - // length of Types. - static bool Register(const char* prefix, const char* case_name, - const char* test_names, int index) { - typedef typename Types::Head Type; - typedef Fixture FixtureClass; - typedef typename GTEST_BIND_(TestSel, Type) TestClass; - - // First, registers the first type-parameterized test in the type - // list. - MakeAndRegisterTestInfo( - (std::string(prefix) + (prefix[0] == '\0' ? "" : "/") + case_name + "/" - + StreamableToString(index)).c_str(), - GetPrefixUntilComma(test_names).c_str(), - GetTypeName().c_str(), - NULL, // No value parameter. - GetTypeId(), - TestClass::SetUpTestCase, - TestClass::TearDownTestCase, - new TestFactoryImpl); - - // Next, recurses (at compile time) with the tail of the type list. - return TypeParameterizedTest - ::Register(prefix, case_name, test_names, index + 1); - } -}; - -// The base case for the compile time recursion. -template -class TypeParameterizedTest { - public: - static bool Register(const char* /*prefix*/, const char* /*case_name*/, - const char* /*test_names*/, int /*index*/) { - return true; - } -}; - -// TypeParameterizedTestCase::Register() -// registers *all combinations* of 'Tests' and 'Types' with Google -// Test. The return value is insignificant - we just need to return -// something such that we can call this function in a namespace scope. -template -class TypeParameterizedTestCase { - public: - static bool Register(const char* prefix, const char* case_name, - const char* test_names) { - typedef typename Tests::Head Head; - - // First, register the first test in 'Test' for each type in 'Types'. - TypeParameterizedTest::Register( - prefix, case_name, test_names, 0); - - // Next, recurses (at compile time) with the tail of the test list. - return TypeParameterizedTestCase - ::Register(prefix, case_name, SkipComma(test_names)); - } -}; - -// The base case for the compile time recursion. -template -class TypeParameterizedTestCase { - public: - static bool Register(const char* /*prefix*/, const char* /*case_name*/, - const char* /*test_names*/) { - return true; - } -}; - -#endif // GTEST_HAS_TYPED_TEST || GTEST_HAS_TYPED_TEST_P - -// Returns the current OS stack trace as an std::string. -// -// The maximum number of stack frames to be included is specified by -// the gtest_stack_trace_depth flag. The skip_count parameter -// specifies the number of top frames to be skipped, which doesn't -// count against the number of frames to be included. -// -// For example, if Foo() calls Bar(), which in turn calls -// GetCurrentOsStackTraceExceptTop(..., 1), Foo() will be included in -// the trace but Bar() and GetCurrentOsStackTraceExceptTop() won't. -GTEST_API_ std::string GetCurrentOsStackTraceExceptTop( - UnitTest* unit_test, int skip_count); - -// Helpers for suppressing warnings on unreachable code or constant -// condition. - -// Always returns true. -GTEST_API_ bool AlwaysTrue(); - -// Always returns false. -inline bool AlwaysFalse() { return !AlwaysTrue(); } - -// Helper for suppressing false warning from Clang on a const char* -// variable declared in a conditional expression always being NULL in -// the else branch. -struct GTEST_API_ ConstCharPtr { - ConstCharPtr(const char* str) : value(str) {} - operator bool() const { return true; } - const char* value; -}; - -// A simple Linear Congruential Generator for generating random -// numbers with a uniform distribution. Unlike rand() and srand(), it -// doesn't use global state (and therefore can't interfere with user -// code). Unlike rand_r(), it's portable. An LCG isn't very random, -// but it's good enough for our purposes. -class GTEST_API_ Random { - public: - static const UInt32 kMaxRange = 1u << 31; - - explicit Random(UInt32 seed) : state_(seed) {} - - void Reseed(UInt32 seed) { state_ = seed; } - - // Generates a random number from [0, range). Crashes if 'range' is - // 0 or greater than kMaxRange. - UInt32 Generate(UInt32 range); - - private: - UInt32 state_; - GTEST_DISALLOW_COPY_AND_ASSIGN_(Random); -}; - -// Defining a variable of type CompileAssertTypesEqual will cause a -// compiler error iff T1 and T2 are different types. -template -struct CompileAssertTypesEqual; - -template -struct CompileAssertTypesEqual { -}; - -// Removes the reference from a type if it is a reference type, -// otherwise leaves it unchanged. This is the same as -// tr1::remove_reference, which is not widely available yet. -template -struct RemoveReference { typedef T type; }; // NOLINT -template -struct RemoveReference { typedef T type; }; // NOLINT - -// A handy wrapper around RemoveReference that works when the argument -// T depends on template parameters. -#define GTEST_REMOVE_REFERENCE_(T) \ - typename ::testing::internal::RemoveReference::type - -// Removes const from a type if it is a const type, otherwise leaves -// it unchanged. This is the same as tr1::remove_const, which is not -// widely available yet. -template -struct RemoveConst { typedef T type; }; // NOLINT -template -struct RemoveConst { typedef T type; }; // NOLINT - -// MSVC 8.0, Sun C++, and IBM XL C++ have a bug which causes the above -// definition to fail to remove the const in 'const int[3]' and 'const -// char[3][4]'. The following specialization works around the bug. -template -struct RemoveConst { - typedef typename RemoveConst::type type[N]; -}; - -#if defined(_MSC_VER) && _MSC_VER < 1400 -// This is the only specialization that allows VC++ 7.1 to remove const in -// 'const int[3] and 'const int[3][4]'. However, it causes trouble with GCC -// and thus needs to be conditionally compiled. -template -struct RemoveConst { - typedef typename RemoveConst::type type[N]; -}; -#endif - -// A handy wrapper around RemoveConst that works when the argument -// T depends on template parameters. -#define GTEST_REMOVE_CONST_(T) \ - typename ::testing::internal::RemoveConst::type - -// Turns const U&, U&, const U, and U all into U. -#define GTEST_REMOVE_REFERENCE_AND_CONST_(T) \ - GTEST_REMOVE_CONST_(GTEST_REMOVE_REFERENCE_(T)) - -// Adds reference to a type if it is not a reference type, -// otherwise leaves it unchanged. This is the same as -// tr1::add_reference, which is not widely available yet. -template -struct AddReference { typedef T& type; }; // NOLINT -template -struct AddReference { typedef T& type; }; // NOLINT - -// A handy wrapper around AddReference that works when the argument T -// depends on template parameters. -#define GTEST_ADD_REFERENCE_(T) \ - typename ::testing::internal::AddReference::type - -// Adds a reference to const on top of T as necessary. For example, -// it transforms -// -// char ==> const char& -// const char ==> const char& -// char& ==> const char& -// const char& ==> const char& -// -// The argument T must depend on some template parameters. -#define GTEST_REFERENCE_TO_CONST_(T) \ - GTEST_ADD_REFERENCE_(const GTEST_REMOVE_REFERENCE_(T)) - -// ImplicitlyConvertible::value is a compile-time bool -// constant that's true iff type From can be implicitly converted to -// type To. -template -class ImplicitlyConvertible { - private: - // We need the following helper functions only for their types. - // They have no implementations. - - // MakeFrom() is an expression whose type is From. We cannot simply - // use From(), as the type From may not have a public default - // constructor. - static From MakeFrom(); - - // These two functions are overloaded. Given an expression - // Helper(x), the compiler will pick the first version if x can be - // implicitly converted to type To; otherwise it will pick the - // second version. - // - // The first version returns a value of size 1, and the second - // version returns a value of size 2. Therefore, by checking the - // size of Helper(x), which can be done at compile time, we can tell - // which version of Helper() is used, and hence whether x can be - // implicitly converted to type To. - static char Helper(To); - static char (&Helper(...))[2]; // NOLINT - - // We have to put the 'public' section after the 'private' section, - // or MSVC refuses to compile the code. - public: - // MSVC warns about implicitly converting from double to int for - // possible loss of data, so we need to temporarily disable the - // warning. -#ifdef _MSC_VER -# pragma warning(push) // Saves the current warning state. -# pragma warning(disable:4244) // Temporarily disables warning 4244. - - static const bool value = - sizeof(Helper(ImplicitlyConvertible::MakeFrom())) == 1; -# pragma warning(pop) // Restores the warning state. -#elif defined(__BORLANDC__) - // C++Builder cannot use member overload resolution during template - // instantiation. The simplest workaround is to use its C++0x type traits - // functions (C++Builder 2009 and above only). - static const bool value = __is_convertible(From, To); -#else - static const bool value = - sizeof(Helper(ImplicitlyConvertible::MakeFrom())) == 1; -#endif // _MSV_VER -}; -template -const bool ImplicitlyConvertible::value; - -// IsAProtocolMessage::value is a compile-time bool constant that's -// true iff T is type ProtocolMessage, proto2::Message, or a subclass -// of those. -template -struct IsAProtocolMessage - : public bool_constant< - ImplicitlyConvertible::value || - ImplicitlyConvertible::value> { -}; - -// When the compiler sees expression IsContainerTest(0), if C is an -// STL-style container class, the first overload of IsContainerTest -// will be viable (since both C::iterator* and C::const_iterator* are -// valid types and NULL can be implicitly converted to them). It will -// be picked over the second overload as 'int' is a perfect match for -// the type of argument 0. If C::iterator or C::const_iterator is not -// a valid type, the first overload is not viable, and the second -// overload will be picked. Therefore, we can determine whether C is -// a container class by checking the type of IsContainerTest(0). -// The value of the expression is insignificant. -// -// Note that we look for both C::iterator and C::const_iterator. The -// reason is that C++ injects the name of a class as a member of the -// class itself (e.g. you can refer to class iterator as either -// 'iterator' or 'iterator::iterator'). If we look for C::iterator -// only, for example, we would mistakenly think that a class named -// iterator is an STL container. -// -// Also note that the simpler approach of overloading -// IsContainerTest(typename C::const_iterator*) and -// IsContainerTest(...) doesn't work with Visual Age C++ and Sun C++. -typedef int IsContainer; -template -IsContainer IsContainerTest(int /* dummy */, - typename C::iterator* /* it */ = NULL, - typename C::const_iterator* /* const_it */ = NULL) { - return 0; -} - -typedef char IsNotContainer; -template -IsNotContainer IsContainerTest(long /* dummy */) { return '\0'; } - -// EnableIf::type is void when 'Cond' is true, and -// undefined when 'Cond' is false. To use SFINAE to make a function -// overload only apply when a particular expression is true, add -// "typename EnableIf::type* = 0" as the last parameter. -template struct EnableIf; -template<> struct EnableIf { typedef void type; }; // NOLINT - -// Utilities for native arrays. - -// ArrayEq() compares two k-dimensional native arrays using the -// elements' operator==, where k can be any integer >= 0. When k is -// 0, ArrayEq() degenerates into comparing a single pair of values. - -template -bool ArrayEq(const T* lhs, size_t size, const U* rhs); - -// This generic version is used when k is 0. -template -inline bool ArrayEq(const T& lhs, const U& rhs) { return lhs == rhs; } - -// This overload is used when k >= 1. -template -inline bool ArrayEq(const T(&lhs)[N], const U(&rhs)[N]) { - return internal::ArrayEq(lhs, N, rhs); -} - -// This helper reduces code bloat. If we instead put its logic inside -// the previous ArrayEq() function, arrays with different sizes would -// lead to different copies of the template code. -template -bool ArrayEq(const T* lhs, size_t size, const U* rhs) { - for (size_t i = 0; i != size; i++) { - if (!internal::ArrayEq(lhs[i], rhs[i])) - return false; - } - return true; -} - -// Finds the first element in the iterator range [begin, end) that -// equals elem. Element may be a native array type itself. -template -Iter ArrayAwareFind(Iter begin, Iter end, const Element& elem) { - for (Iter it = begin; it != end; ++it) { - if (internal::ArrayEq(*it, elem)) - return it; - } - return end; -} - -// CopyArray() copies a k-dimensional native array using the elements' -// operator=, where k can be any integer >= 0. When k is 0, -// CopyArray() degenerates into copying a single value. - -template -void CopyArray(const T* from, size_t size, U* to); - -// This generic version is used when k is 0. -template -inline void CopyArray(const T& from, U* to) { *to = from; } - -// This overload is used when k >= 1. -template -inline void CopyArray(const T(&from)[N], U(*to)[N]) { - internal::CopyArray(from, N, *to); -} - -// This helper reduces code bloat. If we instead put its logic inside -// the previous CopyArray() function, arrays with different sizes -// would lead to different copies of the template code. -template -void CopyArray(const T* from, size_t size, U* to) { - for (size_t i = 0; i != size; i++) { - internal::CopyArray(from[i], to + i); - } -} - -// The relation between an NativeArray object (see below) and the -// native array it represents. -enum RelationToSource { - kReference, // The NativeArray references the native array. - kCopy // The NativeArray makes a copy of the native array and - // owns the copy. -}; - -// Adapts a native array to a read-only STL-style container. Instead -// of the complete STL container concept, this adaptor only implements -// members useful for Google Mock's container matchers. New members -// should be added as needed. To simplify the implementation, we only -// support Element being a raw type (i.e. having no top-level const or -// reference modifier). It's the client's responsibility to satisfy -// this requirement. Element can be an array type itself (hence -// multi-dimensional arrays are supported). -template -class NativeArray { - public: - // STL-style container typedefs. - typedef Element value_type; - typedef Element* iterator; - typedef const Element* const_iterator; - - // Constructs from a native array. - NativeArray(const Element* array, size_t count, RelationToSource relation) { - Init(array, count, relation); - } - - // Copy constructor. - NativeArray(const NativeArray& rhs) { - Init(rhs.array_, rhs.size_, rhs.relation_to_source_); - } - - ~NativeArray() { - // Ensures that the user doesn't instantiate NativeArray with a - // const or reference type. - static_cast(StaticAssertTypeEqHelper()); - if (relation_to_source_ == kCopy) - delete[] array_; - } - - // STL-style container methods. - size_t size() const { return size_; } - const_iterator begin() const { return array_; } - const_iterator end() const { return array_ + size_; } - bool operator==(const NativeArray& rhs) const { - return size() == rhs.size() && - ArrayEq(begin(), size(), rhs.begin()); - } - - private: - // Initializes this object; makes a copy of the input array if - // 'relation' is kCopy. - void Init(const Element* array, size_t a_size, RelationToSource relation) { - if (relation == kReference) { - array_ = array; - } else { - Element* const copy = new Element[a_size]; - CopyArray(array, a_size, copy); - array_ = copy; - } - size_ = a_size; - relation_to_source_ = relation; - } - - const Element* array_; - size_t size_; - RelationToSource relation_to_source_; - - GTEST_DISALLOW_ASSIGN_(NativeArray); -}; - -} // namespace internal -} // namespace testing - -#define GTEST_MESSAGE_AT_(file, line, message, result_type) \ - ::testing::internal::AssertHelper(result_type, file, line, message) \ - = ::testing::Message() - -#define GTEST_MESSAGE_(message, result_type) \ - GTEST_MESSAGE_AT_(__FILE__, __LINE__, message, result_type) - -#define GTEST_FATAL_FAILURE_(message) \ - return GTEST_MESSAGE_(message, ::testing::TestPartResult::kFatalFailure) - -#define GTEST_NONFATAL_FAILURE_(message) \ - GTEST_MESSAGE_(message, ::testing::TestPartResult::kNonFatalFailure) - -#define GTEST_SUCCESS_(message) \ - GTEST_MESSAGE_(message, ::testing::TestPartResult::kSuccess) - -// Suppresses MSVC warnings 4072 (unreachable code) for the code following -// statement if it returns or throws (or doesn't return or throw in some -// situations). -#define GTEST_SUPPRESS_UNREACHABLE_CODE_WARNING_BELOW_(statement) \ - if (::testing::internal::AlwaysTrue()) { statement; } - -#define GTEST_TEST_THROW_(statement, expected_exception, fail) \ - GTEST_AMBIGUOUS_ELSE_BLOCKER_ \ - if (::testing::internal::ConstCharPtr gtest_msg = "") { \ - bool gtest_caught_expected = false; \ - try { \ - GTEST_SUPPRESS_UNREACHABLE_CODE_WARNING_BELOW_(statement); \ - } \ - catch (expected_exception const&) { \ - gtest_caught_expected = true; \ - } \ - catch (...) { \ - gtest_msg.value = \ - "Expected: " #statement " throws an exception of type " \ - #expected_exception ".\n Actual: it throws a different type."; \ - goto GTEST_CONCAT_TOKEN_(gtest_label_testthrow_, __LINE__); \ - } \ - if (!gtest_caught_expected) { \ - gtest_msg.value = \ - "Expected: " #statement " throws an exception of type " \ - #expected_exception ".\n Actual: it throws nothing."; \ - goto GTEST_CONCAT_TOKEN_(gtest_label_testthrow_, __LINE__); \ - } \ - } else \ - GTEST_CONCAT_TOKEN_(gtest_label_testthrow_, __LINE__): \ - fail(gtest_msg.value) - -#define GTEST_TEST_NO_THROW_(statement, fail) \ - GTEST_AMBIGUOUS_ELSE_BLOCKER_ \ - if (::testing::internal::AlwaysTrue()) { \ - try { \ - GTEST_SUPPRESS_UNREACHABLE_CODE_WARNING_BELOW_(statement); \ - } \ - catch (...) { \ - goto GTEST_CONCAT_TOKEN_(gtest_label_testnothrow_, __LINE__); \ - } \ - } else \ - GTEST_CONCAT_TOKEN_(gtest_label_testnothrow_, __LINE__): \ - fail("Expected: " #statement " doesn't throw an exception.\n" \ - " Actual: it throws.") - -#define GTEST_TEST_ANY_THROW_(statement, fail) \ - GTEST_AMBIGUOUS_ELSE_BLOCKER_ \ - if (::testing::internal::AlwaysTrue()) { \ - bool gtest_caught_any = false; \ - try { \ - GTEST_SUPPRESS_UNREACHABLE_CODE_WARNING_BELOW_(statement); \ - } \ - catch (...) { \ - gtest_caught_any = true; \ - } \ - if (!gtest_caught_any) { \ - goto GTEST_CONCAT_TOKEN_(gtest_label_testanythrow_, __LINE__); \ - } \ - } else \ - GTEST_CONCAT_TOKEN_(gtest_label_testanythrow_, __LINE__): \ - fail("Expected: " #statement " throws an exception.\n" \ - " Actual: it doesn't.") - - -// Implements Boolean test assertions such as EXPECT_TRUE. expression can be -// either a boolean expression or an AssertionResult. text is a textual -// represenation of expression as it was passed into the EXPECT_TRUE. -#define GTEST_TEST_BOOLEAN_(expression, text, actual, expected, fail) \ - GTEST_AMBIGUOUS_ELSE_BLOCKER_ \ - if (const ::testing::AssertionResult gtest_ar_ = \ - ::testing::AssertionResult(expression)) \ - ; \ - else \ - fail(::testing::internal::GetBoolAssertionFailureMessage(\ - gtest_ar_, text, #actual, #expected).c_str()) - -#define GTEST_TEST_NO_FATAL_FAILURE_(statement, fail) \ - GTEST_AMBIGUOUS_ELSE_BLOCKER_ \ - if (::testing::internal::AlwaysTrue()) { \ - ::testing::internal::HasNewFatalFailureHelper gtest_fatal_failure_checker; \ - GTEST_SUPPRESS_UNREACHABLE_CODE_WARNING_BELOW_(statement); \ - if (gtest_fatal_failure_checker.has_new_fatal_failure()) { \ - goto GTEST_CONCAT_TOKEN_(gtest_label_testnofatal_, __LINE__); \ - } \ - } else \ - GTEST_CONCAT_TOKEN_(gtest_label_testnofatal_, __LINE__): \ - fail("Expected: " #statement " doesn't generate new fatal " \ - "failures in the current thread.\n" \ - " Actual: it does.") - -// Expands to the name of the class that implements the given test. -#define GTEST_TEST_CLASS_NAME_(test_case_name, test_name) \ - test_case_name##_##test_name##_Test - -// Helper macro for defining tests. -#define GTEST_TEST_(test_case_name, test_name, parent_class, parent_id)\ -class GTEST_TEST_CLASS_NAME_(test_case_name, test_name) : public parent_class {\ - public:\ - GTEST_TEST_CLASS_NAME_(test_case_name, test_name)() {}\ - private:\ - virtual void TestBody();\ - static ::testing::TestInfo* const test_info_ GTEST_ATTRIBUTE_UNUSED_;\ - GTEST_DISALLOW_COPY_AND_ASSIGN_(\ - GTEST_TEST_CLASS_NAME_(test_case_name, test_name));\ -};\ -\ -::testing::TestInfo* const GTEST_TEST_CLASS_NAME_(test_case_name, test_name)\ - ::test_info_ =\ - ::testing::internal::MakeAndRegisterTestInfo(\ - #test_case_name, #test_name, NULL, NULL, \ - (parent_id), \ - parent_class::SetUpTestCase, \ - parent_class::TearDownTestCase, \ - new ::testing::internal::TestFactoryImpl<\ - GTEST_TEST_CLASS_NAME_(test_case_name, test_name)>);\ -void GTEST_TEST_CLASS_NAME_(test_case_name, test_name)::TestBody() - -#endif // GTEST_INCLUDE_GTEST_INTERNAL_GTEST_INTERNAL_H_ -// Copyright 2005, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: wan@google.com (Zhanyong Wan) -// -// The Google C++ Testing Framework (Google Test) -// -// This header file defines the public API for death tests. It is -// #included by gtest.h so a user doesn't need to include this -// directly. - -#ifndef GTEST_INCLUDE_GTEST_GTEST_DEATH_TEST_H_ -#define GTEST_INCLUDE_GTEST_GTEST_DEATH_TEST_H_ - -// Copyright 2005, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Authors: wan@google.com (Zhanyong Wan), eefacm@gmail.com (Sean Mcafee) -// -// The Google C++ Testing Framework (Google Test) -// -// This header file defines internal utilities needed for implementing -// death tests. They are subject to change without notice. - -#ifndef GTEST_INCLUDE_GTEST_INTERNAL_GTEST_DEATH_TEST_INTERNAL_H_ -#define GTEST_INCLUDE_GTEST_INTERNAL_GTEST_DEATH_TEST_INTERNAL_H_ - - -#include - -namespace testing { -namespace internal { - -GTEST_DECLARE_string_(internal_run_death_test); - -// Names of the flags (needed for parsing Google Test flags). -const char kDeathTestStyleFlag[] = "death_test_style"; -const char kDeathTestUseFork[] = "death_test_use_fork"; -const char kInternalRunDeathTestFlag[] = "internal_run_death_test"; - -#if GTEST_HAS_DEATH_TEST - -// DeathTest is a class that hides much of the complexity of the -// GTEST_DEATH_TEST_ macro. It is abstract; its static Create method -// returns a concrete class that depends on the prevailing death test -// style, as defined by the --gtest_death_test_style and/or -// --gtest_internal_run_death_test flags. - -// In describing the results of death tests, these terms are used with -// the corresponding definitions: -// -// exit status: The integer exit information in the format specified -// by wait(2) -// exit code: The integer code passed to exit(3), _exit(2), or -// returned from main() -class GTEST_API_ DeathTest { - public: - // Create returns false if there was an error determining the - // appropriate action to take for the current death test; for example, - // if the gtest_death_test_style flag is set to an invalid value. - // The LastMessage method will return a more detailed message in that - // case. Otherwise, the DeathTest pointer pointed to by the "test" - // argument is set. If the death test should be skipped, the pointer - // is set to NULL; otherwise, it is set to the address of a new concrete - // DeathTest object that controls the execution of the current test. - static bool Create(const char* statement, const RE* regex, - const char* file, int line, DeathTest** test); - DeathTest(); - virtual ~DeathTest() { } - - // A helper class that aborts a death test when it's deleted. - class ReturnSentinel { - public: - explicit ReturnSentinel(DeathTest* test) : test_(test) { } - ~ReturnSentinel() { test_->Abort(TEST_ENCOUNTERED_RETURN_STATEMENT); } - private: - DeathTest* const test_; - GTEST_DISALLOW_COPY_AND_ASSIGN_(ReturnSentinel); - } GTEST_ATTRIBUTE_UNUSED_; - - // An enumeration of possible roles that may be taken when a death - // test is encountered. EXECUTE means that the death test logic should - // be executed immediately. OVERSEE means that the program should prepare - // the appropriate environment for a child process to execute the death - // test, then wait for it to complete. - enum TestRole { OVERSEE_TEST, EXECUTE_TEST }; - - // An enumeration of the three reasons that a test might be aborted. - enum AbortReason { - TEST_ENCOUNTERED_RETURN_STATEMENT, - TEST_THREW_EXCEPTION, - TEST_DID_NOT_DIE - }; - - // Assumes one of the above roles. - virtual TestRole AssumeRole() = 0; - - // Waits for the death test to finish and returns its status. - virtual int Wait() = 0; - - // Returns true if the death test passed; that is, the test process - // exited during the test, its exit status matches a user-supplied - // predicate, and its stderr output matches a user-supplied regular - // expression. - // The user-supplied predicate may be a macro expression rather - // than a function pointer or functor, or else Wait and Passed could - // be combined. - virtual bool Passed(bool exit_status_ok) = 0; - - // Signals that the death test did not die as expected. - virtual void Abort(AbortReason reason) = 0; - - // Returns a human-readable outcome message regarding the outcome of - // the last death test. - static const char* LastMessage(); - - static void set_last_death_test_message(const std::string& message); - - private: - // A string containing a description of the outcome of the last death test. - static std::string last_death_test_message_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(DeathTest); -}; - -// Factory interface for death tests. May be mocked out for testing. -class DeathTestFactory { - public: - virtual ~DeathTestFactory() { } - virtual bool Create(const char* statement, const RE* regex, - const char* file, int line, DeathTest** test) = 0; -}; - -// A concrete DeathTestFactory implementation for normal use. -class DefaultDeathTestFactory : public DeathTestFactory { - public: - virtual bool Create(const char* statement, const RE* regex, - const char* file, int line, DeathTest** test); -}; - -// Returns true if exit_status describes a process that was terminated -// by a signal, or exited normally with a nonzero exit code. -GTEST_API_ bool ExitedUnsuccessfully(int exit_status); - -// Traps C++ exceptions escaping statement and reports them as test -// failures. Note that trapping SEH exceptions is not implemented here. -# if GTEST_HAS_EXCEPTIONS -# define GTEST_EXECUTE_DEATH_TEST_STATEMENT_(statement, death_test) \ - try { \ - GTEST_SUPPRESS_UNREACHABLE_CODE_WARNING_BELOW_(statement); \ - } catch (const ::std::exception& gtest_exception) { \ - fprintf(\ - stderr, \ - "\n%s: Caught std::exception-derived exception escaping the " \ - "death test statement. Exception message: %s\n", \ - ::testing::internal::FormatFileLocation(__FILE__, __LINE__).c_str(), \ - gtest_exception.what()); \ - fflush(stderr); \ - death_test->Abort(::testing::internal::DeathTest::TEST_THREW_EXCEPTION); \ - } catch (...) { \ - death_test->Abort(::testing::internal::DeathTest::TEST_THREW_EXCEPTION); \ - } - -# else -# define GTEST_EXECUTE_DEATH_TEST_STATEMENT_(statement, death_test) \ - GTEST_SUPPRESS_UNREACHABLE_CODE_WARNING_BELOW_(statement) - -# endif - -// This macro is for implementing ASSERT_DEATH*, EXPECT_DEATH*, -// ASSERT_EXIT*, and EXPECT_EXIT*. -# define GTEST_DEATH_TEST_(statement, predicate, regex, fail) \ - GTEST_AMBIGUOUS_ELSE_BLOCKER_ \ - if (::testing::internal::AlwaysTrue()) { \ - const ::testing::internal::RE& gtest_regex = (regex); \ - ::testing::internal::DeathTest* gtest_dt; \ - if (!::testing::internal::DeathTest::Create(#statement, >est_regex, \ - __FILE__, __LINE__, >est_dt)) { \ - goto GTEST_CONCAT_TOKEN_(gtest_label_, __LINE__); \ - } \ - if (gtest_dt != NULL) { \ - ::testing::internal::scoped_ptr< ::testing::internal::DeathTest> \ - gtest_dt_ptr(gtest_dt); \ - switch (gtest_dt->AssumeRole()) { \ - case ::testing::internal::DeathTest::OVERSEE_TEST: \ - if (!gtest_dt->Passed(predicate(gtest_dt->Wait()))) { \ - goto GTEST_CONCAT_TOKEN_(gtest_label_, __LINE__); \ - } \ - break; \ - case ::testing::internal::DeathTest::EXECUTE_TEST: { \ - ::testing::internal::DeathTest::ReturnSentinel \ - gtest_sentinel(gtest_dt); \ - GTEST_EXECUTE_DEATH_TEST_STATEMENT_(statement, gtest_dt); \ - gtest_dt->Abort(::testing::internal::DeathTest::TEST_DID_NOT_DIE); \ - break; \ - } \ - default: \ - break; \ - } \ - } \ - } else \ - GTEST_CONCAT_TOKEN_(gtest_label_, __LINE__): \ - fail(::testing::internal::DeathTest::LastMessage()) -// The symbol "fail" here expands to something into which a message -// can be streamed. - -// This macro is for implementing ASSERT/EXPECT_DEBUG_DEATH when compiled in -// NDEBUG mode. In this case we need the statements to be executed, the regex is -// ignored, and the macro must accept a streamed message even though the message -// is never printed. -# define GTEST_EXECUTE_STATEMENT_(statement, regex) \ - GTEST_AMBIGUOUS_ELSE_BLOCKER_ \ - if (::testing::internal::AlwaysTrue()) { \ - GTEST_SUPPRESS_UNREACHABLE_CODE_WARNING_BELOW_(statement); \ - } else \ - ::testing::Message() - -// A class representing the parsed contents of the -// --gtest_internal_run_death_test flag, as it existed when -// RUN_ALL_TESTS was called. -class InternalRunDeathTestFlag { - public: - InternalRunDeathTestFlag(const std::string& a_file, - int a_line, - int an_index, - int a_write_fd) - : file_(a_file), line_(a_line), index_(an_index), - write_fd_(a_write_fd) {} - - ~InternalRunDeathTestFlag() { - if (write_fd_ >= 0) - posix::Close(write_fd_); - } - - const std::string& file() const { return file_; } - int line() const { return line_; } - int index() const { return index_; } - int write_fd() const { return write_fd_; } - - private: - std::string file_; - int line_; - int index_; - int write_fd_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(InternalRunDeathTestFlag); -}; - -// Returns a newly created InternalRunDeathTestFlag object with fields -// initialized from the GTEST_FLAG(internal_run_death_test) flag if -// the flag is specified; otherwise returns NULL. -InternalRunDeathTestFlag* ParseInternalRunDeathTestFlag(); - -#else // GTEST_HAS_DEATH_TEST - -// This macro is used for implementing macros such as -// EXPECT_DEATH_IF_SUPPORTED and ASSERT_DEATH_IF_SUPPORTED on systems where -// death tests are not supported. Those macros must compile on such systems -// iff EXPECT_DEATH and ASSERT_DEATH compile with the same parameters on -// systems that support death tests. This allows one to write such a macro -// on a system that does not support death tests and be sure that it will -// compile on a death-test supporting system. -// -// Parameters: -// statement - A statement that a macro such as EXPECT_DEATH would test -// for program termination. This macro has to make sure this -// statement is compiled but not executed, to ensure that -// EXPECT_DEATH_IF_SUPPORTED compiles with a certain -// parameter iff EXPECT_DEATH compiles with it. -// regex - A regex that a macro such as EXPECT_DEATH would use to test -// the output of statement. This parameter has to be -// compiled but not evaluated by this macro, to ensure that -// this macro only accepts expressions that a macro such as -// EXPECT_DEATH would accept. -// terminator - Must be an empty statement for EXPECT_DEATH_IF_SUPPORTED -// and a return statement for ASSERT_DEATH_IF_SUPPORTED. -// This ensures that ASSERT_DEATH_IF_SUPPORTED will not -// compile inside functions where ASSERT_DEATH doesn't -// compile. -// -// The branch that has an always false condition is used to ensure that -// statement and regex are compiled (and thus syntactically correct) but -// never executed. The unreachable code macro protects the terminator -// statement from generating an 'unreachable code' warning in case -// statement unconditionally returns or throws. The Message constructor at -// the end allows the syntax of streaming additional messages into the -// macro, for compilational compatibility with EXPECT_DEATH/ASSERT_DEATH. -# define GTEST_UNSUPPORTED_DEATH_TEST_(statement, regex, terminator) \ - GTEST_AMBIGUOUS_ELSE_BLOCKER_ \ - if (::testing::internal::AlwaysTrue()) { \ - GTEST_LOG_(WARNING) \ - << "Death tests are not supported on this platform.\n" \ - << "Statement '" #statement "' cannot be verified."; \ - } else if (::testing::internal::AlwaysFalse()) { \ - ::testing::internal::RE::PartialMatch(".*", (regex)); \ - GTEST_SUPPRESS_UNREACHABLE_CODE_WARNING_BELOW_(statement); \ - terminator; \ - } else \ - ::testing::Message() - -#endif // GTEST_HAS_DEATH_TEST - -} // namespace internal -} // namespace testing - -#endif // GTEST_INCLUDE_GTEST_INTERNAL_GTEST_DEATH_TEST_INTERNAL_H_ - -namespace testing { - -// This flag controls the style of death tests. Valid values are "threadsafe", -// meaning that the death test child process will re-execute the test binary -// from the start, running only a single death test, or "fast", -// meaning that the child process will execute the test logic immediately -// after forking. -GTEST_DECLARE_string_(death_test_style); - -#if GTEST_HAS_DEATH_TEST - -namespace internal { - -// Returns a Boolean value indicating whether the caller is currently -// executing in the context of the death test child process. Tools such as -// Valgrind heap checkers may need this to modify their behavior in death -// tests. IMPORTANT: This is an internal utility. Using it may break the -// implementation of death tests. User code MUST NOT use it. -GTEST_API_ bool InDeathTestChild(); - -} // namespace internal - -// The following macros are useful for writing death tests. - -// Here's what happens when an ASSERT_DEATH* or EXPECT_DEATH* is -// executed: -// -// 1. It generates a warning if there is more than one active -// thread. This is because it's safe to fork() or clone() only -// when there is a single thread. -// -// 2. The parent process clone()s a sub-process and runs the death -// test in it; the sub-process exits with code 0 at the end of the -// death test, if it hasn't exited already. -// -// 3. The parent process waits for the sub-process to terminate. -// -// 4. The parent process checks the exit code and error message of -// the sub-process. -// -// Examples: -// -// ASSERT_DEATH(server.SendMessage(56, "Hello"), "Invalid port number"); -// for (int i = 0; i < 5; i++) { -// EXPECT_DEATH(server.ProcessRequest(i), -// "Invalid request .* in ProcessRequest()") -// << "Failed to die on request " << i; -// } -// -// ASSERT_EXIT(server.ExitNow(), ::testing::ExitedWithCode(0), "Exiting"); -// -// bool KilledBySIGHUP(int exit_code) { -// return WIFSIGNALED(exit_code) && WTERMSIG(exit_code) == SIGHUP; -// } -// -// ASSERT_EXIT(client.HangUpServer(), KilledBySIGHUP, "Hanging up!"); -// -// On the regular expressions used in death tests: -// -// On POSIX-compliant systems (*nix), we use the library, -// which uses the POSIX extended regex syntax. -// -// On other platforms (e.g. Windows), we only support a simple regex -// syntax implemented as part of Google Test. This limited -// implementation should be enough most of the time when writing -// death tests; though it lacks many features you can find in PCRE -// or POSIX extended regex syntax. For example, we don't support -// union ("x|y"), grouping ("(xy)"), brackets ("[xy]"), and -// repetition count ("x{5,7}"), among others. -// -// Below is the syntax that we do support. We chose it to be a -// subset of both PCRE and POSIX extended regex, so it's easy to -// learn wherever you come from. In the following: 'A' denotes a -// literal character, period (.), or a single \\ escape sequence; -// 'x' and 'y' denote regular expressions; 'm' and 'n' are for -// natural numbers. -// -// c matches any literal character c -// \\d matches any decimal digit -// \\D matches any character that's not a decimal digit -// \\f matches \f -// \\n matches \n -// \\r matches \r -// \\s matches any ASCII whitespace, including \n -// \\S matches any character that's not a whitespace -// \\t matches \t -// \\v matches \v -// \\w matches any letter, _, or decimal digit -// \\W matches any character that \\w doesn't match -// \\c matches any literal character c, which must be a punctuation -// . matches any single character except \n -// A? matches 0 or 1 occurrences of A -// A* matches 0 or many occurrences of A -// A+ matches 1 or many occurrences of A -// ^ matches the beginning of a string (not that of each line) -// $ matches the end of a string (not that of each line) -// xy matches x followed by y -// -// If you accidentally use PCRE or POSIX extended regex features -// not implemented by us, you will get a run-time failure. In that -// case, please try to rewrite your regular expression within the -// above syntax. -// -// This implementation is *not* meant to be as highly tuned or robust -// as a compiled regex library, but should perform well enough for a -// death test, which already incurs significant overhead by launching -// a child process. -// -// Known caveats: -// -// A "threadsafe" style death test obtains the path to the test -// program from argv[0] and re-executes it in the sub-process. For -// simplicity, the current implementation doesn't search the PATH -// when launching the sub-process. This means that the user must -// invoke the test program via a path that contains at least one -// path separator (e.g. path/to/foo_test and -// /absolute/path/to/bar_test are fine, but foo_test is not). This -// is rarely a problem as people usually don't put the test binary -// directory in PATH. -// -// TODO(wan@google.com): make thread-safe death tests search the PATH. - -// Asserts that a given statement causes the program to exit, with an -// integer exit status that satisfies predicate, and emitting error output -// that matches regex. -# define ASSERT_EXIT(statement, predicate, regex) \ - GTEST_DEATH_TEST_(statement, predicate, regex, GTEST_FATAL_FAILURE_) - -// Like ASSERT_EXIT, but continues on to successive tests in the -// test case, if any: -# define EXPECT_EXIT(statement, predicate, regex) \ - GTEST_DEATH_TEST_(statement, predicate, regex, GTEST_NONFATAL_FAILURE_) - -// Asserts that a given statement causes the program to exit, either by -// explicitly exiting with a nonzero exit code or being killed by a -// signal, and emitting error output that matches regex. -# define ASSERT_DEATH(statement, regex) \ - ASSERT_EXIT(statement, ::testing::internal::ExitedUnsuccessfully, regex) - -// Like ASSERT_DEATH, but continues on to successive tests in the -// test case, if any: -# define EXPECT_DEATH(statement, regex) \ - EXPECT_EXIT(statement, ::testing::internal::ExitedUnsuccessfully, regex) - -// Two predicate classes that can be used in {ASSERT,EXPECT}_EXIT*: - -// Tests that an exit code describes a normal exit with a given exit code. -class GTEST_API_ ExitedWithCode { - public: - explicit ExitedWithCode(int exit_code); - bool operator()(int exit_status) const; - private: - // No implementation - assignment is unsupported. - void operator=(const ExitedWithCode& other); - - const int exit_code_; -}; - -# if !GTEST_OS_WINDOWS -// Tests that an exit code describes an exit due to termination by a -// given signal. -class GTEST_API_ KilledBySignal { - public: - explicit KilledBySignal(int signum); - bool operator()(int exit_status) const; - private: - const int signum_; -}; -# endif // !GTEST_OS_WINDOWS - -// EXPECT_DEBUG_DEATH asserts that the given statements die in debug mode. -// The death testing framework causes this to have interesting semantics, -// since the sideeffects of the call are only visible in opt mode, and not -// in debug mode. -// -// In practice, this can be used to test functions that utilize the -// LOG(DFATAL) macro using the following style: -// -// int DieInDebugOr12(int* sideeffect) { -// if (sideeffect) { -// *sideeffect = 12; -// } -// LOG(DFATAL) << "death"; -// return 12; -// } -// -// TEST(TestCase, TestDieOr12WorksInDgbAndOpt) { -// int sideeffect = 0; -// // Only asserts in dbg. -// EXPECT_DEBUG_DEATH(DieInDebugOr12(&sideeffect), "death"); -// -// #ifdef NDEBUG -// // opt-mode has sideeffect visible. -// EXPECT_EQ(12, sideeffect); -// #else -// // dbg-mode no visible sideeffect. -// EXPECT_EQ(0, sideeffect); -// #endif -// } -// -// This will assert that DieInDebugReturn12InOpt() crashes in debug -// mode, usually due to a DCHECK or LOG(DFATAL), but returns the -// appropriate fallback value (12 in this case) in opt mode. If you -// need to test that a function has appropriate side-effects in opt -// mode, include assertions against the side-effects. A general -// pattern for this is: -// -// EXPECT_DEBUG_DEATH({ -// // Side-effects here will have an effect after this statement in -// // opt mode, but none in debug mode. -// EXPECT_EQ(12, DieInDebugOr12(&sideeffect)); -// }, "death"); -// -# ifdef NDEBUG - -# define EXPECT_DEBUG_DEATH(statement, regex) \ - GTEST_EXECUTE_STATEMENT_(statement, regex) - -# define ASSERT_DEBUG_DEATH(statement, regex) \ - GTEST_EXECUTE_STATEMENT_(statement, regex) - -# else - -# define EXPECT_DEBUG_DEATH(statement, regex) \ - EXPECT_DEATH(statement, regex) - -# define ASSERT_DEBUG_DEATH(statement, regex) \ - ASSERT_DEATH(statement, regex) - -# endif // NDEBUG for EXPECT_DEBUG_DEATH -#endif // GTEST_HAS_DEATH_TEST - -// EXPECT_DEATH_IF_SUPPORTED(statement, regex) and -// ASSERT_DEATH_IF_SUPPORTED(statement, regex) expand to real death tests if -// death tests are supported; otherwise they just issue a warning. This is -// useful when you are combining death test assertions with normal test -// assertions in one test. -#if GTEST_HAS_DEATH_TEST -# define EXPECT_DEATH_IF_SUPPORTED(statement, regex) \ - EXPECT_DEATH(statement, regex) -# define ASSERT_DEATH_IF_SUPPORTED(statement, regex) \ - ASSERT_DEATH(statement, regex) -#else -# define EXPECT_DEATH_IF_SUPPORTED(statement, regex) \ - GTEST_UNSUPPORTED_DEATH_TEST_(statement, regex, ) -# define ASSERT_DEATH_IF_SUPPORTED(statement, regex) \ - GTEST_UNSUPPORTED_DEATH_TEST_(statement, regex, return) -#endif - -} // namespace testing - -#endif // GTEST_INCLUDE_GTEST_GTEST_DEATH_TEST_H_ -// This file was GENERATED by command: -// pump.py gtest-param-test.h.pump -// DO NOT EDIT BY HAND!!! - -// Copyright 2008, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Authors: vladl@google.com (Vlad Losev) -// -// Macros and functions for implementing parameterized tests -// in Google C++ Testing Framework (Google Test) -// -// This file is generated by a SCRIPT. DO NOT EDIT BY HAND! -// -#ifndef GTEST_INCLUDE_GTEST_GTEST_PARAM_TEST_H_ -#define GTEST_INCLUDE_GTEST_GTEST_PARAM_TEST_H_ - - -// Value-parameterized tests allow you to test your code with different -// parameters without writing multiple copies of the same test. -// -// Here is how you use value-parameterized tests: - -#if 0 - -// To write value-parameterized tests, first you should define a fixture -// class. It is usually derived from testing::TestWithParam (see below for -// another inheritance scheme that's sometimes useful in more complicated -// class hierarchies), where the type of your parameter values. -// TestWithParam is itself derived from testing::Test. T can be any -// copyable type. If it's a raw pointer, you are responsible for managing the -// lifespan of the pointed values. - -class FooTest : public ::testing::TestWithParam { - // You can implement all the usual class fixture members here. -}; - -// Then, use the TEST_P macro to define as many parameterized tests -// for this fixture as you want. The _P suffix is for "parameterized" -// or "pattern", whichever you prefer to think. - -TEST_P(FooTest, DoesBlah) { - // Inside a test, access the test parameter with the GetParam() method - // of the TestWithParam class: - EXPECT_TRUE(foo.Blah(GetParam())); - ... -} - -TEST_P(FooTest, HasBlahBlah) { - ... -} - -// Finally, you can use INSTANTIATE_TEST_CASE_P to instantiate the test -// case with any set of parameters you want. Google Test defines a number -// of functions for generating test parameters. They return what we call -// (surprise!) parameter generators. Here is a summary of them, which -// are all in the testing namespace: -// -// -// Range(begin, end [, step]) - Yields values {begin, begin+step, -// begin+step+step, ...}. The values do not -// include end. step defaults to 1. -// Values(v1, v2, ..., vN) - Yields values {v1, v2, ..., vN}. -// ValuesIn(container) - Yields values from a C-style array, an STL -// ValuesIn(begin,end) container, or an iterator range [begin, end). -// Bool() - Yields sequence {false, true}. -// Combine(g1, g2, ..., gN) - Yields all combinations (the Cartesian product -// for the math savvy) of the values generated -// by the N generators. -// -// For more details, see comments at the definitions of these functions below -// in this file. -// -// The following statement will instantiate tests from the FooTest test case -// each with parameter values "meeny", "miny", and "moe". - -INSTANTIATE_TEST_CASE_P(InstantiationName, - FooTest, - Values("meeny", "miny", "moe")); - -// To distinguish different instances of the pattern, (yes, you -// can instantiate it more then once) the first argument to the -// INSTANTIATE_TEST_CASE_P macro is a prefix that will be added to the -// actual test case name. Remember to pick unique prefixes for different -// instantiations. The tests from the instantiation above will have -// these names: -// -// * InstantiationName/FooTest.DoesBlah/0 for "meeny" -// * InstantiationName/FooTest.DoesBlah/1 for "miny" -// * InstantiationName/FooTest.DoesBlah/2 for "moe" -// * InstantiationName/FooTest.HasBlahBlah/0 for "meeny" -// * InstantiationName/FooTest.HasBlahBlah/1 for "miny" -// * InstantiationName/FooTest.HasBlahBlah/2 for "moe" -// -// You can use these names in --gtest_filter. -// -// This statement will instantiate all tests from FooTest again, each -// with parameter values "cat" and "dog": - -const char* pets[] = {"cat", "dog"}; -INSTANTIATE_TEST_CASE_P(AnotherInstantiationName, FooTest, ValuesIn(pets)); - -// The tests from the instantiation above will have these names: -// -// * AnotherInstantiationName/FooTest.DoesBlah/0 for "cat" -// * AnotherInstantiationName/FooTest.DoesBlah/1 for "dog" -// * AnotherInstantiationName/FooTest.HasBlahBlah/0 for "cat" -// * AnotherInstantiationName/FooTest.HasBlahBlah/1 for "dog" -// -// Please note that INSTANTIATE_TEST_CASE_P will instantiate all tests -// in the given test case, whether their definitions come before or -// AFTER the INSTANTIATE_TEST_CASE_P statement. -// -// Please also note that generator expressions (including parameters to the -// generators) are evaluated in InitGoogleTest(), after main() has started. -// This allows the user on one hand, to adjust generator parameters in order -// to dynamically determine a set of tests to run and on the other hand, -// give the user a chance to inspect the generated tests with Google Test -// reflection API before RUN_ALL_TESTS() is executed. -// -// You can see samples/sample7_unittest.cc and samples/sample8_unittest.cc -// for more examples. -// -// In the future, we plan to publish the API for defining new parameter -// generators. But for now this interface remains part of the internal -// implementation and is subject to change. -// -// -// A parameterized test fixture must be derived from testing::Test and from -// testing::WithParamInterface, where T is the type of the parameter -// values. Inheriting from TestWithParam satisfies that requirement because -// TestWithParam inherits from both Test and WithParamInterface. In more -// complicated hierarchies, however, it is occasionally useful to inherit -// separately from Test and WithParamInterface. For example: - -class BaseTest : public ::testing::Test { - // You can inherit all the usual members for a non-parameterized test - // fixture here. -}; - -class DerivedTest : public BaseTest, public ::testing::WithParamInterface { - // The usual test fixture members go here too. -}; - -TEST_F(BaseTest, HasFoo) { - // This is an ordinary non-parameterized test. -} - -TEST_P(DerivedTest, DoesBlah) { - // GetParam works just the same here as if you inherit from TestWithParam. - EXPECT_TRUE(foo.Blah(GetParam())); -} - -#endif // 0 - - -#if !GTEST_OS_SYMBIAN -# include -#endif - -// scripts/fuse_gtest.py depends on gtest's own header being #included -// *unconditionally*. Therefore these #includes cannot be moved -// inside #if GTEST_HAS_PARAM_TEST. -// Copyright 2008 Google Inc. -// All Rights Reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: vladl@google.com (Vlad Losev) - -// Type and function utilities for implementing parameterized tests. - -#ifndef GTEST_INCLUDE_GTEST_INTERNAL_GTEST_PARAM_UTIL_H_ -#define GTEST_INCLUDE_GTEST_INTERNAL_GTEST_PARAM_UTIL_H_ - -#include -#include -#include - -// scripts/fuse_gtest.py depends on gtest's own header being #included -// *unconditionally*. Therefore these #includes cannot be moved -// inside #if GTEST_HAS_PARAM_TEST. -// Copyright 2003 Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Authors: Dan Egnor (egnor@google.com) -// -// A "smart" pointer type with reference tracking. Every pointer to a -// particular object is kept on a circular linked list. When the last pointer -// to an object is destroyed or reassigned, the object is deleted. -// -// Used properly, this deletes the object when the last reference goes away. -// There are several caveats: -// - Like all reference counting schemes, cycles lead to leaks. -// - Each smart pointer is actually two pointers (8 bytes instead of 4). -// - Every time a pointer is assigned, the entire list of pointers to that -// object is traversed. This class is therefore NOT SUITABLE when there -// will often be more than two or three pointers to a particular object. -// - References are only tracked as long as linked_ptr<> objects are copied. -// If a linked_ptr<> is converted to a raw pointer and back, BAD THINGS -// will happen (double deletion). -// -// A good use of this class is storing object references in STL containers. -// You can safely put linked_ptr<> in a vector<>. -// Other uses may not be as good. -// -// Note: If you use an incomplete type with linked_ptr<>, the class -// *containing* linked_ptr<> must have a constructor and destructor (even -// if they do nothing!). -// -// Bill Gibbons suggested we use something like this. -// -// Thread Safety: -// Unlike other linked_ptr implementations, in this implementation -// a linked_ptr object is thread-safe in the sense that: -// - it's safe to copy linked_ptr objects concurrently, -// - it's safe to copy *from* a linked_ptr and read its underlying -// raw pointer (e.g. via get()) concurrently, and -// - it's safe to write to two linked_ptrs that point to the same -// shared object concurrently. -// TODO(wan@google.com): rename this to safe_linked_ptr to avoid -// confusion with normal linked_ptr. - -#ifndef GTEST_INCLUDE_GTEST_INTERNAL_GTEST_LINKED_PTR_H_ -#define GTEST_INCLUDE_GTEST_INTERNAL_GTEST_LINKED_PTR_H_ - -#include -#include - - -namespace testing { -namespace internal { - -// Protects copying of all linked_ptr objects. -GTEST_API_ GTEST_DECLARE_STATIC_MUTEX_(g_linked_ptr_mutex); - -// This is used internally by all instances of linked_ptr<>. It needs to be -// a non-template class because different types of linked_ptr<> can refer to -// the same object (linked_ptr(obj) vs linked_ptr(obj)). -// So, it needs to be possible for different types of linked_ptr to participate -// in the same circular linked list, so we need a single class type here. -// -// DO NOT USE THIS CLASS DIRECTLY YOURSELF. Use linked_ptr. -class linked_ptr_internal { - public: - // Create a new circle that includes only this instance. - void join_new() { - next_ = this; - } - - // Many linked_ptr operations may change p.link_ for some linked_ptr - // variable p in the same circle as this object. Therefore we need - // to prevent two such operations from occurring concurrently. - // - // Note that different types of linked_ptr objects can coexist in a - // circle (e.g. linked_ptr, linked_ptr, and - // linked_ptr). Therefore we must use a single mutex to - // protect all linked_ptr objects. This can create serious - // contention in production code, but is acceptable in a testing - // framework. - - // Join an existing circle. - void join(linked_ptr_internal const* ptr) - GTEST_LOCK_EXCLUDED_(g_linked_ptr_mutex) { - MutexLock lock(&g_linked_ptr_mutex); - - linked_ptr_internal const* p = ptr; - while (p->next_ != ptr) p = p->next_; - p->next_ = this; - next_ = ptr; - } - - // Leave whatever circle we're part of. Returns true if we were the - // last member of the circle. Once this is done, you can join() another. - bool depart() - GTEST_LOCK_EXCLUDED_(g_linked_ptr_mutex) { - MutexLock lock(&g_linked_ptr_mutex); - - if (next_ == this) return true; - linked_ptr_internal const* p = next_; - while (p->next_ != this) p = p->next_; - p->next_ = next_; - return false; - } - - private: - mutable linked_ptr_internal const* next_; -}; - -template -class linked_ptr { - public: - typedef T element_type; - - // Take over ownership of a raw pointer. This should happen as soon as - // possible after the object is created. - explicit linked_ptr(T* ptr = NULL) { capture(ptr); } - ~linked_ptr() { depart(); } - - // Copy an existing linked_ptr<>, adding ourselves to the list of references. - template linked_ptr(linked_ptr const& ptr) { copy(&ptr); } - linked_ptr(linked_ptr const& ptr) { // NOLINT - assert(&ptr != this); - copy(&ptr); - } - - // Assignment releases the old value and acquires the new. - template linked_ptr& operator=(linked_ptr const& ptr) { - depart(); - copy(&ptr); - return *this; - } - - linked_ptr& operator=(linked_ptr const& ptr) { - if (&ptr != this) { - depart(); - copy(&ptr); - } - return *this; - } - - // Smart pointer members. - void reset(T* ptr = NULL) { - depart(); - capture(ptr); - } - T* get() const { return value_; } - T* operator->() const { return value_; } - T& operator*() const { return *value_; } - - bool operator==(T* p) const { return value_ == p; } - bool operator!=(T* p) const { return value_ != p; } - template - bool operator==(linked_ptr const& ptr) const { - return value_ == ptr.get(); - } - template - bool operator!=(linked_ptr const& ptr) const { - return value_ != ptr.get(); - } - - private: - template - friend class linked_ptr; - - T* value_; - linked_ptr_internal link_; - - void depart() { - if (link_.depart()) delete value_; - } - - void capture(T* ptr) { - value_ = ptr; - link_.join_new(); - } - - template void copy(linked_ptr const* ptr) { - value_ = ptr->get(); - if (value_) - link_.join(&ptr->link_); - else - link_.join_new(); - } -}; - -template inline -bool operator==(T* ptr, const linked_ptr& x) { - return ptr == x.get(); -} - -template inline -bool operator!=(T* ptr, const linked_ptr& x) { - return ptr != x.get(); -} - -// A function to convert T* into linked_ptr -// Doing e.g. make_linked_ptr(new FooBarBaz(arg)) is a shorter notation -// for linked_ptr >(new FooBarBaz(arg)) -template -linked_ptr make_linked_ptr(T* ptr) { - return linked_ptr(ptr); -} - -} // namespace internal -} // namespace testing - -#endif // GTEST_INCLUDE_GTEST_INTERNAL_GTEST_LINKED_PTR_H_ -// Copyright 2007, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: wan@google.com (Zhanyong Wan) - -// Google Test - The Google C++ Testing Framework -// -// This file implements a universal value printer that can print a -// value of any type T: -// -// void ::testing::internal::UniversalPrinter::Print(value, ostream_ptr); -// -// A user can teach this function how to print a class type T by -// defining either operator<<() or PrintTo() in the namespace that -// defines T. More specifically, the FIRST defined function in the -// following list will be used (assuming T is defined in namespace -// foo): -// -// 1. foo::PrintTo(const T&, ostream*) -// 2. operator<<(ostream&, const T&) defined in either foo or the -// global namespace. -// -// If none of the above is defined, it will print the debug string of -// the value if it is a protocol buffer, or print the raw bytes in the -// value otherwise. -// -// To aid debugging: when T is a reference type, the address of the -// value is also printed; when T is a (const) char pointer, both the -// pointer value and the NUL-terminated string it points to are -// printed. -// -// We also provide some convenient wrappers: -// -// // Prints a value to a string. For a (const or not) char -// // pointer, the NUL-terminated string (but not the pointer) is -// // printed. -// std::string ::testing::PrintToString(const T& value); -// -// // Prints a value tersely: for a reference type, the referenced -// // value (but not the address) is printed; for a (const or not) char -// // pointer, the NUL-terminated string (but not the pointer) is -// // printed. -// void ::testing::internal::UniversalTersePrint(const T& value, ostream*); -// -// // Prints value using the type inferred by the compiler. The difference -// // from UniversalTersePrint() is that this function prints both the -// // pointer and the NUL-terminated string for a (const or not) char pointer. -// void ::testing::internal::UniversalPrint(const T& value, ostream*); -// -// // Prints the fields of a tuple tersely to a string vector, one -// // element for each field. Tuple support must be enabled in -// // gtest-port.h. -// std::vector UniversalTersePrintTupleFieldsToStrings( -// const Tuple& value); -// -// Known limitation: -// -// The print primitives print the elements of an STL-style container -// using the compiler-inferred type of *iter where iter is a -// const_iterator of the container. When const_iterator is an input -// iterator but not a forward iterator, this inferred type may not -// match value_type, and the print output may be incorrect. In -// practice, this is rarely a problem as for most containers -// const_iterator is a forward iterator. We'll fix this if there's an -// actual need for it. Note that this fix cannot rely on value_type -// being defined as many user-defined container types don't have -// value_type. - -#ifndef GTEST_INCLUDE_GTEST_GTEST_PRINTERS_H_ -#define GTEST_INCLUDE_GTEST_GTEST_PRINTERS_H_ - -#include // NOLINT -#include -#include -#include -#include - -namespace testing { - -// Definitions in the 'internal' and 'internal2' name spaces are -// subject to change without notice. DO NOT USE THEM IN USER CODE! -namespace internal2 { - -// Prints the given number of bytes in the given object to the given -// ostream. -GTEST_API_ void PrintBytesInObjectTo(const unsigned char* obj_bytes, - size_t count, - ::std::ostream* os); - -// For selecting which printer to use when a given type has neither << -// nor PrintTo(). -enum TypeKind { - kProtobuf, // a protobuf type - kConvertibleToInteger, // a type implicitly convertible to BiggestInt - // (e.g. a named or unnamed enum type) - kOtherType // anything else -}; - -// TypeWithoutFormatter::PrintValue(value, os) is called -// by the universal printer to print a value of type T when neither -// operator<< nor PrintTo() is defined for T, where kTypeKind is the -// "kind" of T as defined by enum TypeKind. -template -class TypeWithoutFormatter { - public: - // This default version is called when kTypeKind is kOtherType. - static void PrintValue(const T& value, ::std::ostream* os) { - PrintBytesInObjectTo(reinterpret_cast(&value), - sizeof(value), os); - } -}; - -// We print a protobuf using its ShortDebugString() when the string -// doesn't exceed this many characters; otherwise we print it using -// DebugString() for better readability. -const size_t kProtobufOneLinerMaxLength = 50; - -template -class TypeWithoutFormatter { - public: - static void PrintValue(const T& value, ::std::ostream* os) { - const ::testing::internal::string short_str = value.ShortDebugString(); - const ::testing::internal::string pretty_str = - short_str.length() <= kProtobufOneLinerMaxLength ? - short_str : ("\n" + value.DebugString()); - *os << ("<" + pretty_str + ">"); - } -}; - -template -class TypeWithoutFormatter { - public: - // Since T has no << operator or PrintTo() but can be implicitly - // converted to BiggestInt, we print it as a BiggestInt. - // - // Most likely T is an enum type (either named or unnamed), in which - // case printing it as an integer is the desired behavior. In case - // T is not an enum, printing it as an integer is the best we can do - // given that it has no user-defined printer. - static void PrintValue(const T& value, ::std::ostream* os) { - const internal::BiggestInt kBigInt = value; - *os << kBigInt; - } -}; - -// Prints the given value to the given ostream. If the value is a -// protocol message, its debug string is printed; if it's an enum or -// of a type implicitly convertible to BiggestInt, it's printed as an -// integer; otherwise the bytes in the value are printed. This is -// what UniversalPrinter::Print() does when it knows nothing about -// type T and T has neither << operator nor PrintTo(). -// -// A user can override this behavior for a class type Foo by defining -// a << operator in the namespace where Foo is defined. -// -// We put this operator in namespace 'internal2' instead of 'internal' -// to simplify the implementation, as much code in 'internal' needs to -// use << in STL, which would conflict with our own << were it defined -// in 'internal'. -// -// Note that this operator<< takes a generic std::basic_ostream type instead of the more restricted std::ostream. If -// we define it to take an std::ostream instead, we'll get an -// "ambiguous overloads" compiler error when trying to print a type -// Foo that supports streaming to std::basic_ostream, as the compiler cannot tell whether -// operator<<(std::ostream&, const T&) or -// operator<<(std::basic_stream, const Foo&) is more -// specific. -template -::std::basic_ostream& operator<<( - ::std::basic_ostream& os, const T& x) { - TypeWithoutFormatter::value ? kProtobuf : - internal::ImplicitlyConvertible::value ? - kConvertibleToInteger : kOtherType)>::PrintValue(x, &os); - return os; -} - -} // namespace internal2 -} // namespace testing - -// This namespace MUST NOT BE NESTED IN ::testing, or the name look-up -// magic needed for implementing UniversalPrinter won't work. -namespace testing_internal { - -// Used to print a value that is not an STL-style container when the -// user doesn't define PrintTo() for it. -template -void DefaultPrintNonContainerTo(const T& value, ::std::ostream* os) { - // With the following statement, during unqualified name lookup, - // testing::internal2::operator<< appears as if it was declared in - // the nearest enclosing namespace that contains both - // ::testing_internal and ::testing::internal2, i.e. the global - // namespace. For more details, refer to the C++ Standard section - // 7.3.4-1 [namespace.udir]. This allows us to fall back onto - // testing::internal2::operator<< in case T doesn't come with a << - // operator. - // - // We cannot write 'using ::testing::internal2::operator<<;', which - // gcc 3.3 fails to compile due to a compiler bug. - using namespace ::testing::internal2; // NOLINT - - // Assuming T is defined in namespace foo, in the next statement, - // the compiler will consider all of: - // - // 1. foo::operator<< (thanks to Koenig look-up), - // 2. ::operator<< (as the current namespace is enclosed in ::), - // 3. testing::internal2::operator<< (thanks to the using statement above). - // - // The operator<< whose type matches T best will be picked. - // - // We deliberately allow #2 to be a candidate, as sometimes it's - // impossible to define #1 (e.g. when foo is ::std, defining - // anything in it is undefined behavior unless you are a compiler - // vendor.). - *os << value; -} - -} // namespace testing_internal - -namespace testing { -namespace internal { - -// UniversalPrinter::Print(value, ostream_ptr) prints the given -// value to the given ostream. The caller must ensure that -// 'ostream_ptr' is not NULL, or the behavior is undefined. -// -// We define UniversalPrinter as a class template (as opposed to a -// function template), as we need to partially specialize it for -// reference types, which cannot be done with function templates. -template -class UniversalPrinter; - -template -void UniversalPrint(const T& value, ::std::ostream* os); - -// Used to print an STL-style container when the user doesn't define -// a PrintTo() for it. -template -void DefaultPrintTo(IsContainer /* dummy */, - false_type /* is not a pointer */, - const C& container, ::std::ostream* os) { - const size_t kMaxCount = 32; // The maximum number of elements to print. - *os << '{'; - size_t count = 0; - for (typename C::const_iterator it = container.begin(); - it != container.end(); ++it, ++count) { - if (count > 0) { - *os << ','; - if (count == kMaxCount) { // Enough has been printed. - *os << " ..."; - break; - } - } - *os << ' '; - // We cannot call PrintTo(*it, os) here as PrintTo() doesn't - // handle *it being a native array. - internal::UniversalPrint(*it, os); - } - - if (count > 0) { - *os << ' '; - } - *os << '}'; -} - -// Used to print a pointer that is neither a char pointer nor a member -// pointer, when the user doesn't define PrintTo() for it. (A member -// variable pointer or member function pointer doesn't really point to -// a location in the address space. Their representation is -// implementation-defined. Therefore they will be printed as raw -// bytes.) -template -void DefaultPrintTo(IsNotContainer /* dummy */, - true_type /* is a pointer */, - T* p, ::std::ostream* os) { - if (p == NULL) { - *os << "NULL"; - } else { - // C++ doesn't allow casting from a function pointer to any object - // pointer. - // - // IsTrue() silences warnings: "Condition is always true", - // "unreachable code". - if (IsTrue(ImplicitlyConvertible::value)) { - // T is not a function type. We just call << to print p, - // relying on ADL to pick up user-defined << for their pointer - // types, if any. - *os << p; - } else { - // T is a function type, so '*os << p' doesn't do what we want - // (it just prints p as bool). We want to print p as a const - // void*. However, we cannot cast it to const void* directly, - // even using reinterpret_cast, as earlier versions of gcc - // (e.g. 3.4.5) cannot compile the cast when p is a function - // pointer. Casting to UInt64 first solves the problem. - *os << reinterpret_cast( - reinterpret_cast(p)); - } - } -} - -// Used to print a non-container, non-pointer value when the user -// doesn't define PrintTo() for it. -template -void DefaultPrintTo(IsNotContainer /* dummy */, - false_type /* is not a pointer */, - const T& value, ::std::ostream* os) { - ::testing_internal::DefaultPrintNonContainerTo(value, os); -} - -// Prints the given value using the << operator if it has one; -// otherwise prints the bytes in it. This is what -// UniversalPrinter::Print() does when PrintTo() is not specialized -// or overloaded for type T. -// -// A user can override this behavior for a class type Foo by defining -// an overload of PrintTo() in the namespace where Foo is defined. We -// give the user this option as sometimes defining a << operator for -// Foo is not desirable (e.g. the coding style may prevent doing it, -// or there is already a << operator but it doesn't do what the user -// wants). -template -void PrintTo(const T& value, ::std::ostream* os) { - // DefaultPrintTo() is overloaded. The type of its first two - // arguments determine which version will be picked. If T is an - // STL-style container, the version for container will be called; if - // T is a pointer, the pointer version will be called; otherwise the - // generic version will be called. - // - // Note that we check for container types here, prior to we check - // for protocol message types in our operator<<. The rationale is: - // - // For protocol messages, we want to give people a chance to - // override Google Mock's format by defining a PrintTo() or - // operator<<. For STL containers, other formats can be - // incompatible with Google Mock's format for the container - // elements; therefore we check for container types here to ensure - // that our format is used. - // - // The second argument of DefaultPrintTo() is needed to bypass a bug - // in Symbian's C++ compiler that prevents it from picking the right - // overload between: - // - // PrintTo(const T& x, ...); - // PrintTo(T* x, ...); - DefaultPrintTo(IsContainerTest(0), is_pointer(), value, os); -} - -// The following list of PrintTo() overloads tells -// UniversalPrinter::Print() how to print standard types (built-in -// types, strings, plain arrays, and pointers). - -// Overloads for various char types. -GTEST_API_ void PrintTo(unsigned char c, ::std::ostream* os); -GTEST_API_ void PrintTo(signed char c, ::std::ostream* os); -inline void PrintTo(char c, ::std::ostream* os) { - // When printing a plain char, we always treat it as unsigned. This - // way, the output won't be affected by whether the compiler thinks - // char is signed or not. - PrintTo(static_cast(c), os); -} - -// Overloads for other simple built-in types. -inline void PrintTo(bool x, ::std::ostream* os) { - *os << (x ? "true" : "false"); -} - -// Overload for wchar_t type. -// Prints a wchar_t as a symbol if it is printable or as its internal -// code otherwise and also as its decimal code (except for L'\0'). -// The L'\0' char is printed as "L'\\0'". The decimal code is printed -// as signed integer when wchar_t is implemented by the compiler -// as a signed type and is printed as an unsigned integer when wchar_t -// is implemented as an unsigned type. -GTEST_API_ void PrintTo(wchar_t wc, ::std::ostream* os); - -// Overloads for C strings. -GTEST_API_ void PrintTo(const char* s, ::std::ostream* os); -inline void PrintTo(char* s, ::std::ostream* os) { - PrintTo(ImplicitCast_(s), os); -} - -// signed/unsigned char is often used for representing binary data, so -// we print pointers to it as void* to be safe. -inline void PrintTo(const signed char* s, ::std::ostream* os) { - PrintTo(ImplicitCast_(s), os); -} -inline void PrintTo(signed char* s, ::std::ostream* os) { - PrintTo(ImplicitCast_(s), os); -} -inline void PrintTo(const unsigned char* s, ::std::ostream* os) { - PrintTo(ImplicitCast_(s), os); -} -inline void PrintTo(unsigned char* s, ::std::ostream* os) { - PrintTo(ImplicitCast_(s), os); -} - -// MSVC can be configured to define wchar_t as a typedef of unsigned -// short. It defines _NATIVE_WCHAR_T_DEFINED when wchar_t is a native -// type. When wchar_t is a typedef, defining an overload for const -// wchar_t* would cause unsigned short* be printed as a wide string, -// possibly causing invalid memory accesses. -#if !defined(_MSC_VER) || defined(_NATIVE_WCHAR_T_DEFINED) -// Overloads for wide C strings -GTEST_API_ void PrintTo(const wchar_t* s, ::std::ostream* os); -inline void PrintTo(wchar_t* s, ::std::ostream* os) { - PrintTo(ImplicitCast_(s), os); -} -#endif - -// Overload for C arrays. Multi-dimensional arrays are printed -// properly. - -// Prints the given number of elements in an array, without printing -// the curly braces. -template -void PrintRawArrayTo(const T a[], size_t count, ::std::ostream* os) { - UniversalPrint(a[0], os); - for (size_t i = 1; i != count; i++) { - *os << ", "; - UniversalPrint(a[i], os); - } -} - -// Overloads for ::string and ::std::string. -#if GTEST_HAS_GLOBAL_STRING -GTEST_API_ void PrintStringTo(const ::string&s, ::std::ostream* os); -inline void PrintTo(const ::string& s, ::std::ostream* os) { - PrintStringTo(s, os); -} -#endif // GTEST_HAS_GLOBAL_STRING - -GTEST_API_ void PrintStringTo(const ::std::string&s, ::std::ostream* os); -inline void PrintTo(const ::std::string& s, ::std::ostream* os) { - PrintStringTo(s, os); -} - -// Overloads for ::wstring and ::std::wstring. -#if GTEST_HAS_GLOBAL_WSTRING -GTEST_API_ void PrintWideStringTo(const ::wstring&s, ::std::ostream* os); -inline void PrintTo(const ::wstring& s, ::std::ostream* os) { - PrintWideStringTo(s, os); -} -#endif // GTEST_HAS_GLOBAL_WSTRING - -#if GTEST_HAS_STD_WSTRING -GTEST_API_ void PrintWideStringTo(const ::std::wstring&s, ::std::ostream* os); -inline void PrintTo(const ::std::wstring& s, ::std::ostream* os) { - PrintWideStringTo(s, os); -} -#endif // GTEST_HAS_STD_WSTRING - -#if GTEST_HAS_TR1_TUPLE -// Overload for ::std::tr1::tuple. Needed for printing function arguments, -// which are packed as tuples. - -// Helper function for printing a tuple. T must be instantiated with -// a tuple type. -template -void PrintTupleTo(const T& t, ::std::ostream* os); - -// Overloaded PrintTo() for tuples of various arities. We support -// tuples of up-to 10 fields. The following implementation works -// regardless of whether tr1::tuple is implemented using the -// non-standard variadic template feature or not. - -inline void PrintTo(const ::std::tr1::tuple<>& t, ::std::ostream* os) { - PrintTupleTo(t, os); -} - -template -void PrintTo(const ::std::tr1::tuple& t, ::std::ostream* os) { - PrintTupleTo(t, os); -} - -template -void PrintTo(const ::std::tr1::tuple& t, ::std::ostream* os) { - PrintTupleTo(t, os); -} - -template -void PrintTo(const ::std::tr1::tuple& t, ::std::ostream* os) { - PrintTupleTo(t, os); -} - -template -void PrintTo(const ::std::tr1::tuple& t, ::std::ostream* os) { - PrintTupleTo(t, os); -} - -template -void PrintTo(const ::std::tr1::tuple& t, - ::std::ostream* os) { - PrintTupleTo(t, os); -} - -template -void PrintTo(const ::std::tr1::tuple& t, - ::std::ostream* os) { - PrintTupleTo(t, os); -} - -template -void PrintTo(const ::std::tr1::tuple& t, - ::std::ostream* os) { - PrintTupleTo(t, os); -} - -template -void PrintTo(const ::std::tr1::tuple& t, - ::std::ostream* os) { - PrintTupleTo(t, os); -} - -template -void PrintTo(const ::std::tr1::tuple& t, - ::std::ostream* os) { - PrintTupleTo(t, os); -} - -template -void PrintTo( - const ::std::tr1::tuple& t, - ::std::ostream* os) { - PrintTupleTo(t, os); -} -#endif // GTEST_HAS_TR1_TUPLE - -// Overload for std::pair. -template -void PrintTo(const ::std::pair& value, ::std::ostream* os) { - *os << '('; - // We cannot use UniversalPrint(value.first, os) here, as T1 may be - // a reference type. The same for printing value.second. - UniversalPrinter::Print(value.first, os); - *os << ", "; - UniversalPrinter::Print(value.second, os); - *os << ')'; -} - -// Implements printing a non-reference type T by letting the compiler -// pick the right overload of PrintTo() for T. -template -class UniversalPrinter { - public: - // MSVC warns about adding const to a function type, so we want to - // disable the warning. -#ifdef _MSC_VER -# pragma warning(push) // Saves the current warning state. -# pragma warning(disable:4180) // Temporarily disables warning 4180. -#endif // _MSC_VER - - // Note: we deliberately don't call this PrintTo(), as that name - // conflicts with ::testing::internal::PrintTo in the body of the - // function. - static void Print(const T& value, ::std::ostream* os) { - // By default, ::testing::internal::PrintTo() is used for printing - // the value. - // - // Thanks to Koenig look-up, if T is a class and has its own - // PrintTo() function defined in its namespace, that function will - // be visible here. Since it is more specific than the generic ones - // in ::testing::internal, it will be picked by the compiler in the - // following statement - exactly what we want. - PrintTo(value, os); - } - -#ifdef _MSC_VER -# pragma warning(pop) // Restores the warning state. -#endif // _MSC_VER -}; - -// UniversalPrintArray(begin, len, os) prints an array of 'len' -// elements, starting at address 'begin'. -template -void UniversalPrintArray(const T* begin, size_t len, ::std::ostream* os) { - if (len == 0) { - *os << "{}"; - } else { - *os << "{ "; - const size_t kThreshold = 18; - const size_t kChunkSize = 8; - // If the array has more than kThreshold elements, we'll have to - // omit some details by printing only the first and the last - // kChunkSize elements. - // TODO(wan@google.com): let the user control the threshold using a flag. - if (len <= kThreshold) { - PrintRawArrayTo(begin, len, os); - } else { - PrintRawArrayTo(begin, kChunkSize, os); - *os << ", ..., "; - PrintRawArrayTo(begin + len - kChunkSize, kChunkSize, os); - } - *os << " }"; - } -} -// This overload prints a (const) char array compactly. -GTEST_API_ void UniversalPrintArray( - const char* begin, size_t len, ::std::ostream* os); - -// This overload prints a (const) wchar_t array compactly. -GTEST_API_ void UniversalPrintArray( - const wchar_t* begin, size_t len, ::std::ostream* os); - -// Implements printing an array type T[N]. -template -class UniversalPrinter { - public: - // Prints the given array, omitting some elements when there are too - // many. - static void Print(const T (&a)[N], ::std::ostream* os) { - UniversalPrintArray(a, N, os); - } -}; - -// Implements printing a reference type T&. -template -class UniversalPrinter { - public: - // MSVC warns about adding const to a function type, so we want to - // disable the warning. -#ifdef _MSC_VER -# pragma warning(push) // Saves the current warning state. -# pragma warning(disable:4180) // Temporarily disables warning 4180. -#endif // _MSC_VER - - static void Print(const T& value, ::std::ostream* os) { - // Prints the address of the value. We use reinterpret_cast here - // as static_cast doesn't compile when T is a function type. - *os << "@" << reinterpret_cast(&value) << " "; - - // Then prints the value itself. - UniversalPrint(value, os); - } - -#ifdef _MSC_VER -# pragma warning(pop) // Restores the warning state. -#endif // _MSC_VER -}; - -// Prints a value tersely: for a reference type, the referenced value -// (but not the address) is printed; for a (const) char pointer, the -// NUL-terminated string (but not the pointer) is printed. - -template -class UniversalTersePrinter { - public: - static void Print(const T& value, ::std::ostream* os) { - UniversalPrint(value, os); - } -}; -template -class UniversalTersePrinter { - public: - static void Print(const T& value, ::std::ostream* os) { - UniversalPrint(value, os); - } -}; -template -class UniversalTersePrinter { - public: - static void Print(const T (&value)[N], ::std::ostream* os) { - UniversalPrinter::Print(value, os); - } -}; -template <> -class UniversalTersePrinter { - public: - static void Print(const char* str, ::std::ostream* os) { - if (str == NULL) { - *os << "NULL"; - } else { - UniversalPrint(string(str), os); - } - } -}; -template <> -class UniversalTersePrinter { - public: - static void Print(char* str, ::std::ostream* os) { - UniversalTersePrinter::Print(str, os); - } -}; - -#if GTEST_HAS_STD_WSTRING -template <> -class UniversalTersePrinter { - public: - static void Print(const wchar_t* str, ::std::ostream* os) { - if (str == NULL) { - *os << "NULL"; - } else { - UniversalPrint(::std::wstring(str), os); - } - } -}; -#endif - -template <> -class UniversalTersePrinter { - public: - static void Print(wchar_t* str, ::std::ostream* os) { - UniversalTersePrinter::Print(str, os); - } -}; - -template -void UniversalTersePrint(const T& value, ::std::ostream* os) { - UniversalTersePrinter::Print(value, os); -} - -// Prints a value using the type inferred by the compiler. The -// difference between this and UniversalTersePrint() is that for a -// (const) char pointer, this prints both the pointer and the -// NUL-terminated string. -template -void UniversalPrint(const T& value, ::std::ostream* os) { - // A workarond for the bug in VC++ 7.1 that prevents us from instantiating - // UniversalPrinter with T directly. - typedef T T1; - UniversalPrinter::Print(value, os); -} - -#if GTEST_HAS_TR1_TUPLE -typedef ::std::vector Strings; - -// This helper template allows PrintTo() for tuples and -// UniversalTersePrintTupleFieldsToStrings() to be defined by -// induction on the number of tuple fields. The idea is that -// TuplePrefixPrinter::PrintPrefixTo(t, os) prints the first N -// fields in tuple t, and can be defined in terms of -// TuplePrefixPrinter. - -// The inductive case. -template -struct TuplePrefixPrinter { - // Prints the first N fields of a tuple. - template - static void PrintPrefixTo(const Tuple& t, ::std::ostream* os) { - TuplePrefixPrinter::PrintPrefixTo(t, os); - *os << ", "; - UniversalPrinter::type> - ::Print(::std::tr1::get(t), os); - } - - // Tersely prints the first N fields of a tuple to a string vector, - // one element for each field. - template - static void TersePrintPrefixToStrings(const Tuple& t, Strings* strings) { - TuplePrefixPrinter::TersePrintPrefixToStrings(t, strings); - ::std::stringstream ss; - UniversalTersePrint(::std::tr1::get(t), &ss); - strings->push_back(ss.str()); - } -}; - -// Base cases. -template <> -struct TuplePrefixPrinter<0> { - template - static void PrintPrefixTo(const Tuple&, ::std::ostream*) {} - - template - static void TersePrintPrefixToStrings(const Tuple&, Strings*) {} -}; -// We have to specialize the entire TuplePrefixPrinter<> class -// template here, even though the definition of -// TersePrintPrefixToStrings() is the same as the generic version, as -// Embarcadero (formerly CodeGear, formerly Borland) C++ doesn't -// support specializing a method template of a class template. -template <> -struct TuplePrefixPrinter<1> { - template - static void PrintPrefixTo(const Tuple& t, ::std::ostream* os) { - UniversalPrinter::type>:: - Print(::std::tr1::get<0>(t), os); - } - - template - static void TersePrintPrefixToStrings(const Tuple& t, Strings* strings) { - ::std::stringstream ss; - UniversalTersePrint(::std::tr1::get<0>(t), &ss); - strings->push_back(ss.str()); - } -}; - -// Helper function for printing a tuple. T must be instantiated with -// a tuple type. -template -void PrintTupleTo(const T& t, ::std::ostream* os) { - *os << "("; - TuplePrefixPrinter< ::std::tr1::tuple_size::value>:: - PrintPrefixTo(t, os); - *os << ")"; -} - -// Prints the fields of a tuple tersely to a string vector, one -// element for each field. See the comment before -// UniversalTersePrint() for how we define "tersely". -template -Strings UniversalTersePrintTupleFieldsToStrings(const Tuple& value) { - Strings result; - TuplePrefixPrinter< ::std::tr1::tuple_size::value>:: - TersePrintPrefixToStrings(value, &result); - return result; -} -#endif // GTEST_HAS_TR1_TUPLE - -} // namespace internal - -template -::std::string PrintToString(const T& value) { - ::std::stringstream ss; - internal::UniversalTersePrinter::Print(value, &ss); - return ss.str(); -} - -} // namespace testing - -#endif // GTEST_INCLUDE_GTEST_GTEST_PRINTERS_H_ - -#if GTEST_HAS_PARAM_TEST - -namespace testing { -namespace internal { - -// INTERNAL IMPLEMENTATION - DO NOT USE IN USER CODE. -// -// Outputs a message explaining invalid registration of different -// fixture class for the same test case. This may happen when -// TEST_P macro is used to define two tests with the same name -// but in different namespaces. -GTEST_API_ void ReportInvalidTestCaseType(const char* test_case_name, - const char* file, int line); - -template class ParamGeneratorInterface; -template class ParamGenerator; - -// Interface for iterating over elements provided by an implementation -// of ParamGeneratorInterface. -template -class ParamIteratorInterface { - public: - virtual ~ParamIteratorInterface() {} - // A pointer to the base generator instance. - // Used only for the purposes of iterator comparison - // to make sure that two iterators belong to the same generator. - virtual const ParamGeneratorInterface* BaseGenerator() const = 0; - // Advances iterator to point to the next element - // provided by the generator. The caller is responsible - // for not calling Advance() on an iterator equal to - // BaseGenerator()->End(). - virtual void Advance() = 0; - // Clones the iterator object. Used for implementing copy semantics - // of ParamIterator. - virtual ParamIteratorInterface* Clone() const = 0; - // Dereferences the current iterator and provides (read-only) access - // to the pointed value. It is the caller's responsibility not to call - // Current() on an iterator equal to BaseGenerator()->End(). - // Used for implementing ParamGenerator::operator*(). - virtual const T* Current() const = 0; - // Determines whether the given iterator and other point to the same - // element in the sequence generated by the generator. - // Used for implementing ParamGenerator::operator==(). - virtual bool Equals(const ParamIteratorInterface& other) const = 0; -}; - -// Class iterating over elements provided by an implementation of -// ParamGeneratorInterface. It wraps ParamIteratorInterface -// and implements the const forward iterator concept. -template -class ParamIterator { - public: - typedef T value_type; - typedef const T& reference; - typedef ptrdiff_t difference_type; - - // ParamIterator assumes ownership of the impl_ pointer. - ParamIterator(const ParamIterator& other) : impl_(other.impl_->Clone()) {} - ParamIterator& operator=(const ParamIterator& other) { - if (this != &other) - impl_.reset(other.impl_->Clone()); - return *this; - } - - const T& operator*() const { return *impl_->Current(); } - const T* operator->() const { return impl_->Current(); } - // Prefix version of operator++. - ParamIterator& operator++() { - impl_->Advance(); - return *this; - } - // Postfix version of operator++. - ParamIterator operator++(int /*unused*/) { - ParamIteratorInterface* clone = impl_->Clone(); - impl_->Advance(); - return ParamIterator(clone); - } - bool operator==(const ParamIterator& other) const { - return impl_.get() == other.impl_.get() || impl_->Equals(*other.impl_); - } - bool operator!=(const ParamIterator& other) const { - return !(*this == other); - } - - private: - friend class ParamGenerator; - explicit ParamIterator(ParamIteratorInterface* impl) : impl_(impl) {} - scoped_ptr > impl_; -}; - -// ParamGeneratorInterface is the binary interface to access generators -// defined in other translation units. -template -class ParamGeneratorInterface { - public: - typedef T ParamType; - - virtual ~ParamGeneratorInterface() {} - - // Generator interface definition - virtual ParamIteratorInterface* Begin() const = 0; - virtual ParamIteratorInterface* End() const = 0; -}; - -// Wraps ParamGeneratorInterface and provides general generator syntax -// compatible with the STL Container concept. -// This class implements copy initialization semantics and the contained -// ParamGeneratorInterface instance is shared among all copies -// of the original object. This is possible because that instance is immutable. -template -class ParamGenerator { - public: - typedef ParamIterator iterator; - - explicit ParamGenerator(ParamGeneratorInterface* impl) : impl_(impl) {} - ParamGenerator(const ParamGenerator& other) : impl_(other.impl_) {} - - ParamGenerator& operator=(const ParamGenerator& other) { - impl_ = other.impl_; - return *this; - } - - iterator begin() const { return iterator(impl_->Begin()); } - iterator end() const { return iterator(impl_->End()); } - - private: - linked_ptr > impl_; -}; - -// Generates values from a range of two comparable values. Can be used to -// generate sequences of user-defined types that implement operator+() and -// operator<(). -// This class is used in the Range() function. -template -class RangeGenerator : public ParamGeneratorInterface { - public: - RangeGenerator(T begin, T end, IncrementT step) - : begin_(begin), end_(end), - step_(step), end_index_(CalculateEndIndex(begin, end, step)) {} - virtual ~RangeGenerator() {} - - virtual ParamIteratorInterface* Begin() const { - return new Iterator(this, begin_, 0, step_); - } - virtual ParamIteratorInterface* End() const { - return new Iterator(this, end_, end_index_, step_); - } - - private: - class Iterator : public ParamIteratorInterface { - public: - Iterator(const ParamGeneratorInterface* base, T value, int index, - IncrementT step) - : base_(base), value_(value), index_(index), step_(step) {} - virtual ~Iterator() {} - - virtual const ParamGeneratorInterface* BaseGenerator() const { - return base_; - } - virtual void Advance() { - value_ = value_ + step_; - index_++; - } - virtual ParamIteratorInterface* Clone() const { - return new Iterator(*this); - } - virtual const T* Current() const { return &value_; } - virtual bool Equals(const ParamIteratorInterface& other) const { - // Having the same base generator guarantees that the other - // iterator is of the same type and we can downcast. - GTEST_CHECK_(BaseGenerator() == other.BaseGenerator()) - << "The program attempted to compare iterators " - << "from different generators." << std::endl; - const int other_index = - CheckedDowncastToActualType(&other)->index_; - return index_ == other_index; - } - - private: - Iterator(const Iterator& other) - : ParamIteratorInterface(), - base_(other.base_), value_(other.value_), index_(other.index_), - step_(other.step_) {} - - // No implementation - assignment is unsupported. - void operator=(const Iterator& other); - - const ParamGeneratorInterface* const base_; - T value_; - int index_; - const IncrementT step_; - }; // class RangeGenerator::Iterator - - static int CalculateEndIndex(const T& begin, - const T& end, - const IncrementT& step) { - int end_index = 0; - for (T i = begin; i < end; i = i + step) - end_index++; - return end_index; - } - - // No implementation - assignment is unsupported. - void operator=(const RangeGenerator& other); - - const T begin_; - const T end_; - const IncrementT step_; - // The index for the end() iterator. All the elements in the generated - // sequence are indexed (0-based) to aid iterator comparison. - const int end_index_; -}; // class RangeGenerator - - -// Generates values from a pair of STL-style iterators. Used in the -// ValuesIn() function. The elements are copied from the source range -// since the source can be located on the stack, and the generator -// is likely to persist beyond that stack frame. -template -class ValuesInIteratorRangeGenerator : public ParamGeneratorInterface { - public: - template - ValuesInIteratorRangeGenerator(ForwardIterator begin, ForwardIterator end) - : container_(begin, end) {} - virtual ~ValuesInIteratorRangeGenerator() {} - - virtual ParamIteratorInterface* Begin() const { - return new Iterator(this, container_.begin()); - } - virtual ParamIteratorInterface* End() const { - return new Iterator(this, container_.end()); - } - - private: - typedef typename ::std::vector ContainerType; - - class Iterator : public ParamIteratorInterface { - public: - Iterator(const ParamGeneratorInterface* base, - typename ContainerType::const_iterator iterator) - : base_(base), iterator_(iterator) {} - virtual ~Iterator() {} - - virtual const ParamGeneratorInterface* BaseGenerator() const { - return base_; - } - virtual void Advance() { - ++iterator_; - value_.reset(); - } - virtual ParamIteratorInterface* Clone() const { - return new Iterator(*this); - } - // We need to use cached value referenced by iterator_ because *iterator_ - // can return a temporary object (and of type other then T), so just - // having "return &*iterator_;" doesn't work. - // value_ is updated here and not in Advance() because Advance() - // can advance iterator_ beyond the end of the range, and we cannot - // detect that fact. The client code, on the other hand, is - // responsible for not calling Current() on an out-of-range iterator. - virtual const T* Current() const { - if (value_.get() == NULL) - value_.reset(new T(*iterator_)); - return value_.get(); - } - virtual bool Equals(const ParamIteratorInterface& other) const { - // Having the same base generator guarantees that the other - // iterator is of the same type and we can downcast. - GTEST_CHECK_(BaseGenerator() == other.BaseGenerator()) - << "The program attempted to compare iterators " - << "from different generators." << std::endl; - return iterator_ == - CheckedDowncastToActualType(&other)->iterator_; - } - - private: - Iterator(const Iterator& other) - // The explicit constructor call suppresses a false warning - // emitted by gcc when supplied with the -Wextra option. - : ParamIteratorInterface(), - base_(other.base_), - iterator_(other.iterator_) {} - - const ParamGeneratorInterface* const base_; - typename ContainerType::const_iterator iterator_; - // A cached value of *iterator_. We keep it here to allow access by - // pointer in the wrapping iterator's operator->(). - // value_ needs to be mutable to be accessed in Current(). - // Use of scoped_ptr helps manage cached value's lifetime, - // which is bound by the lifespan of the iterator itself. - mutable scoped_ptr value_; - }; // class ValuesInIteratorRangeGenerator::Iterator - - // No implementation - assignment is unsupported. - void operator=(const ValuesInIteratorRangeGenerator& other); - - const ContainerType container_; -}; // class ValuesInIteratorRangeGenerator - -// INTERNAL IMPLEMENTATION - DO NOT USE IN USER CODE. -// -// Stores a parameter value and later creates tests parameterized with that -// value. -template -class ParameterizedTestFactory : public TestFactoryBase { - public: - typedef typename TestClass::ParamType ParamType; - explicit ParameterizedTestFactory(ParamType parameter) : - parameter_(parameter) {} - virtual Test* CreateTest() { - TestClass::SetParam(¶meter_); - return new TestClass(); - } - - private: - const ParamType parameter_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(ParameterizedTestFactory); -}; - -// INTERNAL IMPLEMENTATION - DO NOT USE IN USER CODE. -// -// TestMetaFactoryBase is a base class for meta-factories that create -// test factories for passing into MakeAndRegisterTestInfo function. -template -class TestMetaFactoryBase { - public: - virtual ~TestMetaFactoryBase() {} - - virtual TestFactoryBase* CreateTestFactory(ParamType parameter) = 0; -}; - -// INTERNAL IMPLEMENTATION - DO NOT USE IN USER CODE. -// -// TestMetaFactory creates test factories for passing into -// MakeAndRegisterTestInfo function. Since MakeAndRegisterTestInfo receives -// ownership of test factory pointer, same factory object cannot be passed -// into that method twice. But ParameterizedTestCaseInfo is going to call -// it for each Test/Parameter value combination. Thus it needs meta factory -// creator class. -template -class TestMetaFactory - : public TestMetaFactoryBase { - public: - typedef typename TestCase::ParamType ParamType; - - TestMetaFactory() {} - - virtual TestFactoryBase* CreateTestFactory(ParamType parameter) { - return new ParameterizedTestFactory(parameter); - } - - private: - GTEST_DISALLOW_COPY_AND_ASSIGN_(TestMetaFactory); -}; - -// INTERNAL IMPLEMENTATION - DO NOT USE IN USER CODE. -// -// ParameterizedTestCaseInfoBase is a generic interface -// to ParameterizedTestCaseInfo classes. ParameterizedTestCaseInfoBase -// accumulates test information provided by TEST_P macro invocations -// and generators provided by INSTANTIATE_TEST_CASE_P macro invocations -// and uses that information to register all resulting test instances -// in RegisterTests method. The ParameterizeTestCaseRegistry class holds -// a collection of pointers to the ParameterizedTestCaseInfo objects -// and calls RegisterTests() on each of them when asked. -class ParameterizedTestCaseInfoBase { - public: - virtual ~ParameterizedTestCaseInfoBase() {} - - // Base part of test case name for display purposes. - virtual const string& GetTestCaseName() const = 0; - // Test case id to verify identity. - virtual TypeId GetTestCaseTypeId() const = 0; - // UnitTest class invokes this method to register tests in this - // test case right before running them in RUN_ALL_TESTS macro. - // This method should not be called more then once on any single - // instance of a ParameterizedTestCaseInfoBase derived class. - virtual void RegisterTests() = 0; - - protected: - ParameterizedTestCaseInfoBase() {} - - private: - GTEST_DISALLOW_COPY_AND_ASSIGN_(ParameterizedTestCaseInfoBase); -}; - -// INTERNAL IMPLEMENTATION - DO NOT USE IN USER CODE. -// -// ParameterizedTestCaseInfo accumulates tests obtained from TEST_P -// macro invocations for a particular test case and generators -// obtained from INSTANTIATE_TEST_CASE_P macro invocations for that -// test case. It registers tests with all values generated by all -// generators when asked. -template -class ParameterizedTestCaseInfo : public ParameterizedTestCaseInfoBase { - public: - // ParamType and GeneratorCreationFunc are private types but are required - // for declarations of public methods AddTestPattern() and - // AddTestCaseInstantiation(). - typedef typename TestCase::ParamType ParamType; - // A function that returns an instance of appropriate generator type. - typedef ParamGenerator(GeneratorCreationFunc)(); - - explicit ParameterizedTestCaseInfo(const char* name) - : test_case_name_(name) {} - - // Test case base name for display purposes. - virtual const string& GetTestCaseName() const { return test_case_name_; } - // Test case id to verify identity. - virtual TypeId GetTestCaseTypeId() const { return GetTypeId(); } - // TEST_P macro uses AddTestPattern() to record information - // about a single test in a LocalTestInfo structure. - // test_case_name is the base name of the test case (without invocation - // prefix). test_base_name is the name of an individual test without - // parameter index. For the test SequenceA/FooTest.DoBar/1 FooTest is - // test case base name and DoBar is test base name. - void AddTestPattern(const char* test_case_name, - const char* test_base_name, - TestMetaFactoryBase* meta_factory) { - tests_.push_back(linked_ptr(new TestInfo(test_case_name, - test_base_name, - meta_factory))); - } - // INSTANTIATE_TEST_CASE_P macro uses AddGenerator() to record information - // about a generator. - int AddTestCaseInstantiation(const string& instantiation_name, - GeneratorCreationFunc* func, - const char* /* file */, - int /* line */) { - instantiations_.push_back(::std::make_pair(instantiation_name, func)); - return 0; // Return value used only to run this method in namespace scope. - } - // UnitTest class invokes this method to register tests in this test case - // test cases right before running tests in RUN_ALL_TESTS macro. - // This method should not be called more then once on any single - // instance of a ParameterizedTestCaseInfoBase derived class. - // UnitTest has a guard to prevent from calling this method more then once. - virtual void RegisterTests() { - for (typename TestInfoContainer::iterator test_it = tests_.begin(); - test_it != tests_.end(); ++test_it) { - linked_ptr test_info = *test_it; - for (typename InstantiationContainer::iterator gen_it = - instantiations_.begin(); gen_it != instantiations_.end(); - ++gen_it) { - const string& instantiation_name = gen_it->first; - ParamGenerator generator((*gen_it->second)()); - - string test_case_name; - if ( !instantiation_name.empty() ) - test_case_name = instantiation_name + "/"; - test_case_name += test_info->test_case_base_name; - - int i = 0; - for (typename ParamGenerator::iterator param_it = - generator.begin(); - param_it != generator.end(); ++param_it, ++i) { - Message test_name_stream; - test_name_stream << test_info->test_base_name << "/" << i; - MakeAndRegisterTestInfo( - test_case_name.c_str(), - test_name_stream.GetString().c_str(), - NULL, // No type parameter. - PrintToString(*param_it).c_str(), - GetTestCaseTypeId(), - TestCase::SetUpTestCase, - TestCase::TearDownTestCase, - test_info->test_meta_factory->CreateTestFactory(*param_it)); - } // for param_it - } // for gen_it - } // for test_it - } // RegisterTests - - private: - // LocalTestInfo structure keeps information about a single test registered - // with TEST_P macro. - struct TestInfo { - TestInfo(const char* a_test_case_base_name, - const char* a_test_base_name, - TestMetaFactoryBase* a_test_meta_factory) : - test_case_base_name(a_test_case_base_name), - test_base_name(a_test_base_name), - test_meta_factory(a_test_meta_factory) {} - - const string test_case_base_name; - const string test_base_name; - const scoped_ptr > test_meta_factory; - }; - typedef ::std::vector > TestInfoContainer; - // Keeps pairs of - // received from INSTANTIATE_TEST_CASE_P macros. - typedef ::std::vector > - InstantiationContainer; - - const string test_case_name_; - TestInfoContainer tests_; - InstantiationContainer instantiations_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(ParameterizedTestCaseInfo); -}; // class ParameterizedTestCaseInfo - -// INTERNAL IMPLEMENTATION - DO NOT USE IN USER CODE. -// -// ParameterizedTestCaseRegistry contains a map of ParameterizedTestCaseInfoBase -// classes accessed by test case names. TEST_P and INSTANTIATE_TEST_CASE_P -// macros use it to locate their corresponding ParameterizedTestCaseInfo -// descriptors. -class ParameterizedTestCaseRegistry { - public: - ParameterizedTestCaseRegistry() {} - ~ParameterizedTestCaseRegistry() { - for (TestCaseInfoContainer::iterator it = test_case_infos_.begin(); - it != test_case_infos_.end(); ++it) { - delete *it; - } - } - - // Looks up or creates and returns a structure containing information about - // tests and instantiations of a particular test case. - template - ParameterizedTestCaseInfo* GetTestCasePatternHolder( - const char* test_case_name, - const char* file, - int line) { - ParameterizedTestCaseInfo* typed_test_info = NULL; - for (TestCaseInfoContainer::iterator it = test_case_infos_.begin(); - it != test_case_infos_.end(); ++it) { - if ((*it)->GetTestCaseName() == test_case_name) { - if ((*it)->GetTestCaseTypeId() != GetTypeId()) { - // Complain about incorrect usage of Google Test facilities - // and terminate the program since we cannot guaranty correct - // test case setup and tear-down in this case. - ReportInvalidTestCaseType(test_case_name, file, line); - posix::Abort(); - } else { - // At this point we are sure that the object we found is of the same - // type we are looking for, so we downcast it to that type - // without further checks. - typed_test_info = CheckedDowncastToActualType< - ParameterizedTestCaseInfo >(*it); - } - break; - } - } - if (typed_test_info == NULL) { - typed_test_info = new ParameterizedTestCaseInfo(test_case_name); - test_case_infos_.push_back(typed_test_info); - } - return typed_test_info; - } - void RegisterTests() { - for (TestCaseInfoContainer::iterator it = test_case_infos_.begin(); - it != test_case_infos_.end(); ++it) { - (*it)->RegisterTests(); - } - } - - private: - typedef ::std::vector TestCaseInfoContainer; - - TestCaseInfoContainer test_case_infos_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(ParameterizedTestCaseRegistry); -}; - -} // namespace internal -} // namespace testing - -#endif // GTEST_HAS_PARAM_TEST - -#endif // GTEST_INCLUDE_GTEST_INTERNAL_GTEST_PARAM_UTIL_H_ -// This file was GENERATED by command: -// pump.py gtest-param-util-generated.h.pump -// DO NOT EDIT BY HAND!!! - -// Copyright 2008 Google Inc. -// All Rights Reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: vladl@google.com (Vlad Losev) - -// Type and function utilities for implementing parameterized tests. -// This file is generated by a SCRIPT. DO NOT EDIT BY HAND! -// -// Currently Google Test supports at most 50 arguments in Values, -// and at most 10 arguments in Combine. Please contact -// googletestframework@googlegroups.com if you need more. -// Please note that the number of arguments to Combine is limited -// by the maximum arity of the implementation of tr1::tuple which is -// currently set at 10. - -#ifndef GTEST_INCLUDE_GTEST_INTERNAL_GTEST_PARAM_UTIL_GENERATED_H_ -#define GTEST_INCLUDE_GTEST_INTERNAL_GTEST_PARAM_UTIL_GENERATED_H_ - -// scripts/fuse_gtest.py depends on gtest's own header being #included -// *unconditionally*. Therefore these #includes cannot be moved -// inside #if GTEST_HAS_PARAM_TEST. - -#if GTEST_HAS_PARAM_TEST - -namespace testing { - -// Forward declarations of ValuesIn(), which is implemented in -// include/gtest/gtest-param-test.h. -template -internal::ParamGenerator< - typename ::testing::internal::IteratorTraits::value_type> -ValuesIn(ForwardIterator begin, ForwardIterator end); - -template -internal::ParamGenerator ValuesIn(const T (&array)[N]); - -template -internal::ParamGenerator ValuesIn( - const Container& container); - -namespace internal { - -// Used in the Values() function to provide polymorphic capabilities. -template -class ValueArray1 { - public: - explicit ValueArray1(T1 v1) : v1_(v1) {} - - template - operator ParamGenerator() const { return ValuesIn(&v1_, &v1_ + 1); } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray1& other); - - const T1 v1_; -}; - -template -class ValueArray2 { - public: - ValueArray2(T1 v1, T2 v2) : v1_(v1), v2_(v2) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray2& other); - - const T1 v1_; - const T2 v2_; -}; - -template -class ValueArray3 { - public: - ValueArray3(T1 v1, T2 v2, T3 v3) : v1_(v1), v2_(v2), v3_(v3) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray3& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; -}; - -template -class ValueArray4 { - public: - ValueArray4(T1 v1, T2 v2, T3 v3, T4 v4) : v1_(v1), v2_(v2), v3_(v3), - v4_(v4) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray4& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; -}; - -template -class ValueArray5 { - public: - ValueArray5(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5) : v1_(v1), v2_(v2), v3_(v3), - v4_(v4), v5_(v5) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray5& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; -}; - -template -class ValueArray6 { - public: - ValueArray6(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6) : v1_(v1), v2_(v2), - v3_(v3), v4_(v4), v5_(v5), v6_(v6) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray6& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; -}; - -template -class ValueArray7 { - public: - ValueArray7(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7) : v1_(v1), - v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray7& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; -}; - -template -class ValueArray8 { - public: - ValueArray8(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, - T8 v8) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), - v8_(v8) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray8& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; -}; - -template -class ValueArray9 { - public: - ValueArray9(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, - T9 v9) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), - v8_(v8), v9_(v9) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray9& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; -}; - -template -class ValueArray10 { - public: - ValueArray10(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), - v8_(v8), v9_(v9), v10_(v10) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray10& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; -}; - -template -class ValueArray11 { - public: - ValueArray11(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), - v7_(v7), v8_(v8), v9_(v9), v10_(v10), v11_(v11) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray11& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; -}; - -template -class ValueArray12 { - public: - ValueArray12(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), - v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), v11_(v11), v12_(v12) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray12& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; -}; - -template -class ValueArray13 { - public: - ValueArray13(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), - v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), v11_(v11), - v12_(v12), v13_(v13) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray13& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; -}; - -template -class ValueArray14 { - public: - ValueArray14(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14) : v1_(v1), v2_(v2), v3_(v3), - v4_(v4), v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), - v11_(v11), v12_(v12), v13_(v13), v14_(v14) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray14& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; -}; - -template -class ValueArray15 { - public: - ValueArray15(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15) : v1_(v1), v2_(v2), - v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), - v11_(v11), v12_(v12), v13_(v13), v14_(v14), v15_(v15) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray15& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; -}; - -template -class ValueArray16 { - public: - ValueArray16(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16) : v1_(v1), - v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), - v10_(v10), v11_(v11), v12_(v12), v13_(v13), v14_(v14), v15_(v15), - v16_(v16) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray16& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; -}; - -template -class ValueArray17 { - public: - ValueArray17(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, - T17 v17) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), - v8_(v8), v9_(v9), v10_(v10), v11_(v11), v12_(v12), v13_(v13), v14_(v14), - v15_(v15), v16_(v16), v17_(v17) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray17& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; -}; - -template -class ValueArray18 { - public: - ValueArray18(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), - v8_(v8), v9_(v9), v10_(v10), v11_(v11), v12_(v12), v13_(v13), v14_(v14), - v15_(v15), v16_(v16), v17_(v17), v18_(v18) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray18& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; -}; - -template -class ValueArray19 { - public: - ValueArray19(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), - v7_(v7), v8_(v8), v9_(v9), v10_(v10), v11_(v11), v12_(v12), v13_(v13), - v14_(v14), v15_(v15), v16_(v16), v17_(v17), v18_(v18), v19_(v19) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray19& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; -}; - -template -class ValueArray20 { - public: - ValueArray20(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), - v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), v11_(v11), v12_(v12), - v13_(v13), v14_(v14), v15_(v15), v16_(v16), v17_(v17), v18_(v18), - v19_(v19), v20_(v20) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray20& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; -}; - -template -class ValueArray21 { - public: - ValueArray21(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), - v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), v11_(v11), - v12_(v12), v13_(v13), v14_(v14), v15_(v15), v16_(v16), v17_(v17), - v18_(v18), v19_(v19), v20_(v20), v21_(v21) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray21& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; -}; - -template -class ValueArray22 { - public: - ValueArray22(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22) : v1_(v1), v2_(v2), v3_(v3), - v4_(v4), v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), - v11_(v11), v12_(v12), v13_(v13), v14_(v14), v15_(v15), v16_(v16), - v17_(v17), v18_(v18), v19_(v19), v20_(v20), v21_(v21), v22_(v22) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray22& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; -}; - -template -class ValueArray23 { - public: - ValueArray23(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23) : v1_(v1), v2_(v2), - v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), - v11_(v11), v12_(v12), v13_(v13), v14_(v14), v15_(v15), v16_(v16), - v17_(v17), v18_(v18), v19_(v19), v20_(v20), v21_(v21), v22_(v22), - v23_(v23) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray23& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; -}; - -template -class ValueArray24 { - public: - ValueArray24(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24) : v1_(v1), - v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), - v10_(v10), v11_(v11), v12_(v12), v13_(v13), v14_(v14), v15_(v15), - v16_(v16), v17_(v17), v18_(v18), v19_(v19), v20_(v20), v21_(v21), - v22_(v22), v23_(v23), v24_(v24) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray24& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; -}; - -template -class ValueArray25 { - public: - ValueArray25(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, - T25 v25) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), - v8_(v8), v9_(v9), v10_(v10), v11_(v11), v12_(v12), v13_(v13), v14_(v14), - v15_(v15), v16_(v16), v17_(v17), v18_(v18), v19_(v19), v20_(v20), - v21_(v21), v22_(v22), v23_(v23), v24_(v24), v25_(v25) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray25& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; -}; - -template -class ValueArray26 { - public: - ValueArray26(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), - v8_(v8), v9_(v9), v10_(v10), v11_(v11), v12_(v12), v13_(v13), v14_(v14), - v15_(v15), v16_(v16), v17_(v17), v18_(v18), v19_(v19), v20_(v20), - v21_(v21), v22_(v22), v23_(v23), v24_(v24), v25_(v25), v26_(v26) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray26& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; -}; - -template -class ValueArray27 { - public: - ValueArray27(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), - v7_(v7), v8_(v8), v9_(v9), v10_(v10), v11_(v11), v12_(v12), v13_(v13), - v14_(v14), v15_(v15), v16_(v16), v17_(v17), v18_(v18), v19_(v19), - v20_(v20), v21_(v21), v22_(v22), v23_(v23), v24_(v24), v25_(v25), - v26_(v26), v27_(v27) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray27& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; -}; - -template -class ValueArray28 { - public: - ValueArray28(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), - v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), v11_(v11), v12_(v12), - v13_(v13), v14_(v14), v15_(v15), v16_(v16), v17_(v17), v18_(v18), - v19_(v19), v20_(v20), v21_(v21), v22_(v22), v23_(v23), v24_(v24), - v25_(v25), v26_(v26), v27_(v27), v28_(v28) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray28& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; -}; - -template -class ValueArray29 { - public: - ValueArray29(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), - v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), v11_(v11), - v12_(v12), v13_(v13), v14_(v14), v15_(v15), v16_(v16), v17_(v17), - v18_(v18), v19_(v19), v20_(v20), v21_(v21), v22_(v22), v23_(v23), - v24_(v24), v25_(v25), v26_(v26), v27_(v27), v28_(v28), v29_(v29) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray29& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; -}; - -template -class ValueArray30 { - public: - ValueArray30(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30) : v1_(v1), v2_(v2), v3_(v3), - v4_(v4), v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), - v11_(v11), v12_(v12), v13_(v13), v14_(v14), v15_(v15), v16_(v16), - v17_(v17), v18_(v18), v19_(v19), v20_(v20), v21_(v21), v22_(v22), - v23_(v23), v24_(v24), v25_(v25), v26_(v26), v27_(v27), v28_(v28), - v29_(v29), v30_(v30) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray30& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; -}; - -template -class ValueArray31 { - public: - ValueArray31(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31) : v1_(v1), v2_(v2), - v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), - v11_(v11), v12_(v12), v13_(v13), v14_(v14), v15_(v15), v16_(v16), - v17_(v17), v18_(v18), v19_(v19), v20_(v20), v21_(v21), v22_(v22), - v23_(v23), v24_(v24), v25_(v25), v26_(v26), v27_(v27), v28_(v28), - v29_(v29), v30_(v30), v31_(v31) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray31& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; -}; - -template -class ValueArray32 { - public: - ValueArray32(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32) : v1_(v1), - v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), - v10_(v10), v11_(v11), v12_(v12), v13_(v13), v14_(v14), v15_(v15), - v16_(v16), v17_(v17), v18_(v18), v19_(v19), v20_(v20), v21_(v21), - v22_(v22), v23_(v23), v24_(v24), v25_(v25), v26_(v26), v27_(v27), - v28_(v28), v29_(v29), v30_(v30), v31_(v31), v32_(v32) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_), static_cast(v32_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray32& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; - const T32 v32_; -}; - -template -class ValueArray33 { - public: - ValueArray33(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, - T33 v33) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), - v8_(v8), v9_(v9), v10_(v10), v11_(v11), v12_(v12), v13_(v13), v14_(v14), - v15_(v15), v16_(v16), v17_(v17), v18_(v18), v19_(v19), v20_(v20), - v21_(v21), v22_(v22), v23_(v23), v24_(v24), v25_(v25), v26_(v26), - v27_(v27), v28_(v28), v29_(v29), v30_(v30), v31_(v31), v32_(v32), - v33_(v33) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_), static_cast(v32_), - static_cast(v33_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray33& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; - const T32 v32_; - const T33 v33_; -}; - -template -class ValueArray34 { - public: - ValueArray34(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), - v8_(v8), v9_(v9), v10_(v10), v11_(v11), v12_(v12), v13_(v13), v14_(v14), - v15_(v15), v16_(v16), v17_(v17), v18_(v18), v19_(v19), v20_(v20), - v21_(v21), v22_(v22), v23_(v23), v24_(v24), v25_(v25), v26_(v26), - v27_(v27), v28_(v28), v29_(v29), v30_(v30), v31_(v31), v32_(v32), - v33_(v33), v34_(v34) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_), static_cast(v32_), - static_cast(v33_), static_cast(v34_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray34& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; - const T32 v32_; - const T33 v33_; - const T34 v34_; -}; - -template -class ValueArray35 { - public: - ValueArray35(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), - v7_(v7), v8_(v8), v9_(v9), v10_(v10), v11_(v11), v12_(v12), v13_(v13), - v14_(v14), v15_(v15), v16_(v16), v17_(v17), v18_(v18), v19_(v19), - v20_(v20), v21_(v21), v22_(v22), v23_(v23), v24_(v24), v25_(v25), - v26_(v26), v27_(v27), v28_(v28), v29_(v29), v30_(v30), v31_(v31), - v32_(v32), v33_(v33), v34_(v34), v35_(v35) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_), static_cast(v32_), - static_cast(v33_), static_cast(v34_), static_cast(v35_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray35& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; - const T32 v32_; - const T33 v33_; - const T34 v34_; - const T35 v35_; -}; - -template -class ValueArray36 { - public: - ValueArray36(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35, T36 v36) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), - v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), v11_(v11), v12_(v12), - v13_(v13), v14_(v14), v15_(v15), v16_(v16), v17_(v17), v18_(v18), - v19_(v19), v20_(v20), v21_(v21), v22_(v22), v23_(v23), v24_(v24), - v25_(v25), v26_(v26), v27_(v27), v28_(v28), v29_(v29), v30_(v30), - v31_(v31), v32_(v32), v33_(v33), v34_(v34), v35_(v35), v36_(v36) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_), static_cast(v32_), - static_cast(v33_), static_cast(v34_), static_cast(v35_), - static_cast(v36_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray36& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; - const T32 v32_; - const T33 v33_; - const T34 v34_; - const T35 v35_; - const T36 v36_; -}; - -template -class ValueArray37 { - public: - ValueArray37(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35, T36 v36, T37 v37) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), - v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), v11_(v11), - v12_(v12), v13_(v13), v14_(v14), v15_(v15), v16_(v16), v17_(v17), - v18_(v18), v19_(v19), v20_(v20), v21_(v21), v22_(v22), v23_(v23), - v24_(v24), v25_(v25), v26_(v26), v27_(v27), v28_(v28), v29_(v29), - v30_(v30), v31_(v31), v32_(v32), v33_(v33), v34_(v34), v35_(v35), - v36_(v36), v37_(v37) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_), static_cast(v32_), - static_cast(v33_), static_cast(v34_), static_cast(v35_), - static_cast(v36_), static_cast(v37_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray37& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; - const T32 v32_; - const T33 v33_; - const T34 v34_; - const T35 v35_; - const T36 v36_; - const T37 v37_; -}; - -template -class ValueArray38 { - public: - ValueArray38(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35, T36 v36, T37 v37, T38 v38) : v1_(v1), v2_(v2), v3_(v3), - v4_(v4), v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), - v11_(v11), v12_(v12), v13_(v13), v14_(v14), v15_(v15), v16_(v16), - v17_(v17), v18_(v18), v19_(v19), v20_(v20), v21_(v21), v22_(v22), - v23_(v23), v24_(v24), v25_(v25), v26_(v26), v27_(v27), v28_(v28), - v29_(v29), v30_(v30), v31_(v31), v32_(v32), v33_(v33), v34_(v34), - v35_(v35), v36_(v36), v37_(v37), v38_(v38) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_), static_cast(v32_), - static_cast(v33_), static_cast(v34_), static_cast(v35_), - static_cast(v36_), static_cast(v37_), static_cast(v38_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray38& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; - const T32 v32_; - const T33 v33_; - const T34 v34_; - const T35 v35_; - const T36 v36_; - const T37 v37_; - const T38 v38_; -}; - -template -class ValueArray39 { - public: - ValueArray39(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39) : v1_(v1), v2_(v2), - v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), - v11_(v11), v12_(v12), v13_(v13), v14_(v14), v15_(v15), v16_(v16), - v17_(v17), v18_(v18), v19_(v19), v20_(v20), v21_(v21), v22_(v22), - v23_(v23), v24_(v24), v25_(v25), v26_(v26), v27_(v27), v28_(v28), - v29_(v29), v30_(v30), v31_(v31), v32_(v32), v33_(v33), v34_(v34), - v35_(v35), v36_(v36), v37_(v37), v38_(v38), v39_(v39) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_), static_cast(v32_), - static_cast(v33_), static_cast(v34_), static_cast(v35_), - static_cast(v36_), static_cast(v37_), static_cast(v38_), - static_cast(v39_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray39& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; - const T32 v32_; - const T33 v33_; - const T34 v34_; - const T35 v35_; - const T36 v36_; - const T37 v37_; - const T38 v38_; - const T39 v39_; -}; - -template -class ValueArray40 { - public: - ValueArray40(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39, T40 v40) : v1_(v1), - v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), - v10_(v10), v11_(v11), v12_(v12), v13_(v13), v14_(v14), v15_(v15), - v16_(v16), v17_(v17), v18_(v18), v19_(v19), v20_(v20), v21_(v21), - v22_(v22), v23_(v23), v24_(v24), v25_(v25), v26_(v26), v27_(v27), - v28_(v28), v29_(v29), v30_(v30), v31_(v31), v32_(v32), v33_(v33), - v34_(v34), v35_(v35), v36_(v36), v37_(v37), v38_(v38), v39_(v39), - v40_(v40) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_), static_cast(v32_), - static_cast(v33_), static_cast(v34_), static_cast(v35_), - static_cast(v36_), static_cast(v37_), static_cast(v38_), - static_cast(v39_), static_cast(v40_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray40& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; - const T32 v32_; - const T33 v33_; - const T34 v34_; - const T35 v35_; - const T36 v36_; - const T37 v37_; - const T38 v38_; - const T39 v39_; - const T40 v40_; -}; - -template -class ValueArray41 { - public: - ValueArray41(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39, T40 v40, - T41 v41) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), - v8_(v8), v9_(v9), v10_(v10), v11_(v11), v12_(v12), v13_(v13), v14_(v14), - v15_(v15), v16_(v16), v17_(v17), v18_(v18), v19_(v19), v20_(v20), - v21_(v21), v22_(v22), v23_(v23), v24_(v24), v25_(v25), v26_(v26), - v27_(v27), v28_(v28), v29_(v29), v30_(v30), v31_(v31), v32_(v32), - v33_(v33), v34_(v34), v35_(v35), v36_(v36), v37_(v37), v38_(v38), - v39_(v39), v40_(v40), v41_(v41) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_), static_cast(v32_), - static_cast(v33_), static_cast(v34_), static_cast(v35_), - static_cast(v36_), static_cast(v37_), static_cast(v38_), - static_cast(v39_), static_cast(v40_), static_cast(v41_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray41& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; - const T32 v32_; - const T33 v33_; - const T34 v34_; - const T35 v35_; - const T36 v36_; - const T37 v37_; - const T38 v38_; - const T39 v39_; - const T40 v40_; - const T41 v41_; -}; - -template -class ValueArray42 { - public: - ValueArray42(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39, T40 v40, T41 v41, - T42 v42) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), - v8_(v8), v9_(v9), v10_(v10), v11_(v11), v12_(v12), v13_(v13), v14_(v14), - v15_(v15), v16_(v16), v17_(v17), v18_(v18), v19_(v19), v20_(v20), - v21_(v21), v22_(v22), v23_(v23), v24_(v24), v25_(v25), v26_(v26), - v27_(v27), v28_(v28), v29_(v29), v30_(v30), v31_(v31), v32_(v32), - v33_(v33), v34_(v34), v35_(v35), v36_(v36), v37_(v37), v38_(v38), - v39_(v39), v40_(v40), v41_(v41), v42_(v42) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_), static_cast(v32_), - static_cast(v33_), static_cast(v34_), static_cast(v35_), - static_cast(v36_), static_cast(v37_), static_cast(v38_), - static_cast(v39_), static_cast(v40_), static_cast(v41_), - static_cast(v42_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray42& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; - const T32 v32_; - const T33 v33_; - const T34 v34_; - const T35 v35_; - const T36 v36_; - const T37 v37_; - const T38 v38_; - const T39 v39_; - const T40 v40_; - const T41 v41_; - const T42 v42_; -}; - -template -class ValueArray43 { - public: - ValueArray43(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39, T40 v40, T41 v41, - T42 v42, T43 v43) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), - v7_(v7), v8_(v8), v9_(v9), v10_(v10), v11_(v11), v12_(v12), v13_(v13), - v14_(v14), v15_(v15), v16_(v16), v17_(v17), v18_(v18), v19_(v19), - v20_(v20), v21_(v21), v22_(v22), v23_(v23), v24_(v24), v25_(v25), - v26_(v26), v27_(v27), v28_(v28), v29_(v29), v30_(v30), v31_(v31), - v32_(v32), v33_(v33), v34_(v34), v35_(v35), v36_(v36), v37_(v37), - v38_(v38), v39_(v39), v40_(v40), v41_(v41), v42_(v42), v43_(v43) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_), static_cast(v32_), - static_cast(v33_), static_cast(v34_), static_cast(v35_), - static_cast(v36_), static_cast(v37_), static_cast(v38_), - static_cast(v39_), static_cast(v40_), static_cast(v41_), - static_cast(v42_), static_cast(v43_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray43& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; - const T32 v32_; - const T33 v33_; - const T34 v34_; - const T35 v35_; - const T36 v36_; - const T37 v37_; - const T38 v38_; - const T39 v39_; - const T40 v40_; - const T41 v41_; - const T42 v42_; - const T43 v43_; -}; - -template -class ValueArray44 { - public: - ValueArray44(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39, T40 v40, T41 v41, - T42 v42, T43 v43, T44 v44) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), - v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), v11_(v11), v12_(v12), - v13_(v13), v14_(v14), v15_(v15), v16_(v16), v17_(v17), v18_(v18), - v19_(v19), v20_(v20), v21_(v21), v22_(v22), v23_(v23), v24_(v24), - v25_(v25), v26_(v26), v27_(v27), v28_(v28), v29_(v29), v30_(v30), - v31_(v31), v32_(v32), v33_(v33), v34_(v34), v35_(v35), v36_(v36), - v37_(v37), v38_(v38), v39_(v39), v40_(v40), v41_(v41), v42_(v42), - v43_(v43), v44_(v44) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_), static_cast(v32_), - static_cast(v33_), static_cast(v34_), static_cast(v35_), - static_cast(v36_), static_cast(v37_), static_cast(v38_), - static_cast(v39_), static_cast(v40_), static_cast(v41_), - static_cast(v42_), static_cast(v43_), static_cast(v44_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray44& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; - const T32 v32_; - const T33 v33_; - const T34 v34_; - const T35 v35_; - const T36 v36_; - const T37 v37_; - const T38 v38_; - const T39 v39_; - const T40 v40_; - const T41 v41_; - const T42 v42_; - const T43 v43_; - const T44 v44_; -}; - -template -class ValueArray45 { - public: - ValueArray45(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39, T40 v40, T41 v41, - T42 v42, T43 v43, T44 v44, T45 v45) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), - v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), v11_(v11), - v12_(v12), v13_(v13), v14_(v14), v15_(v15), v16_(v16), v17_(v17), - v18_(v18), v19_(v19), v20_(v20), v21_(v21), v22_(v22), v23_(v23), - v24_(v24), v25_(v25), v26_(v26), v27_(v27), v28_(v28), v29_(v29), - v30_(v30), v31_(v31), v32_(v32), v33_(v33), v34_(v34), v35_(v35), - v36_(v36), v37_(v37), v38_(v38), v39_(v39), v40_(v40), v41_(v41), - v42_(v42), v43_(v43), v44_(v44), v45_(v45) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_), static_cast(v32_), - static_cast(v33_), static_cast(v34_), static_cast(v35_), - static_cast(v36_), static_cast(v37_), static_cast(v38_), - static_cast(v39_), static_cast(v40_), static_cast(v41_), - static_cast(v42_), static_cast(v43_), static_cast(v44_), - static_cast(v45_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray45& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; - const T32 v32_; - const T33 v33_; - const T34 v34_; - const T35 v35_; - const T36 v36_; - const T37 v37_; - const T38 v38_; - const T39 v39_; - const T40 v40_; - const T41 v41_; - const T42 v42_; - const T43 v43_; - const T44 v44_; - const T45 v45_; -}; - -template -class ValueArray46 { - public: - ValueArray46(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39, T40 v40, T41 v41, - T42 v42, T43 v43, T44 v44, T45 v45, T46 v46) : v1_(v1), v2_(v2), v3_(v3), - v4_(v4), v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), - v11_(v11), v12_(v12), v13_(v13), v14_(v14), v15_(v15), v16_(v16), - v17_(v17), v18_(v18), v19_(v19), v20_(v20), v21_(v21), v22_(v22), - v23_(v23), v24_(v24), v25_(v25), v26_(v26), v27_(v27), v28_(v28), - v29_(v29), v30_(v30), v31_(v31), v32_(v32), v33_(v33), v34_(v34), - v35_(v35), v36_(v36), v37_(v37), v38_(v38), v39_(v39), v40_(v40), - v41_(v41), v42_(v42), v43_(v43), v44_(v44), v45_(v45), v46_(v46) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_), static_cast(v32_), - static_cast(v33_), static_cast(v34_), static_cast(v35_), - static_cast(v36_), static_cast(v37_), static_cast(v38_), - static_cast(v39_), static_cast(v40_), static_cast(v41_), - static_cast(v42_), static_cast(v43_), static_cast(v44_), - static_cast(v45_), static_cast(v46_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray46& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; - const T32 v32_; - const T33 v33_; - const T34 v34_; - const T35 v35_; - const T36 v36_; - const T37 v37_; - const T38 v38_; - const T39 v39_; - const T40 v40_; - const T41 v41_; - const T42 v42_; - const T43 v43_; - const T44 v44_; - const T45 v45_; - const T46 v46_; -}; - -template -class ValueArray47 { - public: - ValueArray47(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39, T40 v40, T41 v41, - T42 v42, T43 v43, T44 v44, T45 v45, T46 v46, T47 v47) : v1_(v1), v2_(v2), - v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), v10_(v10), - v11_(v11), v12_(v12), v13_(v13), v14_(v14), v15_(v15), v16_(v16), - v17_(v17), v18_(v18), v19_(v19), v20_(v20), v21_(v21), v22_(v22), - v23_(v23), v24_(v24), v25_(v25), v26_(v26), v27_(v27), v28_(v28), - v29_(v29), v30_(v30), v31_(v31), v32_(v32), v33_(v33), v34_(v34), - v35_(v35), v36_(v36), v37_(v37), v38_(v38), v39_(v39), v40_(v40), - v41_(v41), v42_(v42), v43_(v43), v44_(v44), v45_(v45), v46_(v46), - v47_(v47) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_), static_cast(v32_), - static_cast(v33_), static_cast(v34_), static_cast(v35_), - static_cast(v36_), static_cast(v37_), static_cast(v38_), - static_cast(v39_), static_cast(v40_), static_cast(v41_), - static_cast(v42_), static_cast(v43_), static_cast(v44_), - static_cast(v45_), static_cast(v46_), static_cast(v47_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray47& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; - const T32 v32_; - const T33 v33_; - const T34 v34_; - const T35 v35_; - const T36 v36_; - const T37 v37_; - const T38 v38_; - const T39 v39_; - const T40 v40_; - const T41 v41_; - const T42 v42_; - const T43 v43_; - const T44 v44_; - const T45 v45_; - const T46 v46_; - const T47 v47_; -}; - -template -class ValueArray48 { - public: - ValueArray48(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39, T40 v40, T41 v41, - T42 v42, T43 v43, T44 v44, T45 v45, T46 v46, T47 v47, T48 v48) : v1_(v1), - v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), v8_(v8), v9_(v9), - v10_(v10), v11_(v11), v12_(v12), v13_(v13), v14_(v14), v15_(v15), - v16_(v16), v17_(v17), v18_(v18), v19_(v19), v20_(v20), v21_(v21), - v22_(v22), v23_(v23), v24_(v24), v25_(v25), v26_(v26), v27_(v27), - v28_(v28), v29_(v29), v30_(v30), v31_(v31), v32_(v32), v33_(v33), - v34_(v34), v35_(v35), v36_(v36), v37_(v37), v38_(v38), v39_(v39), - v40_(v40), v41_(v41), v42_(v42), v43_(v43), v44_(v44), v45_(v45), - v46_(v46), v47_(v47), v48_(v48) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_), static_cast(v32_), - static_cast(v33_), static_cast(v34_), static_cast(v35_), - static_cast(v36_), static_cast(v37_), static_cast(v38_), - static_cast(v39_), static_cast(v40_), static_cast(v41_), - static_cast(v42_), static_cast(v43_), static_cast(v44_), - static_cast(v45_), static_cast(v46_), static_cast(v47_), - static_cast(v48_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray48& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; - const T32 v32_; - const T33 v33_; - const T34 v34_; - const T35 v35_; - const T36 v36_; - const T37 v37_; - const T38 v38_; - const T39 v39_; - const T40 v40_; - const T41 v41_; - const T42 v42_; - const T43 v43_; - const T44 v44_; - const T45 v45_; - const T46 v46_; - const T47 v47_; - const T48 v48_; -}; - -template -class ValueArray49 { - public: - ValueArray49(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39, T40 v40, T41 v41, - T42 v42, T43 v43, T44 v44, T45 v45, T46 v46, T47 v47, T48 v48, - T49 v49) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), - v8_(v8), v9_(v9), v10_(v10), v11_(v11), v12_(v12), v13_(v13), v14_(v14), - v15_(v15), v16_(v16), v17_(v17), v18_(v18), v19_(v19), v20_(v20), - v21_(v21), v22_(v22), v23_(v23), v24_(v24), v25_(v25), v26_(v26), - v27_(v27), v28_(v28), v29_(v29), v30_(v30), v31_(v31), v32_(v32), - v33_(v33), v34_(v34), v35_(v35), v36_(v36), v37_(v37), v38_(v38), - v39_(v39), v40_(v40), v41_(v41), v42_(v42), v43_(v43), v44_(v44), - v45_(v45), v46_(v46), v47_(v47), v48_(v48), v49_(v49) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_), static_cast(v32_), - static_cast(v33_), static_cast(v34_), static_cast(v35_), - static_cast(v36_), static_cast(v37_), static_cast(v38_), - static_cast(v39_), static_cast(v40_), static_cast(v41_), - static_cast(v42_), static_cast(v43_), static_cast(v44_), - static_cast(v45_), static_cast(v46_), static_cast(v47_), - static_cast(v48_), static_cast(v49_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray49& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; - const T32 v32_; - const T33 v33_; - const T34 v34_; - const T35 v35_; - const T36 v36_; - const T37 v37_; - const T38 v38_; - const T39 v39_; - const T40 v40_; - const T41 v41_; - const T42 v42_; - const T43 v43_; - const T44 v44_; - const T45 v45_; - const T46 v46_; - const T47 v47_; - const T48 v48_; - const T49 v49_; -}; - -template -class ValueArray50 { - public: - ValueArray50(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39, T40 v40, T41 v41, - T42 v42, T43 v43, T44 v44, T45 v45, T46 v46, T47 v47, T48 v48, T49 v49, - T50 v50) : v1_(v1), v2_(v2), v3_(v3), v4_(v4), v5_(v5), v6_(v6), v7_(v7), - v8_(v8), v9_(v9), v10_(v10), v11_(v11), v12_(v12), v13_(v13), v14_(v14), - v15_(v15), v16_(v16), v17_(v17), v18_(v18), v19_(v19), v20_(v20), - v21_(v21), v22_(v22), v23_(v23), v24_(v24), v25_(v25), v26_(v26), - v27_(v27), v28_(v28), v29_(v29), v30_(v30), v31_(v31), v32_(v32), - v33_(v33), v34_(v34), v35_(v35), v36_(v36), v37_(v37), v38_(v38), - v39_(v39), v40_(v40), v41_(v41), v42_(v42), v43_(v43), v44_(v44), - v45_(v45), v46_(v46), v47_(v47), v48_(v48), v49_(v49), v50_(v50) {} - - template - operator ParamGenerator() const { - const T array[] = {static_cast(v1_), static_cast(v2_), - static_cast(v3_), static_cast(v4_), static_cast(v5_), - static_cast(v6_), static_cast(v7_), static_cast(v8_), - static_cast(v9_), static_cast(v10_), static_cast(v11_), - static_cast(v12_), static_cast(v13_), static_cast(v14_), - static_cast(v15_), static_cast(v16_), static_cast(v17_), - static_cast(v18_), static_cast(v19_), static_cast(v20_), - static_cast(v21_), static_cast(v22_), static_cast(v23_), - static_cast(v24_), static_cast(v25_), static_cast(v26_), - static_cast(v27_), static_cast(v28_), static_cast(v29_), - static_cast(v30_), static_cast(v31_), static_cast(v32_), - static_cast(v33_), static_cast(v34_), static_cast(v35_), - static_cast(v36_), static_cast(v37_), static_cast(v38_), - static_cast(v39_), static_cast(v40_), static_cast(v41_), - static_cast(v42_), static_cast(v43_), static_cast(v44_), - static_cast(v45_), static_cast(v46_), static_cast(v47_), - static_cast(v48_), static_cast(v49_), static_cast(v50_)}; - return ValuesIn(array); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const ValueArray50& other); - - const T1 v1_; - const T2 v2_; - const T3 v3_; - const T4 v4_; - const T5 v5_; - const T6 v6_; - const T7 v7_; - const T8 v8_; - const T9 v9_; - const T10 v10_; - const T11 v11_; - const T12 v12_; - const T13 v13_; - const T14 v14_; - const T15 v15_; - const T16 v16_; - const T17 v17_; - const T18 v18_; - const T19 v19_; - const T20 v20_; - const T21 v21_; - const T22 v22_; - const T23 v23_; - const T24 v24_; - const T25 v25_; - const T26 v26_; - const T27 v27_; - const T28 v28_; - const T29 v29_; - const T30 v30_; - const T31 v31_; - const T32 v32_; - const T33 v33_; - const T34 v34_; - const T35 v35_; - const T36 v36_; - const T37 v37_; - const T38 v38_; - const T39 v39_; - const T40 v40_; - const T41 v41_; - const T42 v42_; - const T43 v43_; - const T44 v44_; - const T45 v45_; - const T46 v46_; - const T47 v47_; - const T48 v48_; - const T49 v49_; - const T50 v50_; -}; - -# if GTEST_HAS_COMBINE -// INTERNAL IMPLEMENTATION - DO NOT USE IN USER CODE. -// -// Generates values from the Cartesian product of values produced -// by the argument generators. -// -template -class CartesianProductGenerator2 - : public ParamGeneratorInterface< ::std::tr1::tuple > { - public: - typedef ::std::tr1::tuple ParamType; - - CartesianProductGenerator2(const ParamGenerator& g1, - const ParamGenerator& g2) - : g1_(g1), g2_(g2) {} - virtual ~CartesianProductGenerator2() {} - - virtual ParamIteratorInterface* Begin() const { - return new Iterator(this, g1_, g1_.begin(), g2_, g2_.begin()); - } - virtual ParamIteratorInterface* End() const { - return new Iterator(this, g1_, g1_.end(), g2_, g2_.end()); - } - - private: - class Iterator : public ParamIteratorInterface { - public: - Iterator(const ParamGeneratorInterface* base, - const ParamGenerator& g1, - const typename ParamGenerator::iterator& current1, - const ParamGenerator& g2, - const typename ParamGenerator::iterator& current2) - : base_(base), - begin1_(g1.begin()), end1_(g1.end()), current1_(current1), - begin2_(g2.begin()), end2_(g2.end()), current2_(current2) { - ComputeCurrentValue(); - } - virtual ~Iterator() {} - - virtual const ParamGeneratorInterface* BaseGenerator() const { - return base_; - } - // Advance should not be called on beyond-of-range iterators - // so no component iterators must be beyond end of range, either. - virtual void Advance() { - assert(!AtEnd()); - ++current2_; - if (current2_ == end2_) { - current2_ = begin2_; - ++current1_; - } - ComputeCurrentValue(); - } - virtual ParamIteratorInterface* Clone() const { - return new Iterator(*this); - } - virtual const ParamType* Current() const { return ¤t_value_; } - virtual bool Equals(const ParamIteratorInterface& other) const { - // Having the same base generator guarantees that the other - // iterator is of the same type and we can downcast. - GTEST_CHECK_(BaseGenerator() == other.BaseGenerator()) - << "The program attempted to compare iterators " - << "from different generators." << std::endl; - const Iterator* typed_other = - CheckedDowncastToActualType(&other); - // We must report iterators equal if they both point beyond their - // respective ranges. That can happen in a variety of fashions, - // so we have to consult AtEnd(). - return (AtEnd() && typed_other->AtEnd()) || - ( - current1_ == typed_other->current1_ && - current2_ == typed_other->current2_); - } - - private: - Iterator(const Iterator& other) - : base_(other.base_), - begin1_(other.begin1_), - end1_(other.end1_), - current1_(other.current1_), - begin2_(other.begin2_), - end2_(other.end2_), - current2_(other.current2_) { - ComputeCurrentValue(); - } - - void ComputeCurrentValue() { - if (!AtEnd()) - current_value_ = ParamType(*current1_, *current2_); - } - bool AtEnd() const { - // We must report iterator past the end of the range when either of the - // component iterators has reached the end of its range. - return - current1_ == end1_ || - current2_ == end2_; - } - - // No implementation - assignment is unsupported. - void operator=(const Iterator& other); - - const ParamGeneratorInterface* const base_; - // begin[i]_ and end[i]_ define the i-th range that Iterator traverses. - // current[i]_ is the actual traversing iterator. - const typename ParamGenerator::iterator begin1_; - const typename ParamGenerator::iterator end1_; - typename ParamGenerator::iterator current1_; - const typename ParamGenerator::iterator begin2_; - const typename ParamGenerator::iterator end2_; - typename ParamGenerator::iterator current2_; - ParamType current_value_; - }; // class CartesianProductGenerator2::Iterator - - // No implementation - assignment is unsupported. - void operator=(const CartesianProductGenerator2& other); - - const ParamGenerator g1_; - const ParamGenerator g2_; -}; // class CartesianProductGenerator2 - - -template -class CartesianProductGenerator3 - : public ParamGeneratorInterface< ::std::tr1::tuple > { - public: - typedef ::std::tr1::tuple ParamType; - - CartesianProductGenerator3(const ParamGenerator& g1, - const ParamGenerator& g2, const ParamGenerator& g3) - : g1_(g1), g2_(g2), g3_(g3) {} - virtual ~CartesianProductGenerator3() {} - - virtual ParamIteratorInterface* Begin() const { - return new Iterator(this, g1_, g1_.begin(), g2_, g2_.begin(), g3_, - g3_.begin()); - } - virtual ParamIteratorInterface* End() const { - return new Iterator(this, g1_, g1_.end(), g2_, g2_.end(), g3_, g3_.end()); - } - - private: - class Iterator : public ParamIteratorInterface { - public: - Iterator(const ParamGeneratorInterface* base, - const ParamGenerator& g1, - const typename ParamGenerator::iterator& current1, - const ParamGenerator& g2, - const typename ParamGenerator::iterator& current2, - const ParamGenerator& g3, - const typename ParamGenerator::iterator& current3) - : base_(base), - begin1_(g1.begin()), end1_(g1.end()), current1_(current1), - begin2_(g2.begin()), end2_(g2.end()), current2_(current2), - begin3_(g3.begin()), end3_(g3.end()), current3_(current3) { - ComputeCurrentValue(); - } - virtual ~Iterator() {} - - virtual const ParamGeneratorInterface* BaseGenerator() const { - return base_; - } - // Advance should not be called on beyond-of-range iterators - // so no component iterators must be beyond end of range, either. - virtual void Advance() { - assert(!AtEnd()); - ++current3_; - if (current3_ == end3_) { - current3_ = begin3_; - ++current2_; - } - if (current2_ == end2_) { - current2_ = begin2_; - ++current1_; - } - ComputeCurrentValue(); - } - virtual ParamIteratorInterface* Clone() const { - return new Iterator(*this); - } - virtual const ParamType* Current() const { return ¤t_value_; } - virtual bool Equals(const ParamIteratorInterface& other) const { - // Having the same base generator guarantees that the other - // iterator is of the same type and we can downcast. - GTEST_CHECK_(BaseGenerator() == other.BaseGenerator()) - << "The program attempted to compare iterators " - << "from different generators." << std::endl; - const Iterator* typed_other = - CheckedDowncastToActualType(&other); - // We must report iterators equal if they both point beyond their - // respective ranges. That can happen in a variety of fashions, - // so we have to consult AtEnd(). - return (AtEnd() && typed_other->AtEnd()) || - ( - current1_ == typed_other->current1_ && - current2_ == typed_other->current2_ && - current3_ == typed_other->current3_); - } - - private: - Iterator(const Iterator& other) - : base_(other.base_), - begin1_(other.begin1_), - end1_(other.end1_), - current1_(other.current1_), - begin2_(other.begin2_), - end2_(other.end2_), - current2_(other.current2_), - begin3_(other.begin3_), - end3_(other.end3_), - current3_(other.current3_) { - ComputeCurrentValue(); - } - - void ComputeCurrentValue() { - if (!AtEnd()) - current_value_ = ParamType(*current1_, *current2_, *current3_); - } - bool AtEnd() const { - // We must report iterator past the end of the range when either of the - // component iterators has reached the end of its range. - return - current1_ == end1_ || - current2_ == end2_ || - current3_ == end3_; - } - - // No implementation - assignment is unsupported. - void operator=(const Iterator& other); - - const ParamGeneratorInterface* const base_; - // begin[i]_ and end[i]_ define the i-th range that Iterator traverses. - // current[i]_ is the actual traversing iterator. - const typename ParamGenerator::iterator begin1_; - const typename ParamGenerator::iterator end1_; - typename ParamGenerator::iterator current1_; - const typename ParamGenerator::iterator begin2_; - const typename ParamGenerator::iterator end2_; - typename ParamGenerator::iterator current2_; - const typename ParamGenerator::iterator begin3_; - const typename ParamGenerator::iterator end3_; - typename ParamGenerator::iterator current3_; - ParamType current_value_; - }; // class CartesianProductGenerator3::Iterator - - // No implementation - assignment is unsupported. - void operator=(const CartesianProductGenerator3& other); - - const ParamGenerator g1_; - const ParamGenerator g2_; - const ParamGenerator g3_; -}; // class CartesianProductGenerator3 - - -template -class CartesianProductGenerator4 - : public ParamGeneratorInterface< ::std::tr1::tuple > { - public: - typedef ::std::tr1::tuple ParamType; - - CartesianProductGenerator4(const ParamGenerator& g1, - const ParamGenerator& g2, const ParamGenerator& g3, - const ParamGenerator& g4) - : g1_(g1), g2_(g2), g3_(g3), g4_(g4) {} - virtual ~CartesianProductGenerator4() {} - - virtual ParamIteratorInterface* Begin() const { - return new Iterator(this, g1_, g1_.begin(), g2_, g2_.begin(), g3_, - g3_.begin(), g4_, g4_.begin()); - } - virtual ParamIteratorInterface* End() const { - return new Iterator(this, g1_, g1_.end(), g2_, g2_.end(), g3_, g3_.end(), - g4_, g4_.end()); - } - - private: - class Iterator : public ParamIteratorInterface { - public: - Iterator(const ParamGeneratorInterface* base, - const ParamGenerator& g1, - const typename ParamGenerator::iterator& current1, - const ParamGenerator& g2, - const typename ParamGenerator::iterator& current2, - const ParamGenerator& g3, - const typename ParamGenerator::iterator& current3, - const ParamGenerator& g4, - const typename ParamGenerator::iterator& current4) - : base_(base), - begin1_(g1.begin()), end1_(g1.end()), current1_(current1), - begin2_(g2.begin()), end2_(g2.end()), current2_(current2), - begin3_(g3.begin()), end3_(g3.end()), current3_(current3), - begin4_(g4.begin()), end4_(g4.end()), current4_(current4) { - ComputeCurrentValue(); - } - virtual ~Iterator() {} - - virtual const ParamGeneratorInterface* BaseGenerator() const { - return base_; - } - // Advance should not be called on beyond-of-range iterators - // so no component iterators must be beyond end of range, either. - virtual void Advance() { - assert(!AtEnd()); - ++current4_; - if (current4_ == end4_) { - current4_ = begin4_; - ++current3_; - } - if (current3_ == end3_) { - current3_ = begin3_; - ++current2_; - } - if (current2_ == end2_) { - current2_ = begin2_; - ++current1_; - } - ComputeCurrentValue(); - } - virtual ParamIteratorInterface* Clone() const { - return new Iterator(*this); - } - virtual const ParamType* Current() const { return ¤t_value_; } - virtual bool Equals(const ParamIteratorInterface& other) const { - // Having the same base generator guarantees that the other - // iterator is of the same type and we can downcast. - GTEST_CHECK_(BaseGenerator() == other.BaseGenerator()) - << "The program attempted to compare iterators " - << "from different generators." << std::endl; - const Iterator* typed_other = - CheckedDowncastToActualType(&other); - // We must report iterators equal if they both point beyond their - // respective ranges. That can happen in a variety of fashions, - // so we have to consult AtEnd(). - return (AtEnd() && typed_other->AtEnd()) || - ( - current1_ == typed_other->current1_ && - current2_ == typed_other->current2_ && - current3_ == typed_other->current3_ && - current4_ == typed_other->current4_); - } - - private: - Iterator(const Iterator& other) - : base_(other.base_), - begin1_(other.begin1_), - end1_(other.end1_), - current1_(other.current1_), - begin2_(other.begin2_), - end2_(other.end2_), - current2_(other.current2_), - begin3_(other.begin3_), - end3_(other.end3_), - current3_(other.current3_), - begin4_(other.begin4_), - end4_(other.end4_), - current4_(other.current4_) { - ComputeCurrentValue(); - } - - void ComputeCurrentValue() { - if (!AtEnd()) - current_value_ = ParamType(*current1_, *current2_, *current3_, - *current4_); - } - bool AtEnd() const { - // We must report iterator past the end of the range when either of the - // component iterators has reached the end of its range. - return - current1_ == end1_ || - current2_ == end2_ || - current3_ == end3_ || - current4_ == end4_; - } - - // No implementation - assignment is unsupported. - void operator=(const Iterator& other); - - const ParamGeneratorInterface* const base_; - // begin[i]_ and end[i]_ define the i-th range that Iterator traverses. - // current[i]_ is the actual traversing iterator. - const typename ParamGenerator::iterator begin1_; - const typename ParamGenerator::iterator end1_; - typename ParamGenerator::iterator current1_; - const typename ParamGenerator::iterator begin2_; - const typename ParamGenerator::iterator end2_; - typename ParamGenerator::iterator current2_; - const typename ParamGenerator::iterator begin3_; - const typename ParamGenerator::iterator end3_; - typename ParamGenerator::iterator current3_; - const typename ParamGenerator::iterator begin4_; - const typename ParamGenerator::iterator end4_; - typename ParamGenerator::iterator current4_; - ParamType current_value_; - }; // class CartesianProductGenerator4::Iterator - - // No implementation - assignment is unsupported. - void operator=(const CartesianProductGenerator4& other); - - const ParamGenerator g1_; - const ParamGenerator g2_; - const ParamGenerator g3_; - const ParamGenerator g4_; -}; // class CartesianProductGenerator4 - - -template -class CartesianProductGenerator5 - : public ParamGeneratorInterface< ::std::tr1::tuple > { - public: - typedef ::std::tr1::tuple ParamType; - - CartesianProductGenerator5(const ParamGenerator& g1, - const ParamGenerator& g2, const ParamGenerator& g3, - const ParamGenerator& g4, const ParamGenerator& g5) - : g1_(g1), g2_(g2), g3_(g3), g4_(g4), g5_(g5) {} - virtual ~CartesianProductGenerator5() {} - - virtual ParamIteratorInterface* Begin() const { - return new Iterator(this, g1_, g1_.begin(), g2_, g2_.begin(), g3_, - g3_.begin(), g4_, g4_.begin(), g5_, g5_.begin()); - } - virtual ParamIteratorInterface* End() const { - return new Iterator(this, g1_, g1_.end(), g2_, g2_.end(), g3_, g3_.end(), - g4_, g4_.end(), g5_, g5_.end()); - } - - private: - class Iterator : public ParamIteratorInterface { - public: - Iterator(const ParamGeneratorInterface* base, - const ParamGenerator& g1, - const typename ParamGenerator::iterator& current1, - const ParamGenerator& g2, - const typename ParamGenerator::iterator& current2, - const ParamGenerator& g3, - const typename ParamGenerator::iterator& current3, - const ParamGenerator& g4, - const typename ParamGenerator::iterator& current4, - const ParamGenerator& g5, - const typename ParamGenerator::iterator& current5) - : base_(base), - begin1_(g1.begin()), end1_(g1.end()), current1_(current1), - begin2_(g2.begin()), end2_(g2.end()), current2_(current2), - begin3_(g3.begin()), end3_(g3.end()), current3_(current3), - begin4_(g4.begin()), end4_(g4.end()), current4_(current4), - begin5_(g5.begin()), end5_(g5.end()), current5_(current5) { - ComputeCurrentValue(); - } - virtual ~Iterator() {} - - virtual const ParamGeneratorInterface* BaseGenerator() const { - return base_; - } - // Advance should not be called on beyond-of-range iterators - // so no component iterators must be beyond end of range, either. - virtual void Advance() { - assert(!AtEnd()); - ++current5_; - if (current5_ == end5_) { - current5_ = begin5_; - ++current4_; - } - if (current4_ == end4_) { - current4_ = begin4_; - ++current3_; - } - if (current3_ == end3_) { - current3_ = begin3_; - ++current2_; - } - if (current2_ == end2_) { - current2_ = begin2_; - ++current1_; - } - ComputeCurrentValue(); - } - virtual ParamIteratorInterface* Clone() const { - return new Iterator(*this); - } - virtual const ParamType* Current() const { return ¤t_value_; } - virtual bool Equals(const ParamIteratorInterface& other) const { - // Having the same base generator guarantees that the other - // iterator is of the same type and we can downcast. - GTEST_CHECK_(BaseGenerator() == other.BaseGenerator()) - << "The program attempted to compare iterators " - << "from different generators." << std::endl; - const Iterator* typed_other = - CheckedDowncastToActualType(&other); - // We must report iterators equal if they both point beyond their - // respective ranges. That can happen in a variety of fashions, - // so we have to consult AtEnd(). - return (AtEnd() && typed_other->AtEnd()) || - ( - current1_ == typed_other->current1_ && - current2_ == typed_other->current2_ && - current3_ == typed_other->current3_ && - current4_ == typed_other->current4_ && - current5_ == typed_other->current5_); - } - - private: - Iterator(const Iterator& other) - : base_(other.base_), - begin1_(other.begin1_), - end1_(other.end1_), - current1_(other.current1_), - begin2_(other.begin2_), - end2_(other.end2_), - current2_(other.current2_), - begin3_(other.begin3_), - end3_(other.end3_), - current3_(other.current3_), - begin4_(other.begin4_), - end4_(other.end4_), - current4_(other.current4_), - begin5_(other.begin5_), - end5_(other.end5_), - current5_(other.current5_) { - ComputeCurrentValue(); - } - - void ComputeCurrentValue() { - if (!AtEnd()) - current_value_ = ParamType(*current1_, *current2_, *current3_, - *current4_, *current5_); - } - bool AtEnd() const { - // We must report iterator past the end of the range when either of the - // component iterators has reached the end of its range. - return - current1_ == end1_ || - current2_ == end2_ || - current3_ == end3_ || - current4_ == end4_ || - current5_ == end5_; - } - - // No implementation - assignment is unsupported. - void operator=(const Iterator& other); - - const ParamGeneratorInterface* const base_; - // begin[i]_ and end[i]_ define the i-th range that Iterator traverses. - // current[i]_ is the actual traversing iterator. - const typename ParamGenerator::iterator begin1_; - const typename ParamGenerator::iterator end1_; - typename ParamGenerator::iterator current1_; - const typename ParamGenerator::iterator begin2_; - const typename ParamGenerator::iterator end2_; - typename ParamGenerator::iterator current2_; - const typename ParamGenerator::iterator begin3_; - const typename ParamGenerator::iterator end3_; - typename ParamGenerator::iterator current3_; - const typename ParamGenerator::iterator begin4_; - const typename ParamGenerator::iterator end4_; - typename ParamGenerator::iterator current4_; - const typename ParamGenerator::iterator begin5_; - const typename ParamGenerator::iterator end5_; - typename ParamGenerator::iterator current5_; - ParamType current_value_; - }; // class CartesianProductGenerator5::Iterator - - // No implementation - assignment is unsupported. - void operator=(const CartesianProductGenerator5& other); - - const ParamGenerator g1_; - const ParamGenerator g2_; - const ParamGenerator g3_; - const ParamGenerator g4_; - const ParamGenerator g5_; -}; // class CartesianProductGenerator5 - - -template -class CartesianProductGenerator6 - : public ParamGeneratorInterface< ::std::tr1::tuple > { - public: - typedef ::std::tr1::tuple ParamType; - - CartesianProductGenerator6(const ParamGenerator& g1, - const ParamGenerator& g2, const ParamGenerator& g3, - const ParamGenerator& g4, const ParamGenerator& g5, - const ParamGenerator& g6) - : g1_(g1), g2_(g2), g3_(g3), g4_(g4), g5_(g5), g6_(g6) {} - virtual ~CartesianProductGenerator6() {} - - virtual ParamIteratorInterface* Begin() const { - return new Iterator(this, g1_, g1_.begin(), g2_, g2_.begin(), g3_, - g3_.begin(), g4_, g4_.begin(), g5_, g5_.begin(), g6_, g6_.begin()); - } - virtual ParamIteratorInterface* End() const { - return new Iterator(this, g1_, g1_.end(), g2_, g2_.end(), g3_, g3_.end(), - g4_, g4_.end(), g5_, g5_.end(), g6_, g6_.end()); - } - - private: - class Iterator : public ParamIteratorInterface { - public: - Iterator(const ParamGeneratorInterface* base, - const ParamGenerator& g1, - const typename ParamGenerator::iterator& current1, - const ParamGenerator& g2, - const typename ParamGenerator::iterator& current2, - const ParamGenerator& g3, - const typename ParamGenerator::iterator& current3, - const ParamGenerator& g4, - const typename ParamGenerator::iterator& current4, - const ParamGenerator& g5, - const typename ParamGenerator::iterator& current5, - const ParamGenerator& g6, - const typename ParamGenerator::iterator& current6) - : base_(base), - begin1_(g1.begin()), end1_(g1.end()), current1_(current1), - begin2_(g2.begin()), end2_(g2.end()), current2_(current2), - begin3_(g3.begin()), end3_(g3.end()), current3_(current3), - begin4_(g4.begin()), end4_(g4.end()), current4_(current4), - begin5_(g5.begin()), end5_(g5.end()), current5_(current5), - begin6_(g6.begin()), end6_(g6.end()), current6_(current6) { - ComputeCurrentValue(); - } - virtual ~Iterator() {} - - virtual const ParamGeneratorInterface* BaseGenerator() const { - return base_; - } - // Advance should not be called on beyond-of-range iterators - // so no component iterators must be beyond end of range, either. - virtual void Advance() { - assert(!AtEnd()); - ++current6_; - if (current6_ == end6_) { - current6_ = begin6_; - ++current5_; - } - if (current5_ == end5_) { - current5_ = begin5_; - ++current4_; - } - if (current4_ == end4_) { - current4_ = begin4_; - ++current3_; - } - if (current3_ == end3_) { - current3_ = begin3_; - ++current2_; - } - if (current2_ == end2_) { - current2_ = begin2_; - ++current1_; - } - ComputeCurrentValue(); - } - virtual ParamIteratorInterface* Clone() const { - return new Iterator(*this); - } - virtual const ParamType* Current() const { return ¤t_value_; } - virtual bool Equals(const ParamIteratorInterface& other) const { - // Having the same base generator guarantees that the other - // iterator is of the same type and we can downcast. - GTEST_CHECK_(BaseGenerator() == other.BaseGenerator()) - << "The program attempted to compare iterators " - << "from different generators." << std::endl; - const Iterator* typed_other = - CheckedDowncastToActualType(&other); - // We must report iterators equal if they both point beyond their - // respective ranges. That can happen in a variety of fashions, - // so we have to consult AtEnd(). - return (AtEnd() && typed_other->AtEnd()) || - ( - current1_ == typed_other->current1_ && - current2_ == typed_other->current2_ && - current3_ == typed_other->current3_ && - current4_ == typed_other->current4_ && - current5_ == typed_other->current5_ && - current6_ == typed_other->current6_); - } - - private: - Iterator(const Iterator& other) - : base_(other.base_), - begin1_(other.begin1_), - end1_(other.end1_), - current1_(other.current1_), - begin2_(other.begin2_), - end2_(other.end2_), - current2_(other.current2_), - begin3_(other.begin3_), - end3_(other.end3_), - current3_(other.current3_), - begin4_(other.begin4_), - end4_(other.end4_), - current4_(other.current4_), - begin5_(other.begin5_), - end5_(other.end5_), - current5_(other.current5_), - begin6_(other.begin6_), - end6_(other.end6_), - current6_(other.current6_) { - ComputeCurrentValue(); - } - - void ComputeCurrentValue() { - if (!AtEnd()) - current_value_ = ParamType(*current1_, *current2_, *current3_, - *current4_, *current5_, *current6_); - } - bool AtEnd() const { - // We must report iterator past the end of the range when either of the - // component iterators has reached the end of its range. - return - current1_ == end1_ || - current2_ == end2_ || - current3_ == end3_ || - current4_ == end4_ || - current5_ == end5_ || - current6_ == end6_; - } - - // No implementation - assignment is unsupported. - void operator=(const Iterator& other); - - const ParamGeneratorInterface* const base_; - // begin[i]_ and end[i]_ define the i-th range that Iterator traverses. - // current[i]_ is the actual traversing iterator. - const typename ParamGenerator::iterator begin1_; - const typename ParamGenerator::iterator end1_; - typename ParamGenerator::iterator current1_; - const typename ParamGenerator::iterator begin2_; - const typename ParamGenerator::iterator end2_; - typename ParamGenerator::iterator current2_; - const typename ParamGenerator::iterator begin3_; - const typename ParamGenerator::iterator end3_; - typename ParamGenerator::iterator current3_; - const typename ParamGenerator::iterator begin4_; - const typename ParamGenerator::iterator end4_; - typename ParamGenerator::iterator current4_; - const typename ParamGenerator::iterator begin5_; - const typename ParamGenerator::iterator end5_; - typename ParamGenerator::iterator current5_; - const typename ParamGenerator::iterator begin6_; - const typename ParamGenerator::iterator end6_; - typename ParamGenerator::iterator current6_; - ParamType current_value_; - }; // class CartesianProductGenerator6::Iterator - - // No implementation - assignment is unsupported. - void operator=(const CartesianProductGenerator6& other); - - const ParamGenerator g1_; - const ParamGenerator g2_; - const ParamGenerator g3_; - const ParamGenerator g4_; - const ParamGenerator g5_; - const ParamGenerator g6_; -}; // class CartesianProductGenerator6 - - -template -class CartesianProductGenerator7 - : public ParamGeneratorInterface< ::std::tr1::tuple > { - public: - typedef ::std::tr1::tuple ParamType; - - CartesianProductGenerator7(const ParamGenerator& g1, - const ParamGenerator& g2, const ParamGenerator& g3, - const ParamGenerator& g4, const ParamGenerator& g5, - const ParamGenerator& g6, const ParamGenerator& g7) - : g1_(g1), g2_(g2), g3_(g3), g4_(g4), g5_(g5), g6_(g6), g7_(g7) {} - virtual ~CartesianProductGenerator7() {} - - virtual ParamIteratorInterface* Begin() const { - return new Iterator(this, g1_, g1_.begin(), g2_, g2_.begin(), g3_, - g3_.begin(), g4_, g4_.begin(), g5_, g5_.begin(), g6_, g6_.begin(), g7_, - g7_.begin()); - } - virtual ParamIteratorInterface* End() const { - return new Iterator(this, g1_, g1_.end(), g2_, g2_.end(), g3_, g3_.end(), - g4_, g4_.end(), g5_, g5_.end(), g6_, g6_.end(), g7_, g7_.end()); - } - - private: - class Iterator : public ParamIteratorInterface { - public: - Iterator(const ParamGeneratorInterface* base, - const ParamGenerator& g1, - const typename ParamGenerator::iterator& current1, - const ParamGenerator& g2, - const typename ParamGenerator::iterator& current2, - const ParamGenerator& g3, - const typename ParamGenerator::iterator& current3, - const ParamGenerator& g4, - const typename ParamGenerator::iterator& current4, - const ParamGenerator& g5, - const typename ParamGenerator::iterator& current5, - const ParamGenerator& g6, - const typename ParamGenerator::iterator& current6, - const ParamGenerator& g7, - const typename ParamGenerator::iterator& current7) - : base_(base), - begin1_(g1.begin()), end1_(g1.end()), current1_(current1), - begin2_(g2.begin()), end2_(g2.end()), current2_(current2), - begin3_(g3.begin()), end3_(g3.end()), current3_(current3), - begin4_(g4.begin()), end4_(g4.end()), current4_(current4), - begin5_(g5.begin()), end5_(g5.end()), current5_(current5), - begin6_(g6.begin()), end6_(g6.end()), current6_(current6), - begin7_(g7.begin()), end7_(g7.end()), current7_(current7) { - ComputeCurrentValue(); - } - virtual ~Iterator() {} - - virtual const ParamGeneratorInterface* BaseGenerator() const { - return base_; - } - // Advance should not be called on beyond-of-range iterators - // so no component iterators must be beyond end of range, either. - virtual void Advance() { - assert(!AtEnd()); - ++current7_; - if (current7_ == end7_) { - current7_ = begin7_; - ++current6_; - } - if (current6_ == end6_) { - current6_ = begin6_; - ++current5_; - } - if (current5_ == end5_) { - current5_ = begin5_; - ++current4_; - } - if (current4_ == end4_) { - current4_ = begin4_; - ++current3_; - } - if (current3_ == end3_) { - current3_ = begin3_; - ++current2_; - } - if (current2_ == end2_) { - current2_ = begin2_; - ++current1_; - } - ComputeCurrentValue(); - } - virtual ParamIteratorInterface* Clone() const { - return new Iterator(*this); - } - virtual const ParamType* Current() const { return ¤t_value_; } - virtual bool Equals(const ParamIteratorInterface& other) const { - // Having the same base generator guarantees that the other - // iterator is of the same type and we can downcast. - GTEST_CHECK_(BaseGenerator() == other.BaseGenerator()) - << "The program attempted to compare iterators " - << "from different generators." << std::endl; - const Iterator* typed_other = - CheckedDowncastToActualType(&other); - // We must report iterators equal if they both point beyond their - // respective ranges. That can happen in a variety of fashions, - // so we have to consult AtEnd(). - return (AtEnd() && typed_other->AtEnd()) || - ( - current1_ == typed_other->current1_ && - current2_ == typed_other->current2_ && - current3_ == typed_other->current3_ && - current4_ == typed_other->current4_ && - current5_ == typed_other->current5_ && - current6_ == typed_other->current6_ && - current7_ == typed_other->current7_); - } - - private: - Iterator(const Iterator& other) - : base_(other.base_), - begin1_(other.begin1_), - end1_(other.end1_), - current1_(other.current1_), - begin2_(other.begin2_), - end2_(other.end2_), - current2_(other.current2_), - begin3_(other.begin3_), - end3_(other.end3_), - current3_(other.current3_), - begin4_(other.begin4_), - end4_(other.end4_), - current4_(other.current4_), - begin5_(other.begin5_), - end5_(other.end5_), - current5_(other.current5_), - begin6_(other.begin6_), - end6_(other.end6_), - current6_(other.current6_), - begin7_(other.begin7_), - end7_(other.end7_), - current7_(other.current7_) { - ComputeCurrentValue(); - } - - void ComputeCurrentValue() { - if (!AtEnd()) - current_value_ = ParamType(*current1_, *current2_, *current3_, - *current4_, *current5_, *current6_, *current7_); - } - bool AtEnd() const { - // We must report iterator past the end of the range when either of the - // component iterators has reached the end of its range. - return - current1_ == end1_ || - current2_ == end2_ || - current3_ == end3_ || - current4_ == end4_ || - current5_ == end5_ || - current6_ == end6_ || - current7_ == end7_; - } - - // No implementation - assignment is unsupported. - void operator=(const Iterator& other); - - const ParamGeneratorInterface* const base_; - // begin[i]_ and end[i]_ define the i-th range that Iterator traverses. - // current[i]_ is the actual traversing iterator. - const typename ParamGenerator::iterator begin1_; - const typename ParamGenerator::iterator end1_; - typename ParamGenerator::iterator current1_; - const typename ParamGenerator::iterator begin2_; - const typename ParamGenerator::iterator end2_; - typename ParamGenerator::iterator current2_; - const typename ParamGenerator::iterator begin3_; - const typename ParamGenerator::iterator end3_; - typename ParamGenerator::iterator current3_; - const typename ParamGenerator::iterator begin4_; - const typename ParamGenerator::iterator end4_; - typename ParamGenerator::iterator current4_; - const typename ParamGenerator::iterator begin5_; - const typename ParamGenerator::iterator end5_; - typename ParamGenerator::iterator current5_; - const typename ParamGenerator::iterator begin6_; - const typename ParamGenerator::iterator end6_; - typename ParamGenerator::iterator current6_; - const typename ParamGenerator::iterator begin7_; - const typename ParamGenerator::iterator end7_; - typename ParamGenerator::iterator current7_; - ParamType current_value_; - }; // class CartesianProductGenerator7::Iterator - - // No implementation - assignment is unsupported. - void operator=(const CartesianProductGenerator7& other); - - const ParamGenerator g1_; - const ParamGenerator g2_; - const ParamGenerator g3_; - const ParamGenerator g4_; - const ParamGenerator g5_; - const ParamGenerator g6_; - const ParamGenerator g7_; -}; // class CartesianProductGenerator7 - - -template -class CartesianProductGenerator8 - : public ParamGeneratorInterface< ::std::tr1::tuple > { - public: - typedef ::std::tr1::tuple ParamType; - - CartesianProductGenerator8(const ParamGenerator& g1, - const ParamGenerator& g2, const ParamGenerator& g3, - const ParamGenerator& g4, const ParamGenerator& g5, - const ParamGenerator& g6, const ParamGenerator& g7, - const ParamGenerator& g8) - : g1_(g1), g2_(g2), g3_(g3), g4_(g4), g5_(g5), g6_(g6), g7_(g7), - g8_(g8) {} - virtual ~CartesianProductGenerator8() {} - - virtual ParamIteratorInterface* Begin() const { - return new Iterator(this, g1_, g1_.begin(), g2_, g2_.begin(), g3_, - g3_.begin(), g4_, g4_.begin(), g5_, g5_.begin(), g6_, g6_.begin(), g7_, - g7_.begin(), g8_, g8_.begin()); - } - virtual ParamIteratorInterface* End() const { - return new Iterator(this, g1_, g1_.end(), g2_, g2_.end(), g3_, g3_.end(), - g4_, g4_.end(), g5_, g5_.end(), g6_, g6_.end(), g7_, g7_.end(), g8_, - g8_.end()); - } - - private: - class Iterator : public ParamIteratorInterface { - public: - Iterator(const ParamGeneratorInterface* base, - const ParamGenerator& g1, - const typename ParamGenerator::iterator& current1, - const ParamGenerator& g2, - const typename ParamGenerator::iterator& current2, - const ParamGenerator& g3, - const typename ParamGenerator::iterator& current3, - const ParamGenerator& g4, - const typename ParamGenerator::iterator& current4, - const ParamGenerator& g5, - const typename ParamGenerator::iterator& current5, - const ParamGenerator& g6, - const typename ParamGenerator::iterator& current6, - const ParamGenerator& g7, - const typename ParamGenerator::iterator& current7, - const ParamGenerator& g8, - const typename ParamGenerator::iterator& current8) - : base_(base), - begin1_(g1.begin()), end1_(g1.end()), current1_(current1), - begin2_(g2.begin()), end2_(g2.end()), current2_(current2), - begin3_(g3.begin()), end3_(g3.end()), current3_(current3), - begin4_(g4.begin()), end4_(g4.end()), current4_(current4), - begin5_(g5.begin()), end5_(g5.end()), current5_(current5), - begin6_(g6.begin()), end6_(g6.end()), current6_(current6), - begin7_(g7.begin()), end7_(g7.end()), current7_(current7), - begin8_(g8.begin()), end8_(g8.end()), current8_(current8) { - ComputeCurrentValue(); - } - virtual ~Iterator() {} - - virtual const ParamGeneratorInterface* BaseGenerator() const { - return base_; - } - // Advance should not be called on beyond-of-range iterators - // so no component iterators must be beyond end of range, either. - virtual void Advance() { - assert(!AtEnd()); - ++current8_; - if (current8_ == end8_) { - current8_ = begin8_; - ++current7_; - } - if (current7_ == end7_) { - current7_ = begin7_; - ++current6_; - } - if (current6_ == end6_) { - current6_ = begin6_; - ++current5_; - } - if (current5_ == end5_) { - current5_ = begin5_; - ++current4_; - } - if (current4_ == end4_) { - current4_ = begin4_; - ++current3_; - } - if (current3_ == end3_) { - current3_ = begin3_; - ++current2_; - } - if (current2_ == end2_) { - current2_ = begin2_; - ++current1_; - } - ComputeCurrentValue(); - } - virtual ParamIteratorInterface* Clone() const { - return new Iterator(*this); - } - virtual const ParamType* Current() const { return ¤t_value_; } - virtual bool Equals(const ParamIteratorInterface& other) const { - // Having the same base generator guarantees that the other - // iterator is of the same type and we can downcast. - GTEST_CHECK_(BaseGenerator() == other.BaseGenerator()) - << "The program attempted to compare iterators " - << "from different generators." << std::endl; - const Iterator* typed_other = - CheckedDowncastToActualType(&other); - // We must report iterators equal if they both point beyond their - // respective ranges. That can happen in a variety of fashions, - // so we have to consult AtEnd(). - return (AtEnd() && typed_other->AtEnd()) || - ( - current1_ == typed_other->current1_ && - current2_ == typed_other->current2_ && - current3_ == typed_other->current3_ && - current4_ == typed_other->current4_ && - current5_ == typed_other->current5_ && - current6_ == typed_other->current6_ && - current7_ == typed_other->current7_ && - current8_ == typed_other->current8_); - } - - private: - Iterator(const Iterator& other) - : base_(other.base_), - begin1_(other.begin1_), - end1_(other.end1_), - current1_(other.current1_), - begin2_(other.begin2_), - end2_(other.end2_), - current2_(other.current2_), - begin3_(other.begin3_), - end3_(other.end3_), - current3_(other.current3_), - begin4_(other.begin4_), - end4_(other.end4_), - current4_(other.current4_), - begin5_(other.begin5_), - end5_(other.end5_), - current5_(other.current5_), - begin6_(other.begin6_), - end6_(other.end6_), - current6_(other.current6_), - begin7_(other.begin7_), - end7_(other.end7_), - current7_(other.current7_), - begin8_(other.begin8_), - end8_(other.end8_), - current8_(other.current8_) { - ComputeCurrentValue(); - } - - void ComputeCurrentValue() { - if (!AtEnd()) - current_value_ = ParamType(*current1_, *current2_, *current3_, - *current4_, *current5_, *current6_, *current7_, *current8_); - } - bool AtEnd() const { - // We must report iterator past the end of the range when either of the - // component iterators has reached the end of its range. - return - current1_ == end1_ || - current2_ == end2_ || - current3_ == end3_ || - current4_ == end4_ || - current5_ == end5_ || - current6_ == end6_ || - current7_ == end7_ || - current8_ == end8_; - } - - // No implementation - assignment is unsupported. - void operator=(const Iterator& other); - - const ParamGeneratorInterface* const base_; - // begin[i]_ and end[i]_ define the i-th range that Iterator traverses. - // current[i]_ is the actual traversing iterator. - const typename ParamGenerator::iterator begin1_; - const typename ParamGenerator::iterator end1_; - typename ParamGenerator::iterator current1_; - const typename ParamGenerator::iterator begin2_; - const typename ParamGenerator::iterator end2_; - typename ParamGenerator::iterator current2_; - const typename ParamGenerator::iterator begin3_; - const typename ParamGenerator::iterator end3_; - typename ParamGenerator::iterator current3_; - const typename ParamGenerator::iterator begin4_; - const typename ParamGenerator::iterator end4_; - typename ParamGenerator::iterator current4_; - const typename ParamGenerator::iterator begin5_; - const typename ParamGenerator::iterator end5_; - typename ParamGenerator::iterator current5_; - const typename ParamGenerator::iterator begin6_; - const typename ParamGenerator::iterator end6_; - typename ParamGenerator::iterator current6_; - const typename ParamGenerator::iterator begin7_; - const typename ParamGenerator::iterator end7_; - typename ParamGenerator::iterator current7_; - const typename ParamGenerator::iterator begin8_; - const typename ParamGenerator::iterator end8_; - typename ParamGenerator::iterator current8_; - ParamType current_value_; - }; // class CartesianProductGenerator8::Iterator - - // No implementation - assignment is unsupported. - void operator=(const CartesianProductGenerator8& other); - - const ParamGenerator g1_; - const ParamGenerator g2_; - const ParamGenerator g3_; - const ParamGenerator g4_; - const ParamGenerator g5_; - const ParamGenerator g6_; - const ParamGenerator g7_; - const ParamGenerator g8_; -}; // class CartesianProductGenerator8 - - -template -class CartesianProductGenerator9 - : public ParamGeneratorInterface< ::std::tr1::tuple > { - public: - typedef ::std::tr1::tuple ParamType; - - CartesianProductGenerator9(const ParamGenerator& g1, - const ParamGenerator& g2, const ParamGenerator& g3, - const ParamGenerator& g4, const ParamGenerator& g5, - const ParamGenerator& g6, const ParamGenerator& g7, - const ParamGenerator& g8, const ParamGenerator& g9) - : g1_(g1), g2_(g2), g3_(g3), g4_(g4), g5_(g5), g6_(g6), g7_(g7), g8_(g8), - g9_(g9) {} - virtual ~CartesianProductGenerator9() {} - - virtual ParamIteratorInterface* Begin() const { - return new Iterator(this, g1_, g1_.begin(), g2_, g2_.begin(), g3_, - g3_.begin(), g4_, g4_.begin(), g5_, g5_.begin(), g6_, g6_.begin(), g7_, - g7_.begin(), g8_, g8_.begin(), g9_, g9_.begin()); - } - virtual ParamIteratorInterface* End() const { - return new Iterator(this, g1_, g1_.end(), g2_, g2_.end(), g3_, g3_.end(), - g4_, g4_.end(), g5_, g5_.end(), g6_, g6_.end(), g7_, g7_.end(), g8_, - g8_.end(), g9_, g9_.end()); - } - - private: - class Iterator : public ParamIteratorInterface { - public: - Iterator(const ParamGeneratorInterface* base, - const ParamGenerator& g1, - const typename ParamGenerator::iterator& current1, - const ParamGenerator& g2, - const typename ParamGenerator::iterator& current2, - const ParamGenerator& g3, - const typename ParamGenerator::iterator& current3, - const ParamGenerator& g4, - const typename ParamGenerator::iterator& current4, - const ParamGenerator& g5, - const typename ParamGenerator::iterator& current5, - const ParamGenerator& g6, - const typename ParamGenerator::iterator& current6, - const ParamGenerator& g7, - const typename ParamGenerator::iterator& current7, - const ParamGenerator& g8, - const typename ParamGenerator::iterator& current8, - const ParamGenerator& g9, - const typename ParamGenerator::iterator& current9) - : base_(base), - begin1_(g1.begin()), end1_(g1.end()), current1_(current1), - begin2_(g2.begin()), end2_(g2.end()), current2_(current2), - begin3_(g3.begin()), end3_(g3.end()), current3_(current3), - begin4_(g4.begin()), end4_(g4.end()), current4_(current4), - begin5_(g5.begin()), end5_(g5.end()), current5_(current5), - begin6_(g6.begin()), end6_(g6.end()), current6_(current6), - begin7_(g7.begin()), end7_(g7.end()), current7_(current7), - begin8_(g8.begin()), end8_(g8.end()), current8_(current8), - begin9_(g9.begin()), end9_(g9.end()), current9_(current9) { - ComputeCurrentValue(); - } - virtual ~Iterator() {} - - virtual const ParamGeneratorInterface* BaseGenerator() const { - return base_; - } - // Advance should not be called on beyond-of-range iterators - // so no component iterators must be beyond end of range, either. - virtual void Advance() { - assert(!AtEnd()); - ++current9_; - if (current9_ == end9_) { - current9_ = begin9_; - ++current8_; - } - if (current8_ == end8_) { - current8_ = begin8_; - ++current7_; - } - if (current7_ == end7_) { - current7_ = begin7_; - ++current6_; - } - if (current6_ == end6_) { - current6_ = begin6_; - ++current5_; - } - if (current5_ == end5_) { - current5_ = begin5_; - ++current4_; - } - if (current4_ == end4_) { - current4_ = begin4_; - ++current3_; - } - if (current3_ == end3_) { - current3_ = begin3_; - ++current2_; - } - if (current2_ == end2_) { - current2_ = begin2_; - ++current1_; - } - ComputeCurrentValue(); - } - virtual ParamIteratorInterface* Clone() const { - return new Iterator(*this); - } - virtual const ParamType* Current() const { return ¤t_value_; } - virtual bool Equals(const ParamIteratorInterface& other) const { - // Having the same base generator guarantees that the other - // iterator is of the same type and we can downcast. - GTEST_CHECK_(BaseGenerator() == other.BaseGenerator()) - << "The program attempted to compare iterators " - << "from different generators." << std::endl; - const Iterator* typed_other = - CheckedDowncastToActualType(&other); - // We must report iterators equal if they both point beyond their - // respective ranges. That can happen in a variety of fashions, - // so we have to consult AtEnd(). - return (AtEnd() && typed_other->AtEnd()) || - ( - current1_ == typed_other->current1_ && - current2_ == typed_other->current2_ && - current3_ == typed_other->current3_ && - current4_ == typed_other->current4_ && - current5_ == typed_other->current5_ && - current6_ == typed_other->current6_ && - current7_ == typed_other->current7_ && - current8_ == typed_other->current8_ && - current9_ == typed_other->current9_); - } - - private: - Iterator(const Iterator& other) - : base_(other.base_), - begin1_(other.begin1_), - end1_(other.end1_), - current1_(other.current1_), - begin2_(other.begin2_), - end2_(other.end2_), - current2_(other.current2_), - begin3_(other.begin3_), - end3_(other.end3_), - current3_(other.current3_), - begin4_(other.begin4_), - end4_(other.end4_), - current4_(other.current4_), - begin5_(other.begin5_), - end5_(other.end5_), - current5_(other.current5_), - begin6_(other.begin6_), - end6_(other.end6_), - current6_(other.current6_), - begin7_(other.begin7_), - end7_(other.end7_), - current7_(other.current7_), - begin8_(other.begin8_), - end8_(other.end8_), - current8_(other.current8_), - begin9_(other.begin9_), - end9_(other.end9_), - current9_(other.current9_) { - ComputeCurrentValue(); - } - - void ComputeCurrentValue() { - if (!AtEnd()) - current_value_ = ParamType(*current1_, *current2_, *current3_, - *current4_, *current5_, *current6_, *current7_, *current8_, - *current9_); - } - bool AtEnd() const { - // We must report iterator past the end of the range when either of the - // component iterators has reached the end of its range. - return - current1_ == end1_ || - current2_ == end2_ || - current3_ == end3_ || - current4_ == end4_ || - current5_ == end5_ || - current6_ == end6_ || - current7_ == end7_ || - current8_ == end8_ || - current9_ == end9_; - } - - // No implementation - assignment is unsupported. - void operator=(const Iterator& other); - - const ParamGeneratorInterface* const base_; - // begin[i]_ and end[i]_ define the i-th range that Iterator traverses. - // current[i]_ is the actual traversing iterator. - const typename ParamGenerator::iterator begin1_; - const typename ParamGenerator::iterator end1_; - typename ParamGenerator::iterator current1_; - const typename ParamGenerator::iterator begin2_; - const typename ParamGenerator::iterator end2_; - typename ParamGenerator::iterator current2_; - const typename ParamGenerator::iterator begin3_; - const typename ParamGenerator::iterator end3_; - typename ParamGenerator::iterator current3_; - const typename ParamGenerator::iterator begin4_; - const typename ParamGenerator::iterator end4_; - typename ParamGenerator::iterator current4_; - const typename ParamGenerator::iterator begin5_; - const typename ParamGenerator::iterator end5_; - typename ParamGenerator::iterator current5_; - const typename ParamGenerator::iterator begin6_; - const typename ParamGenerator::iterator end6_; - typename ParamGenerator::iterator current6_; - const typename ParamGenerator::iterator begin7_; - const typename ParamGenerator::iterator end7_; - typename ParamGenerator::iterator current7_; - const typename ParamGenerator::iterator begin8_; - const typename ParamGenerator::iterator end8_; - typename ParamGenerator::iterator current8_; - const typename ParamGenerator::iterator begin9_; - const typename ParamGenerator::iterator end9_; - typename ParamGenerator::iterator current9_; - ParamType current_value_; - }; // class CartesianProductGenerator9::Iterator - - // No implementation - assignment is unsupported. - void operator=(const CartesianProductGenerator9& other); - - const ParamGenerator g1_; - const ParamGenerator g2_; - const ParamGenerator g3_; - const ParamGenerator g4_; - const ParamGenerator g5_; - const ParamGenerator g6_; - const ParamGenerator g7_; - const ParamGenerator g8_; - const ParamGenerator g9_; -}; // class CartesianProductGenerator9 - - -template -class CartesianProductGenerator10 - : public ParamGeneratorInterface< ::std::tr1::tuple > { - public: - typedef ::std::tr1::tuple ParamType; - - CartesianProductGenerator10(const ParamGenerator& g1, - const ParamGenerator& g2, const ParamGenerator& g3, - const ParamGenerator& g4, const ParamGenerator& g5, - const ParamGenerator& g6, const ParamGenerator& g7, - const ParamGenerator& g8, const ParamGenerator& g9, - const ParamGenerator& g10) - : g1_(g1), g2_(g2), g3_(g3), g4_(g4), g5_(g5), g6_(g6), g7_(g7), g8_(g8), - g9_(g9), g10_(g10) {} - virtual ~CartesianProductGenerator10() {} - - virtual ParamIteratorInterface* Begin() const { - return new Iterator(this, g1_, g1_.begin(), g2_, g2_.begin(), g3_, - g3_.begin(), g4_, g4_.begin(), g5_, g5_.begin(), g6_, g6_.begin(), g7_, - g7_.begin(), g8_, g8_.begin(), g9_, g9_.begin(), g10_, g10_.begin()); - } - virtual ParamIteratorInterface* End() const { - return new Iterator(this, g1_, g1_.end(), g2_, g2_.end(), g3_, g3_.end(), - g4_, g4_.end(), g5_, g5_.end(), g6_, g6_.end(), g7_, g7_.end(), g8_, - g8_.end(), g9_, g9_.end(), g10_, g10_.end()); - } - - private: - class Iterator : public ParamIteratorInterface { - public: - Iterator(const ParamGeneratorInterface* base, - const ParamGenerator& g1, - const typename ParamGenerator::iterator& current1, - const ParamGenerator& g2, - const typename ParamGenerator::iterator& current2, - const ParamGenerator& g3, - const typename ParamGenerator::iterator& current3, - const ParamGenerator& g4, - const typename ParamGenerator::iterator& current4, - const ParamGenerator& g5, - const typename ParamGenerator::iterator& current5, - const ParamGenerator& g6, - const typename ParamGenerator::iterator& current6, - const ParamGenerator& g7, - const typename ParamGenerator::iterator& current7, - const ParamGenerator& g8, - const typename ParamGenerator::iterator& current8, - const ParamGenerator& g9, - const typename ParamGenerator::iterator& current9, - const ParamGenerator& g10, - const typename ParamGenerator::iterator& current10) - : base_(base), - begin1_(g1.begin()), end1_(g1.end()), current1_(current1), - begin2_(g2.begin()), end2_(g2.end()), current2_(current2), - begin3_(g3.begin()), end3_(g3.end()), current3_(current3), - begin4_(g4.begin()), end4_(g4.end()), current4_(current4), - begin5_(g5.begin()), end5_(g5.end()), current5_(current5), - begin6_(g6.begin()), end6_(g6.end()), current6_(current6), - begin7_(g7.begin()), end7_(g7.end()), current7_(current7), - begin8_(g8.begin()), end8_(g8.end()), current8_(current8), - begin9_(g9.begin()), end9_(g9.end()), current9_(current9), - begin10_(g10.begin()), end10_(g10.end()), current10_(current10) { - ComputeCurrentValue(); - } - virtual ~Iterator() {} - - virtual const ParamGeneratorInterface* BaseGenerator() const { - return base_; - } - // Advance should not be called on beyond-of-range iterators - // so no component iterators must be beyond end of range, either. - virtual void Advance() { - assert(!AtEnd()); - ++current10_; - if (current10_ == end10_) { - current10_ = begin10_; - ++current9_; - } - if (current9_ == end9_) { - current9_ = begin9_; - ++current8_; - } - if (current8_ == end8_) { - current8_ = begin8_; - ++current7_; - } - if (current7_ == end7_) { - current7_ = begin7_; - ++current6_; - } - if (current6_ == end6_) { - current6_ = begin6_; - ++current5_; - } - if (current5_ == end5_) { - current5_ = begin5_; - ++current4_; - } - if (current4_ == end4_) { - current4_ = begin4_; - ++current3_; - } - if (current3_ == end3_) { - current3_ = begin3_; - ++current2_; - } - if (current2_ == end2_) { - current2_ = begin2_; - ++current1_; - } - ComputeCurrentValue(); - } - virtual ParamIteratorInterface* Clone() const { - return new Iterator(*this); - } - virtual const ParamType* Current() const { return ¤t_value_; } - virtual bool Equals(const ParamIteratorInterface& other) const { - // Having the same base generator guarantees that the other - // iterator is of the same type and we can downcast. - GTEST_CHECK_(BaseGenerator() == other.BaseGenerator()) - << "The program attempted to compare iterators " - << "from different generators." << std::endl; - const Iterator* typed_other = - CheckedDowncastToActualType(&other); - // We must report iterators equal if they both point beyond their - // respective ranges. That can happen in a variety of fashions, - // so we have to consult AtEnd(). - return (AtEnd() && typed_other->AtEnd()) || - ( - current1_ == typed_other->current1_ && - current2_ == typed_other->current2_ && - current3_ == typed_other->current3_ && - current4_ == typed_other->current4_ && - current5_ == typed_other->current5_ && - current6_ == typed_other->current6_ && - current7_ == typed_other->current7_ && - current8_ == typed_other->current8_ && - current9_ == typed_other->current9_ && - current10_ == typed_other->current10_); - } - - private: - Iterator(const Iterator& other) - : base_(other.base_), - begin1_(other.begin1_), - end1_(other.end1_), - current1_(other.current1_), - begin2_(other.begin2_), - end2_(other.end2_), - current2_(other.current2_), - begin3_(other.begin3_), - end3_(other.end3_), - current3_(other.current3_), - begin4_(other.begin4_), - end4_(other.end4_), - current4_(other.current4_), - begin5_(other.begin5_), - end5_(other.end5_), - current5_(other.current5_), - begin6_(other.begin6_), - end6_(other.end6_), - current6_(other.current6_), - begin7_(other.begin7_), - end7_(other.end7_), - current7_(other.current7_), - begin8_(other.begin8_), - end8_(other.end8_), - current8_(other.current8_), - begin9_(other.begin9_), - end9_(other.end9_), - current9_(other.current9_), - begin10_(other.begin10_), - end10_(other.end10_), - current10_(other.current10_) { - ComputeCurrentValue(); - } - - void ComputeCurrentValue() { - if (!AtEnd()) - current_value_ = ParamType(*current1_, *current2_, *current3_, - *current4_, *current5_, *current6_, *current7_, *current8_, - *current9_, *current10_); - } - bool AtEnd() const { - // We must report iterator past the end of the range when either of the - // component iterators has reached the end of its range. - return - current1_ == end1_ || - current2_ == end2_ || - current3_ == end3_ || - current4_ == end4_ || - current5_ == end5_ || - current6_ == end6_ || - current7_ == end7_ || - current8_ == end8_ || - current9_ == end9_ || - current10_ == end10_; - } - - // No implementation - assignment is unsupported. - void operator=(const Iterator& other); - - const ParamGeneratorInterface* const base_; - // begin[i]_ and end[i]_ define the i-th range that Iterator traverses. - // current[i]_ is the actual traversing iterator. - const typename ParamGenerator::iterator begin1_; - const typename ParamGenerator::iterator end1_; - typename ParamGenerator::iterator current1_; - const typename ParamGenerator::iterator begin2_; - const typename ParamGenerator::iterator end2_; - typename ParamGenerator::iterator current2_; - const typename ParamGenerator::iterator begin3_; - const typename ParamGenerator::iterator end3_; - typename ParamGenerator::iterator current3_; - const typename ParamGenerator::iterator begin4_; - const typename ParamGenerator::iterator end4_; - typename ParamGenerator::iterator current4_; - const typename ParamGenerator::iterator begin5_; - const typename ParamGenerator::iterator end5_; - typename ParamGenerator::iterator current5_; - const typename ParamGenerator::iterator begin6_; - const typename ParamGenerator::iterator end6_; - typename ParamGenerator::iterator current6_; - const typename ParamGenerator::iterator begin7_; - const typename ParamGenerator::iterator end7_; - typename ParamGenerator::iterator current7_; - const typename ParamGenerator::iterator begin8_; - const typename ParamGenerator::iterator end8_; - typename ParamGenerator::iterator current8_; - const typename ParamGenerator::iterator begin9_; - const typename ParamGenerator::iterator end9_; - typename ParamGenerator::iterator current9_; - const typename ParamGenerator::iterator begin10_; - const typename ParamGenerator::iterator end10_; - typename ParamGenerator::iterator current10_; - ParamType current_value_; - }; // class CartesianProductGenerator10::Iterator - - // No implementation - assignment is unsupported. - void operator=(const CartesianProductGenerator10& other); - - const ParamGenerator g1_; - const ParamGenerator g2_; - const ParamGenerator g3_; - const ParamGenerator g4_; - const ParamGenerator g5_; - const ParamGenerator g6_; - const ParamGenerator g7_; - const ParamGenerator g8_; - const ParamGenerator g9_; - const ParamGenerator g10_; -}; // class CartesianProductGenerator10 - - -// INTERNAL IMPLEMENTATION - DO NOT USE IN USER CODE. -// -// Helper classes providing Combine() with polymorphic features. They allow -// casting CartesianProductGeneratorN to ParamGenerator if T is -// convertible to U. -// -template -class CartesianProductHolder2 { - public: -CartesianProductHolder2(const Generator1& g1, const Generator2& g2) - : g1_(g1), g2_(g2) {} - template - operator ParamGenerator< ::std::tr1::tuple >() const { - return ParamGenerator< ::std::tr1::tuple >( - new CartesianProductGenerator2( - static_cast >(g1_), - static_cast >(g2_))); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const CartesianProductHolder2& other); - - const Generator1 g1_; - const Generator2 g2_; -}; // class CartesianProductHolder2 - -template -class CartesianProductHolder3 { - public: -CartesianProductHolder3(const Generator1& g1, const Generator2& g2, - const Generator3& g3) - : g1_(g1), g2_(g2), g3_(g3) {} - template - operator ParamGenerator< ::std::tr1::tuple >() const { - return ParamGenerator< ::std::tr1::tuple >( - new CartesianProductGenerator3( - static_cast >(g1_), - static_cast >(g2_), - static_cast >(g3_))); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const CartesianProductHolder3& other); - - const Generator1 g1_; - const Generator2 g2_; - const Generator3 g3_; -}; // class CartesianProductHolder3 - -template -class CartesianProductHolder4 { - public: -CartesianProductHolder4(const Generator1& g1, const Generator2& g2, - const Generator3& g3, const Generator4& g4) - : g1_(g1), g2_(g2), g3_(g3), g4_(g4) {} - template - operator ParamGenerator< ::std::tr1::tuple >() const { - return ParamGenerator< ::std::tr1::tuple >( - new CartesianProductGenerator4( - static_cast >(g1_), - static_cast >(g2_), - static_cast >(g3_), - static_cast >(g4_))); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const CartesianProductHolder4& other); - - const Generator1 g1_; - const Generator2 g2_; - const Generator3 g3_; - const Generator4 g4_; -}; // class CartesianProductHolder4 - -template -class CartesianProductHolder5 { - public: -CartesianProductHolder5(const Generator1& g1, const Generator2& g2, - const Generator3& g3, const Generator4& g4, const Generator5& g5) - : g1_(g1), g2_(g2), g3_(g3), g4_(g4), g5_(g5) {} - template - operator ParamGenerator< ::std::tr1::tuple >() const { - return ParamGenerator< ::std::tr1::tuple >( - new CartesianProductGenerator5( - static_cast >(g1_), - static_cast >(g2_), - static_cast >(g3_), - static_cast >(g4_), - static_cast >(g5_))); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const CartesianProductHolder5& other); - - const Generator1 g1_; - const Generator2 g2_; - const Generator3 g3_; - const Generator4 g4_; - const Generator5 g5_; -}; // class CartesianProductHolder5 - -template -class CartesianProductHolder6 { - public: -CartesianProductHolder6(const Generator1& g1, const Generator2& g2, - const Generator3& g3, const Generator4& g4, const Generator5& g5, - const Generator6& g6) - : g1_(g1), g2_(g2), g3_(g3), g4_(g4), g5_(g5), g6_(g6) {} - template - operator ParamGenerator< ::std::tr1::tuple >() const { - return ParamGenerator< ::std::tr1::tuple >( - new CartesianProductGenerator6( - static_cast >(g1_), - static_cast >(g2_), - static_cast >(g3_), - static_cast >(g4_), - static_cast >(g5_), - static_cast >(g6_))); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const CartesianProductHolder6& other); - - const Generator1 g1_; - const Generator2 g2_; - const Generator3 g3_; - const Generator4 g4_; - const Generator5 g5_; - const Generator6 g6_; -}; // class CartesianProductHolder6 - -template -class CartesianProductHolder7 { - public: -CartesianProductHolder7(const Generator1& g1, const Generator2& g2, - const Generator3& g3, const Generator4& g4, const Generator5& g5, - const Generator6& g6, const Generator7& g7) - : g1_(g1), g2_(g2), g3_(g3), g4_(g4), g5_(g5), g6_(g6), g7_(g7) {} - template - operator ParamGenerator< ::std::tr1::tuple >() const { - return ParamGenerator< ::std::tr1::tuple >( - new CartesianProductGenerator7( - static_cast >(g1_), - static_cast >(g2_), - static_cast >(g3_), - static_cast >(g4_), - static_cast >(g5_), - static_cast >(g6_), - static_cast >(g7_))); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const CartesianProductHolder7& other); - - const Generator1 g1_; - const Generator2 g2_; - const Generator3 g3_; - const Generator4 g4_; - const Generator5 g5_; - const Generator6 g6_; - const Generator7 g7_; -}; // class CartesianProductHolder7 - -template -class CartesianProductHolder8 { - public: -CartesianProductHolder8(const Generator1& g1, const Generator2& g2, - const Generator3& g3, const Generator4& g4, const Generator5& g5, - const Generator6& g6, const Generator7& g7, const Generator8& g8) - : g1_(g1), g2_(g2), g3_(g3), g4_(g4), g5_(g5), g6_(g6), g7_(g7), - g8_(g8) {} - template - operator ParamGenerator< ::std::tr1::tuple >() const { - return ParamGenerator< ::std::tr1::tuple >( - new CartesianProductGenerator8( - static_cast >(g1_), - static_cast >(g2_), - static_cast >(g3_), - static_cast >(g4_), - static_cast >(g5_), - static_cast >(g6_), - static_cast >(g7_), - static_cast >(g8_))); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const CartesianProductHolder8& other); - - const Generator1 g1_; - const Generator2 g2_; - const Generator3 g3_; - const Generator4 g4_; - const Generator5 g5_; - const Generator6 g6_; - const Generator7 g7_; - const Generator8 g8_; -}; // class CartesianProductHolder8 - -template -class CartesianProductHolder9 { - public: -CartesianProductHolder9(const Generator1& g1, const Generator2& g2, - const Generator3& g3, const Generator4& g4, const Generator5& g5, - const Generator6& g6, const Generator7& g7, const Generator8& g8, - const Generator9& g9) - : g1_(g1), g2_(g2), g3_(g3), g4_(g4), g5_(g5), g6_(g6), g7_(g7), g8_(g8), - g9_(g9) {} - template - operator ParamGenerator< ::std::tr1::tuple >() const { - return ParamGenerator< ::std::tr1::tuple >( - new CartesianProductGenerator9( - static_cast >(g1_), - static_cast >(g2_), - static_cast >(g3_), - static_cast >(g4_), - static_cast >(g5_), - static_cast >(g6_), - static_cast >(g7_), - static_cast >(g8_), - static_cast >(g9_))); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const CartesianProductHolder9& other); - - const Generator1 g1_; - const Generator2 g2_; - const Generator3 g3_; - const Generator4 g4_; - const Generator5 g5_; - const Generator6 g6_; - const Generator7 g7_; - const Generator8 g8_; - const Generator9 g9_; -}; // class CartesianProductHolder9 - -template -class CartesianProductHolder10 { - public: -CartesianProductHolder10(const Generator1& g1, const Generator2& g2, - const Generator3& g3, const Generator4& g4, const Generator5& g5, - const Generator6& g6, const Generator7& g7, const Generator8& g8, - const Generator9& g9, const Generator10& g10) - : g1_(g1), g2_(g2), g3_(g3), g4_(g4), g5_(g5), g6_(g6), g7_(g7), g8_(g8), - g9_(g9), g10_(g10) {} - template - operator ParamGenerator< ::std::tr1::tuple >() const { - return ParamGenerator< ::std::tr1::tuple >( - new CartesianProductGenerator10( - static_cast >(g1_), - static_cast >(g2_), - static_cast >(g3_), - static_cast >(g4_), - static_cast >(g5_), - static_cast >(g6_), - static_cast >(g7_), - static_cast >(g8_), - static_cast >(g9_), - static_cast >(g10_))); - } - - private: - // No implementation - assignment is unsupported. - void operator=(const CartesianProductHolder10& other); - - const Generator1 g1_; - const Generator2 g2_; - const Generator3 g3_; - const Generator4 g4_; - const Generator5 g5_; - const Generator6 g6_; - const Generator7 g7_; - const Generator8 g8_; - const Generator9 g9_; - const Generator10 g10_; -}; // class CartesianProductHolder10 - -# endif // GTEST_HAS_COMBINE - -} // namespace internal -} // namespace testing - -#endif // GTEST_HAS_PARAM_TEST - -#endif // GTEST_INCLUDE_GTEST_INTERNAL_GTEST_PARAM_UTIL_GENERATED_H_ - -#if GTEST_HAS_PARAM_TEST - -namespace testing { - -// Functions producing parameter generators. -// -// Google Test uses these generators to produce parameters for value- -// parameterized tests. When a parameterized test case is instantiated -// with a particular generator, Google Test creates and runs tests -// for each element in the sequence produced by the generator. -// -// In the following sample, tests from test case FooTest are instantiated -// each three times with parameter values 3, 5, and 8: -// -// class FooTest : public TestWithParam { ... }; -// -// TEST_P(FooTest, TestThis) { -// } -// TEST_P(FooTest, TestThat) { -// } -// INSTANTIATE_TEST_CASE_P(TestSequence, FooTest, Values(3, 5, 8)); -// - -// Range() returns generators providing sequences of values in a range. -// -// Synopsis: -// Range(start, end) -// - returns a generator producing a sequence of values {start, start+1, -// start+2, ..., }. -// Range(start, end, step) -// - returns a generator producing a sequence of values {start, start+step, -// start+step+step, ..., }. -// Notes: -// * The generated sequences never include end. For example, Range(1, 5) -// returns a generator producing a sequence {1, 2, 3, 4}. Range(1, 9, 2) -// returns a generator producing {1, 3, 5, 7}. -// * start and end must have the same type. That type may be any integral or -// floating-point type or a user defined type satisfying these conditions: -// * It must be assignable (have operator=() defined). -// * It must have operator+() (operator+(int-compatible type) for -// two-operand version). -// * It must have operator<() defined. -// Elements in the resulting sequences will also have that type. -// * Condition start < end must be satisfied in order for resulting sequences -// to contain any elements. -// -template -internal::ParamGenerator Range(T start, T end, IncrementT step) { - return internal::ParamGenerator( - new internal::RangeGenerator(start, end, step)); -} - -template -internal::ParamGenerator Range(T start, T end) { - return Range(start, end, 1); -} - -// ValuesIn() function allows generation of tests with parameters coming from -// a container. -// -// Synopsis: -// ValuesIn(const T (&array)[N]) -// - returns a generator producing sequences with elements from -// a C-style array. -// ValuesIn(const Container& container) -// - returns a generator producing sequences with elements from -// an STL-style container. -// ValuesIn(Iterator begin, Iterator end) -// - returns a generator producing sequences with elements from -// a range [begin, end) defined by a pair of STL-style iterators. These -// iterators can also be plain C pointers. -// -// Please note that ValuesIn copies the values from the containers -// passed in and keeps them to generate tests in RUN_ALL_TESTS(). -// -// Examples: -// -// This instantiates tests from test case StringTest -// each with C-string values of "foo", "bar", and "baz": -// -// const char* strings[] = {"foo", "bar", "baz"}; -// INSTANTIATE_TEST_CASE_P(StringSequence, SrtingTest, ValuesIn(strings)); -// -// This instantiates tests from test case StlStringTest -// each with STL strings with values "a" and "b": -// -// ::std::vector< ::std::string> GetParameterStrings() { -// ::std::vector< ::std::string> v; -// v.push_back("a"); -// v.push_back("b"); -// return v; -// } -// -// INSTANTIATE_TEST_CASE_P(CharSequence, -// StlStringTest, -// ValuesIn(GetParameterStrings())); -// -// -// This will also instantiate tests from CharTest -// each with parameter values 'a' and 'b': -// -// ::std::list GetParameterChars() { -// ::std::list list; -// list.push_back('a'); -// list.push_back('b'); -// return list; -// } -// ::std::list l = GetParameterChars(); -// INSTANTIATE_TEST_CASE_P(CharSequence2, -// CharTest, -// ValuesIn(l.begin(), l.end())); -// -template -internal::ParamGenerator< - typename ::testing::internal::IteratorTraits::value_type> -ValuesIn(ForwardIterator begin, ForwardIterator end) { - typedef typename ::testing::internal::IteratorTraits - ::value_type ParamType; - return internal::ParamGenerator( - new internal::ValuesInIteratorRangeGenerator(begin, end)); -} - -template -internal::ParamGenerator ValuesIn(const T (&array)[N]) { - return ValuesIn(array, array + N); -} - -template -internal::ParamGenerator ValuesIn( - const Container& container) { - return ValuesIn(container.begin(), container.end()); -} - -// Values() allows generating tests from explicitly specified list of -// parameters. -// -// Synopsis: -// Values(T v1, T v2, ..., T vN) -// - returns a generator producing sequences with elements v1, v2, ..., vN. -// -// For example, this instantiates tests from test case BarTest each -// with values "one", "two", and "three": -// -// INSTANTIATE_TEST_CASE_P(NumSequence, BarTest, Values("one", "two", "three")); -// -// This instantiates tests from test case BazTest each with values 1, 2, 3.5. -// The exact type of values will depend on the type of parameter in BazTest. -// -// INSTANTIATE_TEST_CASE_P(FloatingNumbers, BazTest, Values(1, 2, 3.5)); -// -// Currently, Values() supports from 1 to 50 parameters. -// -template -internal::ValueArray1 Values(T1 v1) { - return internal::ValueArray1(v1); -} - -template -internal::ValueArray2 Values(T1 v1, T2 v2) { - return internal::ValueArray2(v1, v2); -} - -template -internal::ValueArray3 Values(T1 v1, T2 v2, T3 v3) { - return internal::ValueArray3(v1, v2, v3); -} - -template -internal::ValueArray4 Values(T1 v1, T2 v2, T3 v3, T4 v4) { - return internal::ValueArray4(v1, v2, v3, v4); -} - -template -internal::ValueArray5 Values(T1 v1, T2 v2, T3 v3, T4 v4, - T5 v5) { - return internal::ValueArray5(v1, v2, v3, v4, v5); -} - -template -internal::ValueArray6 Values(T1 v1, T2 v2, T3 v3, - T4 v4, T5 v5, T6 v6) { - return internal::ValueArray6(v1, v2, v3, v4, v5, v6); -} - -template -internal::ValueArray7 Values(T1 v1, T2 v2, T3 v3, - T4 v4, T5 v5, T6 v6, T7 v7) { - return internal::ValueArray7(v1, v2, v3, v4, v5, - v6, v7); -} - -template -internal::ValueArray8 Values(T1 v1, T2 v2, - T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8) { - return internal::ValueArray8(v1, v2, v3, v4, - v5, v6, v7, v8); -} - -template -internal::ValueArray9 Values(T1 v1, T2 v2, - T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9) { - return internal::ValueArray9(v1, v2, v3, - v4, v5, v6, v7, v8, v9); -} - -template -internal::ValueArray10 Values(T1 v1, - T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, T10 v10) { - return internal::ValueArray10(v1, - v2, v3, v4, v5, v6, v7, v8, v9, v10); -} - -template -internal::ValueArray11 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11) { - return internal::ValueArray11(v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11); -} - -template -internal::ValueArray12 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12) { - return internal::ValueArray12(v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12); -} - -template -internal::ValueArray13 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13) { - return internal::ValueArray13(v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13); -} - -template -internal::ValueArray14 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14) { - return internal::ValueArray14(v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, - v14); -} - -template -internal::ValueArray15 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, - T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15) { - return internal::ValueArray15(v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, - v13, v14, v15); -} - -template -internal::ValueArray16 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, - T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, - T16 v16) { - return internal::ValueArray16(v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, - v12, v13, v14, v15, v16); -} - -template -internal::ValueArray17 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, - T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, - T16 v16, T17 v17) { - return internal::ValueArray17(v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, - v11, v12, v13, v14, v15, v16, v17); -} - -template -internal::ValueArray18 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, - T7 v7, T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, - T16 v16, T17 v17, T18 v18) { - return internal::ValueArray18(v1, v2, v3, v4, v5, v6, v7, v8, v9, - v10, v11, v12, v13, v14, v15, v16, v17, v18); -} - -template -internal::ValueArray19 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, - T6 v6, T7 v7, T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, - T15 v15, T16 v16, T17 v17, T18 v18, T19 v19) { - return internal::ValueArray19(v1, v2, v3, v4, v5, v6, v7, v8, - v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19); -} - -template -internal::ValueArray20 Values(T1 v1, T2 v2, T3 v3, T4 v4, - T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, - T14 v14, T15 v15, T16 v16, T17 v17, T18 v18, T19 v19, T20 v20) { - return internal::ValueArray20(v1, v2, v3, v4, v5, v6, v7, - v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20); -} - -template -internal::ValueArray21 Values(T1 v1, T2 v2, T3 v3, T4 v4, - T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, - T14 v14, T15 v15, T16 v16, T17 v17, T18 v18, T19 v19, T20 v20, T21 v21) { - return internal::ValueArray21(v1, v2, v3, v4, v5, v6, - v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21); -} - -template -internal::ValueArray22 Values(T1 v1, T2 v2, T3 v3, - T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, - T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, T18 v18, T19 v19, T20 v20, - T21 v21, T22 v22) { - return internal::ValueArray22(v1, v2, v3, v4, - v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, - v20, v21, v22); -} - -template -internal::ValueArray23 Values(T1 v1, T2 v2, - T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, - T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, T18 v18, T19 v19, T20 v20, - T21 v21, T22 v22, T23 v23) { - return internal::ValueArray23(v1, v2, v3, - v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, - v20, v21, v22, v23); -} - -template -internal::ValueArray24 Values(T1 v1, T2 v2, - T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, - T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, T18 v18, T19 v19, T20 v20, - T21 v21, T22 v22, T23 v23, T24 v24) { - return internal::ValueArray24(v1, v2, - v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, - v19, v20, v21, v22, v23, v24); -} - -template -internal::ValueArray25 Values(T1 v1, - T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, T10 v10, T11 v11, - T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, T18 v18, T19 v19, - T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25) { - return internal::ValueArray25(v1, - v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, - v18, v19, v20, v21, v22, v23, v24, v25); -} - -template -internal::ValueArray26 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26) { - return internal::ValueArray26(v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, - v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26); -} - -template -internal::ValueArray27 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27) { - return internal::ValueArray27(v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, - v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27); -} - -template -internal::ValueArray28 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28) { - return internal::ValueArray28(v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, - v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, - v28); -} - -template -internal::ValueArray29 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29) { - return internal::ValueArray29(v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, - v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, - v27, v28, v29); -} - -template -internal::ValueArray30 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, - T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, - T17 v17, T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, - T25 v25, T26 v26, T27 v27, T28 v28, T29 v29, T30 v30) { - return internal::ValueArray30(v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, - v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, - v26, v27, v28, v29, v30); -} - -template -internal::ValueArray31 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, - T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, - T16 v16, T17 v17, T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, - T24 v24, T25 v25, T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31) { - return internal::ValueArray31(v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, - v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, - v25, v26, v27, v28, v29, v30, v31); -} - -template -internal::ValueArray32 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, - T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, - T16 v16, T17 v17, T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, - T24 v24, T25 v25, T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, - T32 v32) { - return internal::ValueArray32(v1, v2, v3, v4, v5, v6, v7, v8, v9, - v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, - v24, v25, v26, v27, v28, v29, v30, v31, v32); -} - -template -internal::ValueArray33 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, - T7 v7, T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, - T16 v16, T17 v17, T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, - T24 v24, T25 v25, T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, - T32 v32, T33 v33) { - return internal::ValueArray33(v1, v2, v3, v4, v5, v6, v7, v8, - v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, - v24, v25, v26, v27, v28, v29, v30, v31, v32, v33); -} - -template -internal::ValueArray34 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, - T6 v6, T7 v7, T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, - T15 v15, T16 v16, T17 v17, T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, - T23 v23, T24 v24, T25 v25, T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, - T31 v31, T32 v32, T33 v33, T34 v34) { - return internal::ValueArray34(v1, v2, v3, v4, v5, v6, v7, - v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, - v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34); -} - -template -internal::ValueArray35 Values(T1 v1, T2 v2, T3 v3, T4 v4, - T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, - T14 v14, T15 v15, T16 v16, T17 v17, T18 v18, T19 v19, T20 v20, T21 v21, - T22 v22, T23 v23, T24 v24, T25 v25, T26 v26, T27 v27, T28 v28, T29 v29, - T30 v30, T31 v31, T32 v32, T33 v33, T34 v34, T35 v35) { - return internal::ValueArray35(v1, v2, v3, v4, v5, v6, - v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, - v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35); -} - -template -internal::ValueArray36 Values(T1 v1, T2 v2, T3 v3, T4 v4, - T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, - T14 v14, T15 v15, T16 v16, T17 v17, T18 v18, T19 v19, T20 v20, T21 v21, - T22 v22, T23 v23, T24 v24, T25 v25, T26 v26, T27 v27, T28 v28, T29 v29, - T30 v30, T31 v31, T32 v32, T33 v33, T34 v34, T35 v35, T36 v36) { - return internal::ValueArray36(v1, v2, v3, v4, - v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, - v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, - v34, v35, v36); -} - -template -internal::ValueArray37 Values(T1 v1, T2 v2, T3 v3, - T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, - T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, T18 v18, T19 v19, T20 v20, - T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, T26 v26, T27 v27, T28 v28, - T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, T34 v34, T35 v35, T36 v36, - T37 v37) { - return internal::ValueArray37(v1, v2, v3, - v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, - v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, - v34, v35, v36, v37); -} - -template -internal::ValueArray38 Values(T1 v1, T2 v2, - T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, - T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, T18 v18, T19 v19, T20 v20, - T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, T26 v26, T27 v27, T28 v28, - T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, T34 v34, T35 v35, T36 v36, - T37 v37, T38 v38) { - return internal::ValueArray38(v1, v2, - v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, - v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, - v33, v34, v35, v36, v37, v38); -} - -template -internal::ValueArray39 Values(T1 v1, T2 v2, - T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, - T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, T18 v18, T19 v19, T20 v20, - T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, T26 v26, T27 v27, T28 v28, - T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, T34 v34, T35 v35, T36 v36, - T37 v37, T38 v38, T39 v39) { - return internal::ValueArray39(v1, - v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, - v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, - v32, v33, v34, v35, v36, v37, v38, v39); -} - -template -internal::ValueArray40 Values(T1 v1, - T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, T10 v10, T11 v11, - T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, T18 v18, T19 v19, - T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, T26 v26, T27 v27, - T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, T34 v34, T35 v35, - T36 v36, T37 v37, T38 v38, T39 v39, T40 v40) { - return internal::ValueArray40(v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, - v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, - v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40); -} - -template -internal::ValueArray41 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39, T40 v40, T41 v41) { - return internal::ValueArray41(v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, - v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, - v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41); -} - -template -internal::ValueArray42 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39, T40 v40, T41 v41, - T42 v42) { - return internal::ValueArray42(v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, - v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, - v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, - v42); -} - -template -internal::ValueArray43 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39, T40 v40, T41 v41, - T42 v42, T43 v43) { - return internal::ValueArray43(v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, - v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, - v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, - v41, v42, v43); -} - -template -internal::ValueArray44 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, - T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, T17 v17, - T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, T25 v25, - T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, T33 v33, - T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39, T40 v40, T41 v41, - T42 v42, T43 v43, T44 v44) { - return internal::ValueArray44(v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, - v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, - v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, - v40, v41, v42, v43, v44); -} - -template -internal::ValueArray45 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, T8 v8, - T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, T16 v16, - T17 v17, T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, T24 v24, - T25 v25, T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, T32 v32, - T33 v33, T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39, T40 v40, - T41 v41, T42 v42, T43 v43, T44 v44, T45 v45) { - return internal::ValueArray45(v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, - v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, - v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, - v39, v40, v41, v42, v43, v44, v45); -} - -template -internal::ValueArray46 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, - T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, - T16 v16, T17 v17, T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, - T24 v24, T25 v25, T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, - T32 v32, T33 v33, T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39, - T40 v40, T41 v41, T42 v42, T43 v43, T44 v44, T45 v45, T46 v46) { - return internal::ValueArray46(v1, v2, v3, v4, v5, v6, v7, v8, v9, - v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, - v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, - v38, v39, v40, v41, v42, v43, v44, v45, v46); -} - -template -internal::ValueArray47 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, T7 v7, - T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, - T16 v16, T17 v17, T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, - T24 v24, T25 v25, T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, - T32 v32, T33 v33, T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39, - T40 v40, T41 v41, T42 v42, T43 v43, T44 v44, T45 v45, T46 v46, T47 v47) { - return internal::ValueArray47(v1, v2, v3, v4, v5, v6, v7, v8, - v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, - v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, - v38, v39, v40, v41, v42, v43, v44, v45, v46, v47); -} - -template -internal::ValueArray48 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, T6 v6, - T7 v7, T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, T15 v15, - T16 v16, T17 v17, T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, T23 v23, - T24 v24, T25 v25, T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, T31 v31, - T32 v32, T33 v33, T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, T39 v39, - T40 v40, T41 v41, T42 v42, T43 v43, T44 v44, T45 v45, T46 v46, T47 v47, - T48 v48) { - return internal::ValueArray48(v1, v2, v3, v4, v5, v6, v7, - v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, - v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, - v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48); -} - -template -internal::ValueArray49 Values(T1 v1, T2 v2, T3 v3, T4 v4, T5 v5, - T6 v6, T7 v7, T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, T14 v14, - T15 v15, T16 v16, T17 v17, T18 v18, T19 v19, T20 v20, T21 v21, T22 v22, - T23 v23, T24 v24, T25 v25, T26 v26, T27 v27, T28 v28, T29 v29, T30 v30, - T31 v31, T32 v32, T33 v33, T34 v34, T35 v35, T36 v36, T37 v37, T38 v38, - T39 v39, T40 v40, T41 v41, T42 v42, T43 v43, T44 v44, T45 v45, T46 v46, - T47 v47, T48 v48, T49 v49) { - return internal::ValueArray49(v1, v2, v3, v4, v5, v6, - v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, - v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, - v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49); -} - -template -internal::ValueArray50 Values(T1 v1, T2 v2, T3 v3, T4 v4, - T5 v5, T6 v6, T7 v7, T8 v8, T9 v9, T10 v10, T11 v11, T12 v12, T13 v13, - T14 v14, T15 v15, T16 v16, T17 v17, T18 v18, T19 v19, T20 v20, T21 v21, - T22 v22, T23 v23, T24 v24, T25 v25, T26 v26, T27 v27, T28 v28, T29 v29, - T30 v30, T31 v31, T32 v32, T33 v33, T34 v34, T35 v35, T36 v36, T37 v37, - T38 v38, T39 v39, T40 v40, T41 v41, T42 v42, T43 v43, T44 v44, T45 v45, - T46 v46, T47 v47, T48 v48, T49 v49, T50 v50) { - return internal::ValueArray50(v1, v2, v3, v4, - v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, - v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, - v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, - v48, v49, v50); -} - -// Bool() allows generating tests with parameters in a set of (false, true). -// -// Synopsis: -// Bool() -// - returns a generator producing sequences with elements {false, true}. -// -// It is useful when testing code that depends on Boolean flags. Combinations -// of multiple flags can be tested when several Bool()'s are combined using -// Combine() function. -// -// In the following example all tests in the test case FlagDependentTest -// will be instantiated twice with parameters false and true. -// -// class FlagDependentTest : public testing::TestWithParam { -// virtual void SetUp() { -// external_flag = GetParam(); -// } -// } -// INSTANTIATE_TEST_CASE_P(BoolSequence, FlagDependentTest, Bool()); -// -inline internal::ParamGenerator Bool() { - return Values(false, true); -} - -# if GTEST_HAS_COMBINE -// Combine() allows the user to combine two or more sequences to produce -// values of a Cartesian product of those sequences' elements. -// -// Synopsis: -// Combine(gen1, gen2, ..., genN) -// - returns a generator producing sequences with elements coming from -// the Cartesian product of elements from the sequences generated by -// gen1, gen2, ..., genN. The sequence elements will have a type of -// tuple where T1, T2, ..., TN are the types -// of elements from sequences produces by gen1, gen2, ..., genN. -// -// Combine can have up to 10 arguments. This number is currently limited -// by the maximum number of elements in the tuple implementation used by Google -// Test. -// -// Example: -// -// This will instantiate tests in test case AnimalTest each one with -// the parameter values tuple("cat", BLACK), tuple("cat", WHITE), -// tuple("dog", BLACK), and tuple("dog", WHITE): -// -// enum Color { BLACK, GRAY, WHITE }; -// class AnimalTest -// : public testing::TestWithParam > {...}; -// -// TEST_P(AnimalTest, AnimalLooksNice) {...} -// -// INSTANTIATE_TEST_CASE_P(AnimalVariations, AnimalTest, -// Combine(Values("cat", "dog"), -// Values(BLACK, WHITE))); -// -// This will instantiate tests in FlagDependentTest with all variations of two -// Boolean flags: -// -// class FlagDependentTest -// : public testing::TestWithParam > { -// virtual void SetUp() { -// // Assigns external_flag_1 and external_flag_2 values from the tuple. -// tie(external_flag_1, external_flag_2) = GetParam(); -// } -// }; -// -// TEST_P(FlagDependentTest, TestFeature1) { -// // Test your code using external_flag_1 and external_flag_2 here. -// } -// INSTANTIATE_TEST_CASE_P(TwoBoolSequence, FlagDependentTest, -// Combine(Bool(), Bool())); -// -template -internal::CartesianProductHolder2 Combine( - const Generator1& g1, const Generator2& g2) { - return internal::CartesianProductHolder2( - g1, g2); -} - -template -internal::CartesianProductHolder3 Combine( - const Generator1& g1, const Generator2& g2, const Generator3& g3) { - return internal::CartesianProductHolder3( - g1, g2, g3); -} - -template -internal::CartesianProductHolder4 Combine( - const Generator1& g1, const Generator2& g2, const Generator3& g3, - const Generator4& g4) { - return internal::CartesianProductHolder4( - g1, g2, g3, g4); -} - -template -internal::CartesianProductHolder5 Combine( - const Generator1& g1, const Generator2& g2, const Generator3& g3, - const Generator4& g4, const Generator5& g5) { - return internal::CartesianProductHolder5( - g1, g2, g3, g4, g5); -} - -template -internal::CartesianProductHolder6 Combine( - const Generator1& g1, const Generator2& g2, const Generator3& g3, - const Generator4& g4, const Generator5& g5, const Generator6& g6) { - return internal::CartesianProductHolder6( - g1, g2, g3, g4, g5, g6); -} - -template -internal::CartesianProductHolder7 Combine( - const Generator1& g1, const Generator2& g2, const Generator3& g3, - const Generator4& g4, const Generator5& g5, const Generator6& g6, - const Generator7& g7) { - return internal::CartesianProductHolder7( - g1, g2, g3, g4, g5, g6, g7); -} - -template -internal::CartesianProductHolder8 Combine( - const Generator1& g1, const Generator2& g2, const Generator3& g3, - const Generator4& g4, const Generator5& g5, const Generator6& g6, - const Generator7& g7, const Generator8& g8) { - return internal::CartesianProductHolder8( - g1, g2, g3, g4, g5, g6, g7, g8); -} - -template -internal::CartesianProductHolder9 Combine( - const Generator1& g1, const Generator2& g2, const Generator3& g3, - const Generator4& g4, const Generator5& g5, const Generator6& g6, - const Generator7& g7, const Generator8& g8, const Generator9& g9) { - return internal::CartesianProductHolder9( - g1, g2, g3, g4, g5, g6, g7, g8, g9); -} - -template -internal::CartesianProductHolder10 Combine( - const Generator1& g1, const Generator2& g2, const Generator3& g3, - const Generator4& g4, const Generator5& g5, const Generator6& g6, - const Generator7& g7, const Generator8& g8, const Generator9& g9, - const Generator10& g10) { - return internal::CartesianProductHolder10( - g1, g2, g3, g4, g5, g6, g7, g8, g9, g10); -} -# endif // GTEST_HAS_COMBINE - - - -# define TEST_P(test_case_name, test_name) \ - class GTEST_TEST_CLASS_NAME_(test_case_name, test_name) \ - : public test_case_name { \ - public: \ - GTEST_TEST_CLASS_NAME_(test_case_name, test_name)() {} \ - virtual void TestBody(); \ - private: \ - static int AddToRegistry() { \ - ::testing::UnitTest::GetInstance()->parameterized_test_registry(). \ - GetTestCasePatternHolder(\ - #test_case_name, __FILE__, __LINE__)->AddTestPattern(\ - #test_case_name, \ - #test_name, \ - new ::testing::internal::TestMetaFactory< \ - GTEST_TEST_CLASS_NAME_(test_case_name, test_name)>()); \ - return 0; \ - } \ - static int gtest_registering_dummy_; \ - GTEST_DISALLOW_COPY_AND_ASSIGN_(\ - GTEST_TEST_CLASS_NAME_(test_case_name, test_name)); \ - }; \ - int GTEST_TEST_CLASS_NAME_(test_case_name, \ - test_name)::gtest_registering_dummy_ = \ - GTEST_TEST_CLASS_NAME_(test_case_name, test_name)::AddToRegistry(); \ - void GTEST_TEST_CLASS_NAME_(test_case_name, test_name)::TestBody() - -# define INSTANTIATE_TEST_CASE_P(prefix, test_case_name, generator) \ - ::testing::internal::ParamGenerator \ - gtest_##prefix##test_case_name##_EvalGenerator_() { return generator; } \ - int gtest_##prefix##test_case_name##_dummy_ = \ - ::testing::UnitTest::GetInstance()->parameterized_test_registry(). \ - GetTestCasePatternHolder(\ - #test_case_name, __FILE__, __LINE__)->AddTestCaseInstantiation(\ - #prefix, \ - >est_##prefix##test_case_name##_EvalGenerator_, \ - __FILE__, __LINE__) - -} // namespace testing - -#endif // GTEST_HAS_PARAM_TEST - -#endif // GTEST_INCLUDE_GTEST_GTEST_PARAM_TEST_H_ -// Copyright 2006, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: wan@google.com (Zhanyong Wan) -// -// Google C++ Testing Framework definitions useful in production code. - -#ifndef GTEST_INCLUDE_GTEST_GTEST_PROD_H_ -#define GTEST_INCLUDE_GTEST_GTEST_PROD_H_ - -// When you need to test the private or protected members of a class, -// use the FRIEND_TEST macro to declare your tests as friends of the -// class. For example: -// -// class MyClass { -// private: -// void MyMethod(); -// FRIEND_TEST(MyClassTest, MyMethod); -// }; -// -// class MyClassTest : public testing::Test { -// // ... -// }; -// -// TEST_F(MyClassTest, MyMethod) { -// // Can call MyClass::MyMethod() here. -// } - -#define FRIEND_TEST(test_case_name, test_name)\ -friend class test_case_name##_##test_name##_Test - -#endif // GTEST_INCLUDE_GTEST_GTEST_PROD_H_ -// Copyright 2008, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: mheule@google.com (Markus Heule) -// - -#ifndef GTEST_INCLUDE_GTEST_GTEST_TEST_PART_H_ -#define GTEST_INCLUDE_GTEST_GTEST_TEST_PART_H_ - -#include -#include - -namespace testing { - -// A copyable object representing the result of a test part (i.e. an -// assertion or an explicit FAIL(), ADD_FAILURE(), or SUCCESS()). -// -// Don't inherit from TestPartResult as its destructor is not virtual. -class GTEST_API_ TestPartResult { - public: - // The possible outcomes of a test part (i.e. an assertion or an - // explicit SUCCEED(), FAIL(), or ADD_FAILURE()). - enum Type { - kSuccess, // Succeeded. - kNonFatalFailure, // Failed but the test can continue. - kFatalFailure // Failed and the test should be terminated. - }; - - // C'tor. TestPartResult does NOT have a default constructor. - // Always use this constructor (with parameters) to create a - // TestPartResult object. - TestPartResult(Type a_type, - const char* a_file_name, - int a_line_number, - const char* a_message) - : type_(a_type), - file_name_(a_file_name == NULL ? "" : a_file_name), - line_number_(a_line_number), - summary_(ExtractSummary(a_message)), - message_(a_message) { - } - - // Gets the outcome of the test part. - Type type() const { return type_; } - - // Gets the name of the source file where the test part took place, or - // NULL if it's unknown. - const char* file_name() const { - return file_name_.empty() ? NULL : file_name_.c_str(); - } - - // Gets the line in the source file where the test part took place, - // or -1 if it's unknown. - int line_number() const { return line_number_; } - - // Gets the summary of the failure message. - const char* summary() const { return summary_.c_str(); } - - // Gets the message associated with the test part. - const char* message() const { return message_.c_str(); } - - // Returns true iff the test part passed. - bool passed() const { return type_ == kSuccess; } - - // Returns true iff the test part failed. - bool failed() const { return type_ != kSuccess; } - - // Returns true iff the test part non-fatally failed. - bool nonfatally_failed() const { return type_ == kNonFatalFailure; } - - // Returns true iff the test part fatally failed. - bool fatally_failed() const { return type_ == kFatalFailure; } - - private: - Type type_; - - // Gets the summary of the failure message by omitting the stack - // trace in it. - static std::string ExtractSummary(const char* message); - - // The name of the source file where the test part took place, or - // "" if the source file is unknown. - std::string file_name_; - // The line in the source file where the test part took place, or -1 - // if the line number is unknown. - int line_number_; - std::string summary_; // The test failure summary. - std::string message_; // The test failure message. -}; - -// Prints a TestPartResult object. -std::ostream& operator<<(std::ostream& os, const TestPartResult& result); - -// An array of TestPartResult objects. -// -// Don't inherit from TestPartResultArray as its destructor is not -// virtual. -class GTEST_API_ TestPartResultArray { - public: - TestPartResultArray() {} - - // Appends the given TestPartResult to the array. - void Append(const TestPartResult& result); - - // Returns the TestPartResult at the given index (0-based). - const TestPartResult& GetTestPartResult(int index) const; - - // Returns the number of TestPartResult objects in the array. - int size() const; - - private: - std::vector array_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(TestPartResultArray); -}; - -// This interface knows how to report a test part result. -class TestPartResultReporterInterface { - public: - virtual ~TestPartResultReporterInterface() {} - - virtual void ReportTestPartResult(const TestPartResult& result) = 0; -}; - -namespace internal { - -// This helper class is used by {ASSERT|EXPECT}_NO_FATAL_FAILURE to check if a -// statement generates new fatal failures. To do so it registers itself as the -// current test part result reporter. Besides checking if fatal failures were -// reported, it only delegates the reporting to the former result reporter. -// The original result reporter is restored in the destructor. -// INTERNAL IMPLEMENTATION - DO NOT USE IN A USER PROGRAM. -class GTEST_API_ HasNewFatalFailureHelper - : public TestPartResultReporterInterface { - public: - HasNewFatalFailureHelper(); - virtual ~HasNewFatalFailureHelper(); - virtual void ReportTestPartResult(const TestPartResult& result); - bool has_new_fatal_failure() const { return has_new_fatal_failure_; } - private: - bool has_new_fatal_failure_; - TestPartResultReporterInterface* original_reporter_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(HasNewFatalFailureHelper); -}; - -} // namespace internal - -} // namespace testing - -#endif // GTEST_INCLUDE_GTEST_GTEST_TEST_PART_H_ -// Copyright 2008 Google Inc. -// All Rights Reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: wan@google.com (Zhanyong Wan) - -#ifndef GTEST_INCLUDE_GTEST_GTEST_TYPED_TEST_H_ -#define GTEST_INCLUDE_GTEST_GTEST_TYPED_TEST_H_ - -// This header implements typed tests and type-parameterized tests. - -// Typed (aka type-driven) tests repeat the same test for types in a -// list. You must know which types you want to test with when writing -// typed tests. Here's how you do it: - -#if 0 - -// First, define a fixture class template. It should be parameterized -// by a type. Remember to derive it from testing::Test. -template -class FooTest : public testing::Test { - public: - ... - typedef std::list List; - static T shared_; - T value_; -}; - -// Next, associate a list of types with the test case, which will be -// repeated for each type in the list. The typedef is necessary for -// the macro to parse correctly. -typedef testing::Types MyTypes; -TYPED_TEST_CASE(FooTest, MyTypes); - -// If the type list contains only one type, you can write that type -// directly without Types<...>: -// TYPED_TEST_CASE(FooTest, int); - -// Then, use TYPED_TEST() instead of TEST_F() to define as many typed -// tests for this test case as you want. -TYPED_TEST(FooTest, DoesBlah) { - // Inside a test, refer to TypeParam to get the type parameter. - // Since we are inside a derived class template, C++ requires use to - // visit the members of FooTest via 'this'. - TypeParam n = this->value_; - - // To visit static members of the fixture, add the TestFixture:: - // prefix. - n += TestFixture::shared_; - - // To refer to typedefs in the fixture, add the "typename - // TestFixture::" prefix. - typename TestFixture::List values; - values.push_back(n); - ... -} - -TYPED_TEST(FooTest, HasPropertyA) { ... } - -#endif // 0 - -// Type-parameterized tests are abstract test patterns parameterized -// by a type. Compared with typed tests, type-parameterized tests -// allow you to define the test pattern without knowing what the type -// parameters are. The defined pattern can be instantiated with -// different types any number of times, in any number of translation -// units. -// -// If you are designing an interface or concept, you can define a -// suite of type-parameterized tests to verify properties that any -// valid implementation of the interface/concept should have. Then, -// each implementation can easily instantiate the test suite to verify -// that it conforms to the requirements, without having to write -// similar tests repeatedly. Here's an example: - -#if 0 - -// First, define a fixture class template. It should be parameterized -// by a type. Remember to derive it from testing::Test. -template -class FooTest : public testing::Test { - ... -}; - -// Next, declare that you will define a type-parameterized test case -// (the _P suffix is for "parameterized" or "pattern", whichever you -// prefer): -TYPED_TEST_CASE_P(FooTest); - -// Then, use TYPED_TEST_P() to define as many type-parameterized tests -// for this type-parameterized test case as you want. -TYPED_TEST_P(FooTest, DoesBlah) { - // Inside a test, refer to TypeParam to get the type parameter. - TypeParam n = 0; - ... -} - -TYPED_TEST_P(FooTest, HasPropertyA) { ... } - -// Now the tricky part: you need to register all test patterns before -// you can instantiate them. The first argument of the macro is the -// test case name; the rest are the names of the tests in this test -// case. -REGISTER_TYPED_TEST_CASE_P(FooTest, - DoesBlah, HasPropertyA); - -// Finally, you are free to instantiate the pattern with the types you -// want. If you put the above code in a header file, you can #include -// it in multiple C++ source files and instantiate it multiple times. -// -// To distinguish different instances of the pattern, the first -// argument to the INSTANTIATE_* macro is a prefix that will be added -// to the actual test case name. Remember to pick unique prefixes for -// different instances. -typedef testing::Types MyTypes; -INSTANTIATE_TYPED_TEST_CASE_P(My, FooTest, MyTypes); - -// If the type list contains only one type, you can write that type -// directly without Types<...>: -// INSTANTIATE_TYPED_TEST_CASE_P(My, FooTest, int); - -#endif // 0 - - -// Implements typed tests. - -#if GTEST_HAS_TYPED_TEST - -// INTERNAL IMPLEMENTATION - DO NOT USE IN USER CODE. -// -// Expands to the name of the typedef for the type parameters of the -// given test case. -# define GTEST_TYPE_PARAMS_(TestCaseName) gtest_type_params_##TestCaseName##_ - -// The 'Types' template argument below must have spaces around it -// since some compilers may choke on '>>' when passing a template -// instance (e.g. Types) -# define TYPED_TEST_CASE(CaseName, Types) \ - typedef ::testing::internal::TypeList< Types >::type \ - GTEST_TYPE_PARAMS_(CaseName) - -# define TYPED_TEST(CaseName, TestName) \ - template \ - class GTEST_TEST_CLASS_NAME_(CaseName, TestName) \ - : public CaseName { \ - private: \ - typedef CaseName TestFixture; \ - typedef gtest_TypeParam_ TypeParam; \ - virtual void TestBody(); \ - }; \ - bool gtest_##CaseName##_##TestName##_registered_ GTEST_ATTRIBUTE_UNUSED_ = \ - ::testing::internal::TypeParameterizedTest< \ - CaseName, \ - ::testing::internal::TemplateSel< \ - GTEST_TEST_CLASS_NAME_(CaseName, TestName)>, \ - GTEST_TYPE_PARAMS_(CaseName)>::Register(\ - "", #CaseName, #TestName, 0); \ - template \ - void GTEST_TEST_CLASS_NAME_(CaseName, TestName)::TestBody() - -#endif // GTEST_HAS_TYPED_TEST - -// Implements type-parameterized tests. - -#if GTEST_HAS_TYPED_TEST_P - -// INTERNAL IMPLEMENTATION - DO NOT USE IN USER CODE. -// -// Expands to the namespace name that the type-parameterized tests for -// the given type-parameterized test case are defined in. The exact -// name of the namespace is subject to change without notice. -# define GTEST_CASE_NAMESPACE_(TestCaseName) \ - gtest_case_##TestCaseName##_ - -// INTERNAL IMPLEMENTATION - DO NOT USE IN USER CODE. -// -// Expands to the name of the variable used to remember the names of -// the defined tests in the given test case. -# define GTEST_TYPED_TEST_CASE_P_STATE_(TestCaseName) \ - gtest_typed_test_case_p_state_##TestCaseName##_ - -// INTERNAL IMPLEMENTATION - DO NOT USE IN USER CODE DIRECTLY. -// -// Expands to the name of the variable used to remember the names of -// the registered tests in the given test case. -# define GTEST_REGISTERED_TEST_NAMES_(TestCaseName) \ - gtest_registered_test_names_##TestCaseName##_ - -// The variables defined in the type-parameterized test macros are -// static as typically these macros are used in a .h file that can be -// #included in multiple translation units linked together. -# define TYPED_TEST_CASE_P(CaseName) \ - static ::testing::internal::TypedTestCasePState \ - GTEST_TYPED_TEST_CASE_P_STATE_(CaseName) - -# define TYPED_TEST_P(CaseName, TestName) \ - namespace GTEST_CASE_NAMESPACE_(CaseName) { \ - template \ - class TestName : public CaseName { \ - private: \ - typedef CaseName TestFixture; \ - typedef gtest_TypeParam_ TypeParam; \ - virtual void TestBody(); \ - }; \ - static bool gtest_##TestName##_defined_ GTEST_ATTRIBUTE_UNUSED_ = \ - GTEST_TYPED_TEST_CASE_P_STATE_(CaseName).AddTestName(\ - __FILE__, __LINE__, #CaseName, #TestName); \ - } \ - template \ - void GTEST_CASE_NAMESPACE_(CaseName)::TestName::TestBody() - -# define REGISTER_TYPED_TEST_CASE_P(CaseName, ...) \ - namespace GTEST_CASE_NAMESPACE_(CaseName) { \ - typedef ::testing::internal::Templates<__VA_ARGS__>::type gtest_AllTests_; \ - } \ - static const char* const GTEST_REGISTERED_TEST_NAMES_(CaseName) = \ - GTEST_TYPED_TEST_CASE_P_STATE_(CaseName).VerifyRegisteredTestNames(\ - __FILE__, __LINE__, #__VA_ARGS__) - -// The 'Types' template argument below must have spaces around it -// since some compilers may choke on '>>' when passing a template -// instance (e.g. Types) -# define INSTANTIATE_TYPED_TEST_CASE_P(Prefix, CaseName, Types) \ - bool gtest_##Prefix##_##CaseName GTEST_ATTRIBUTE_UNUSED_ = \ - ::testing::internal::TypeParameterizedTestCase::type>::Register(\ - #Prefix, #CaseName, GTEST_REGISTERED_TEST_NAMES_(CaseName)) - -#endif // GTEST_HAS_TYPED_TEST_P - -#endif // GTEST_INCLUDE_GTEST_GTEST_TYPED_TEST_H_ - -// Depending on the platform, different string classes are available. -// On Linux, in addition to ::std::string, Google also makes use of -// class ::string, which has the same interface as ::std::string, but -// has a different implementation. -// -// The user can define GTEST_HAS_GLOBAL_STRING to 1 to indicate that -// ::string is available AND is a distinct type to ::std::string, or -// define it to 0 to indicate otherwise. -// -// If the user's ::std::string and ::string are the same class due to -// aliasing, he should define GTEST_HAS_GLOBAL_STRING to 0. -// -// If the user doesn't define GTEST_HAS_GLOBAL_STRING, it is defined -// heuristically. - -namespace testing { - -// Declares the flags. - -// This flag temporary enables the disabled tests. -GTEST_DECLARE_bool_(also_run_disabled_tests); - -// This flag brings the debugger on an assertion failure. -GTEST_DECLARE_bool_(break_on_failure); - -// This flag controls whether Google Test catches all test-thrown exceptions -// and logs them as failures. -GTEST_DECLARE_bool_(catch_exceptions); - -// This flag enables using colors in terminal output. Available values are -// "yes" to enable colors, "no" (disable colors), or "auto" (the default) -// to let Google Test decide. -GTEST_DECLARE_string_(color); - -// This flag sets up the filter to select by name using a glob pattern -// the tests to run. If the filter is not given all tests are executed. -GTEST_DECLARE_string_(filter); - -// This flag causes the Google Test to list tests. None of the tests listed -// are actually run if the flag is provided. -GTEST_DECLARE_bool_(list_tests); - -// This flag controls whether Google Test emits a detailed XML report to a file -// in addition to its normal textual output. -GTEST_DECLARE_string_(output); - -// This flags control whether Google Test prints the elapsed time for each -// test. -GTEST_DECLARE_bool_(print_time); - -// This flag specifies the random number seed. -GTEST_DECLARE_int32_(random_seed); - -// This flag sets how many times the tests are repeated. The default value -// is 1. If the value is -1 the tests are repeating forever. -GTEST_DECLARE_int32_(repeat); - -// This flag controls whether Google Test includes Google Test internal -// stack frames in failure stack traces. -GTEST_DECLARE_bool_(show_internal_stack_frames); - -// When this flag is specified, tests' order is randomized on every iteration. -GTEST_DECLARE_bool_(shuffle); - -// This flag specifies the maximum number of stack frames to be -// printed in a failure message. -GTEST_DECLARE_int32_(stack_trace_depth); - -// When this flag is specified, a failed assertion will throw an -// exception if exceptions are enabled, or exit the program with a -// non-zero code otherwise. -GTEST_DECLARE_bool_(throw_on_failure); - -// When this flag is set with a "host:port" string, on supported -// platforms test results are streamed to the specified port on -// the specified host machine. -GTEST_DECLARE_string_(stream_result_to); - -// The upper limit for valid stack trace depths. -const int kMaxStackTraceDepth = 100; - -namespace internal { - -class AssertHelper; -class DefaultGlobalTestPartResultReporter; -class ExecDeathTest; -class NoExecDeathTest; -class FinalSuccessChecker; -class GTestFlagSaver; -class StreamingListenerTest; -class TestResultAccessor; -class TestEventListenersAccessor; -class TestEventRepeater; -class UnitTestRecordPropertyTestHelper; -class WindowsDeathTest; -class UnitTestImpl* GetUnitTestImpl(); -void ReportFailureInUnknownLocation(TestPartResult::Type result_type, - const std::string& message); - -} // namespace internal - -// The friend relationship of some of these classes is cyclic. -// If we don't forward declare them the compiler might confuse the classes -// in friendship clauses with same named classes on the scope. -class Test; -class TestCase; -class TestInfo; -class UnitTest; - -// A class for indicating whether an assertion was successful. When -// the assertion wasn't successful, the AssertionResult object -// remembers a non-empty message that describes how it failed. -// -// To create an instance of this class, use one of the factory functions -// (AssertionSuccess() and AssertionFailure()). -// -// This class is useful for two purposes: -// 1. Defining predicate functions to be used with Boolean test assertions -// EXPECT_TRUE/EXPECT_FALSE and their ASSERT_ counterparts -// 2. Defining predicate-format functions to be -// used with predicate assertions (ASSERT_PRED_FORMAT*, etc). -// -// For example, if you define IsEven predicate: -// -// testing::AssertionResult IsEven(int n) { -// if ((n % 2) == 0) -// return testing::AssertionSuccess(); -// else -// return testing::AssertionFailure() << n << " is odd"; -// } -// -// Then the failed expectation EXPECT_TRUE(IsEven(Fib(5))) -// will print the message -// -// Value of: IsEven(Fib(5)) -// Actual: false (5 is odd) -// Expected: true -// -// instead of a more opaque -// -// Value of: IsEven(Fib(5)) -// Actual: false -// Expected: true -// -// in case IsEven is a simple Boolean predicate. -// -// If you expect your predicate to be reused and want to support informative -// messages in EXPECT_FALSE and ASSERT_FALSE (negative assertions show up -// about half as often as positive ones in our tests), supply messages for -// both success and failure cases: -// -// testing::AssertionResult IsEven(int n) { -// if ((n % 2) == 0) -// return testing::AssertionSuccess() << n << " is even"; -// else -// return testing::AssertionFailure() << n << " is odd"; -// } -// -// Then a statement EXPECT_FALSE(IsEven(Fib(6))) will print -// -// Value of: IsEven(Fib(6)) -// Actual: true (8 is even) -// Expected: false -// -// NB: Predicates that support negative Boolean assertions have reduced -// performance in positive ones so be careful not to use them in tests -// that have lots (tens of thousands) of positive Boolean assertions. -// -// To use this class with EXPECT_PRED_FORMAT assertions such as: -// -// // Verifies that Foo() returns an even number. -// EXPECT_PRED_FORMAT1(IsEven, Foo()); -// -// you need to define: -// -// testing::AssertionResult IsEven(const char* expr, int n) { -// if ((n % 2) == 0) -// return testing::AssertionSuccess(); -// else -// return testing::AssertionFailure() -// << "Expected: " << expr << " is even\n Actual: it's " << n; -// } -// -// If Foo() returns 5, you will see the following message: -// -// Expected: Foo() is even -// Actual: it's 5 -// -class GTEST_API_ AssertionResult { - public: - // Copy constructor. - // Used in EXPECT_TRUE/FALSE(assertion_result). - AssertionResult(const AssertionResult& other); - // Used in the EXPECT_TRUE/FALSE(bool_expression). - explicit AssertionResult(bool success) : success_(success) {} - - // Returns true iff the assertion succeeded. - operator bool() const { return success_; } // NOLINT - - // Returns the assertion's negation. Used with EXPECT/ASSERT_FALSE. - AssertionResult operator!() const; - - // Returns the text streamed into this AssertionResult. Test assertions - // use it when they fail (i.e., the predicate's outcome doesn't match the - // assertion's expectation). When nothing has been streamed into the - // object, returns an empty string. - const char* message() const { - return message_.get() != NULL ? message_->c_str() : ""; - } - // TODO(vladl@google.com): Remove this after making sure no clients use it. - // Deprecated; please use message() instead. - const char* failure_message() const { return message(); } - - // Streams a custom failure message into this object. - template AssertionResult& operator<<(const T& value) { - AppendMessage(Message() << value); - return *this; - } - - // Allows streaming basic output manipulators such as endl or flush into - // this object. - AssertionResult& operator<<( - ::std::ostream& (*basic_manipulator)(::std::ostream& stream)) { - AppendMessage(Message() << basic_manipulator); - return *this; - } - - private: - // Appends the contents of message to message_. - void AppendMessage(const Message& a_message) { - if (message_.get() == NULL) - message_.reset(new ::std::string); - message_->append(a_message.GetString().c_str()); - } - - // Stores result of the assertion predicate. - bool success_; - // Stores the message describing the condition in case the expectation - // construct is not satisfied with the predicate's outcome. - // Referenced via a pointer to avoid taking too much stack frame space - // with test assertions. - internal::scoped_ptr< ::std::string> message_; - - GTEST_DISALLOW_ASSIGN_(AssertionResult); -}; - -// Makes a successful assertion result. -GTEST_API_ AssertionResult AssertionSuccess(); - -// Makes a failed assertion result. -GTEST_API_ AssertionResult AssertionFailure(); - -// Makes a failed assertion result with the given failure message. -// Deprecated; use AssertionFailure() << msg. -GTEST_API_ AssertionResult AssertionFailure(const Message& msg); - -// The abstract class that all tests inherit from. -// -// In Google Test, a unit test program contains one or many TestCases, and -// each TestCase contains one or many Tests. -// -// When you define a test using the TEST macro, you don't need to -// explicitly derive from Test - the TEST macro automatically does -// this for you. -// -// The only time you derive from Test is when defining a test fixture -// to be used a TEST_F. For example: -// -// class FooTest : public testing::Test { -// protected: -// virtual void SetUp() { ... } -// virtual void TearDown() { ... } -// ... -// }; -// -// TEST_F(FooTest, Bar) { ... } -// TEST_F(FooTest, Baz) { ... } -// -// Test is not copyable. -class GTEST_API_ Test { - public: - friend class TestInfo; - - // Defines types for pointers to functions that set up and tear down - // a test case. - typedef internal::SetUpTestCaseFunc SetUpTestCaseFunc; - typedef internal::TearDownTestCaseFunc TearDownTestCaseFunc; - - // The d'tor is virtual as we intend to inherit from Test. - virtual ~Test(); - - // Sets up the stuff shared by all tests in this test case. - // - // Google Test will call Foo::SetUpTestCase() before running the first - // test in test case Foo. Hence a sub-class can define its own - // SetUpTestCase() method to shadow the one defined in the super - // class. - static void SetUpTestCase() {} - - // Tears down the stuff shared by all tests in this test case. - // - // Google Test will call Foo::TearDownTestCase() after running the last - // test in test case Foo. Hence a sub-class can define its own - // TearDownTestCase() method to shadow the one defined in the super - // class. - static void TearDownTestCase() {} - - // Returns true iff the current test has a fatal failure. - static bool HasFatalFailure(); - - // Returns true iff the current test has a non-fatal failure. - static bool HasNonfatalFailure(); - - // Returns true iff the current test has a (either fatal or - // non-fatal) failure. - static bool HasFailure() { return HasFatalFailure() || HasNonfatalFailure(); } - - // Logs a property for the current test, test case, or for the entire - // invocation of the test program when used outside of the context of a - // test case. Only the last value for a given key is remembered. These - // are public static so they can be called from utility functions that are - // not members of the test fixture. Calls to RecordProperty made during - // lifespan of the test (from the moment its constructor starts to the - // moment its destructor finishes) will be output in XML as attributes of - // the element. Properties recorded from fixture's - // SetUpTestCase or TearDownTestCase are logged as attributes of the - // corresponding element. Calls to RecordProperty made in the - // global context (before or after invocation of RUN_ALL_TESTS and from - // SetUp/TearDown method of Environment objects registered with Google - // Test) will be output as attributes of the element. - static void RecordProperty(const std::string& key, const std::string& value); - static void RecordProperty(const std::string& key, int value); - - protected: - // Creates a Test object. - Test(); - - // Sets up the test fixture. - virtual void SetUp(); - - // Tears down the test fixture. - virtual void TearDown(); - - private: - // Returns true iff the current test has the same fixture class as - // the first test in the current test case. - static bool HasSameFixtureClass(); - - // Runs the test after the test fixture has been set up. - // - // A sub-class must implement this to define the test logic. - // - // DO NOT OVERRIDE THIS FUNCTION DIRECTLY IN A USER PROGRAM. - // Instead, use the TEST or TEST_F macro. - virtual void TestBody() = 0; - - // Sets up, executes, and tears down the test. - void Run(); - - // Deletes self. We deliberately pick an unusual name for this - // internal method to avoid clashing with names used in user TESTs. - void DeleteSelf_() { delete this; } - - // Uses a GTestFlagSaver to save and restore all Google Test flags. - const internal::GTestFlagSaver* const gtest_flag_saver_; - - // Often a user mis-spells SetUp() as Setup() and spends a long time - // wondering why it is never called by Google Test. The declaration of - // the following method is solely for catching such an error at - // compile time: - // - // - The return type is deliberately chosen to be not void, so it - // will be a conflict if a user declares void Setup() in his test - // fixture. - // - // - This method is private, so it will be another compiler error - // if a user calls it from his test fixture. - // - // DO NOT OVERRIDE THIS FUNCTION. - // - // If you see an error about overriding the following function or - // about it being private, you have mis-spelled SetUp() as Setup(). - struct Setup_should_be_spelled_SetUp {}; - virtual Setup_should_be_spelled_SetUp* Setup() { return NULL; } - - // We disallow copying Tests. - GTEST_DISALLOW_COPY_AND_ASSIGN_(Test); -}; - -typedef internal::TimeInMillis TimeInMillis; - -// A copyable object representing a user specified test property which can be -// output as a key/value string pair. -// -// Don't inherit from TestProperty as its destructor is not virtual. -class TestProperty { - public: - // C'tor. TestProperty does NOT have a default constructor. - // Always use this constructor (with parameters) to create a - // TestProperty object. - TestProperty(const std::string& a_key, const std::string& a_value) : - key_(a_key), value_(a_value) { - } - - // Gets the user supplied key. - const char* key() const { - return key_.c_str(); - } - - // Gets the user supplied value. - const char* value() const { - return value_.c_str(); - } - - // Sets a new value, overriding the one supplied in the constructor. - void SetValue(const std::string& new_value) { - value_ = new_value; - } - - private: - // The key supplied by the user. - std::string key_; - // The value supplied by the user. - std::string value_; -}; - -// The result of a single Test. This includes a list of -// TestPartResults, a list of TestProperties, a count of how many -// death tests there are in the Test, and how much time it took to run -// the Test. -// -// TestResult is not copyable. -class GTEST_API_ TestResult { - public: - // Creates an empty TestResult. - TestResult(); - - // D'tor. Do not inherit from TestResult. - ~TestResult(); - - // Gets the number of all test parts. This is the sum of the number - // of successful test parts and the number of failed test parts. - int total_part_count() const; - - // Returns the number of the test properties. - int test_property_count() const; - - // Returns true iff the test passed (i.e. no test part failed). - bool Passed() const { return !Failed(); } - - // Returns true iff the test failed. - bool Failed() const; - - // Returns true iff the test fatally failed. - bool HasFatalFailure() const; - - // Returns true iff the test has a non-fatal failure. - bool HasNonfatalFailure() const; - - // Returns the elapsed time, in milliseconds. - TimeInMillis elapsed_time() const { return elapsed_time_; } - - // Returns the i-th test part result among all the results. i can range - // from 0 to test_property_count() - 1. If i is not in that range, aborts - // the program. - const TestPartResult& GetTestPartResult(int i) const; - - // Returns the i-th test property. i can range from 0 to - // test_property_count() - 1. If i is not in that range, aborts the - // program. - const TestProperty& GetTestProperty(int i) const; - - private: - friend class TestInfo; - friend class TestCase; - friend class UnitTest; - friend class internal::DefaultGlobalTestPartResultReporter; - friend class internal::ExecDeathTest; - friend class internal::TestResultAccessor; - friend class internal::UnitTestImpl; - friend class internal::WindowsDeathTest; - - // Gets the vector of TestPartResults. - const std::vector& test_part_results() const { - return test_part_results_; - } - - // Gets the vector of TestProperties. - const std::vector& test_properties() const { - return test_properties_; - } - - // Sets the elapsed time. - void set_elapsed_time(TimeInMillis elapsed) { elapsed_time_ = elapsed; } - - // Adds a test property to the list. The property is validated and may add - // a non-fatal failure if invalid (e.g., if it conflicts with reserved - // key names). If a property is already recorded for the same key, the - // value will be updated, rather than storing multiple values for the same - // key. xml_element specifies the element for which the property is being - // recorded and is used for validation. - void RecordProperty(const std::string& xml_element, - const TestProperty& test_property); - - // Adds a failure if the key is a reserved attribute of Google Test - // testcase tags. Returns true if the property is valid. - // TODO(russr): Validate attribute names are legal and human readable. - static bool ValidateTestProperty(const std::string& xml_element, - const TestProperty& test_property); - - // Adds a test part result to the list. - void AddTestPartResult(const TestPartResult& test_part_result); - - // Returns the death test count. - int death_test_count() const { return death_test_count_; } - - // Increments the death test count, returning the new count. - int increment_death_test_count() { return ++death_test_count_; } - - // Clears the test part results. - void ClearTestPartResults(); - - // Clears the object. - void Clear(); - - // Protects mutable state of the property vector and of owned - // properties, whose values may be updated. - internal::Mutex test_properites_mutex_; - - // The vector of TestPartResults - std::vector test_part_results_; - // The vector of TestProperties - std::vector test_properties_; - // Running count of death tests. - int death_test_count_; - // The elapsed time, in milliseconds. - TimeInMillis elapsed_time_; - - // We disallow copying TestResult. - GTEST_DISALLOW_COPY_AND_ASSIGN_(TestResult); -}; // class TestResult - -// A TestInfo object stores the following information about a test: -// -// Test case name -// Test name -// Whether the test should be run -// A function pointer that creates the test object when invoked -// Test result -// -// The constructor of TestInfo registers itself with the UnitTest -// singleton such that the RUN_ALL_TESTS() macro knows which tests to -// run. -class GTEST_API_ TestInfo { - public: - // Destructs a TestInfo object. This function is not virtual, so - // don't inherit from TestInfo. - ~TestInfo(); - - // Returns the test case name. - const char* test_case_name() const { return test_case_name_.c_str(); } - - // Returns the test name. - const char* name() const { return name_.c_str(); } - - // Returns the name of the parameter type, or NULL if this is not a typed - // or a type-parameterized test. - const char* type_param() const { - if (type_param_.get() != NULL) - return type_param_->c_str(); - return NULL; - } - - // Returns the text representation of the value parameter, or NULL if this - // is not a value-parameterized test. - const char* value_param() const { - if (value_param_.get() != NULL) - return value_param_->c_str(); - return NULL; - } - - // Returns true if this test should run, that is if the test is not - // disabled (or it is disabled but the also_run_disabled_tests flag has - // been specified) and its full name matches the user-specified filter. - // - // Google Test allows the user to filter the tests by their full names. - // The full name of a test Bar in test case Foo is defined as - // "Foo.Bar". Only the tests that match the filter will run. - // - // A filter is a colon-separated list of glob (not regex) patterns, - // optionally followed by a '-' and a colon-separated list of - // negative patterns (tests to exclude). A test is run if it - // matches one of the positive patterns and does not match any of - // the negative patterns. - // - // For example, *A*:Foo.* is a filter that matches any string that - // contains the character 'A' or starts with "Foo.". - bool should_run() const { return should_run_; } - - // Returns true iff this test will appear in the XML report. - bool is_reportable() const { - // For now, the XML report includes all tests matching the filter. - // In the future, we may trim tests that are excluded because of - // sharding. - return matches_filter_; - } - - // Returns the result of the test. - const TestResult* result() const { return &result_; } - - private: -#if GTEST_HAS_DEATH_TEST - friend class internal::DefaultDeathTestFactory; -#endif // GTEST_HAS_DEATH_TEST - friend class Test; - friend class TestCase; - friend class internal::UnitTestImpl; - friend class internal::StreamingListenerTest; - friend TestInfo* internal::MakeAndRegisterTestInfo( - const char* test_case_name, - const char* name, - const char* type_param, - const char* value_param, - internal::TypeId fixture_class_id, - Test::SetUpTestCaseFunc set_up_tc, - Test::TearDownTestCaseFunc tear_down_tc, - internal::TestFactoryBase* factory); - - // Constructs a TestInfo object. The newly constructed instance assumes - // ownership of the factory object. - TestInfo(const std::string& test_case_name, - const std::string& name, - const char* a_type_param, // NULL if not a type-parameterized test - const char* a_value_param, // NULL if not a value-parameterized test - internal::TypeId fixture_class_id, - internal::TestFactoryBase* factory); - - // Increments the number of death tests encountered in this test so - // far. - int increment_death_test_count() { - return result_.increment_death_test_count(); - } - - // Creates the test object, runs it, records its result, and then - // deletes it. - void Run(); - - static void ClearTestResult(TestInfo* test_info) { - test_info->result_.Clear(); - } - - // These fields are immutable properties of the test. - const std::string test_case_name_; // Test case name - const std::string name_; // Test name - // Name of the parameter type, or NULL if this is not a typed or a - // type-parameterized test. - const internal::scoped_ptr type_param_; - // Text representation of the value parameter, or NULL if this is not a - // value-parameterized test. - const internal::scoped_ptr value_param_; - const internal::TypeId fixture_class_id_; // ID of the test fixture class - bool should_run_; // True iff this test should run - bool is_disabled_; // True iff this test is disabled - bool matches_filter_; // True if this test matches the - // user-specified filter. - internal::TestFactoryBase* const factory_; // The factory that creates - // the test object - - // This field is mutable and needs to be reset before running the - // test for the second time. - TestResult result_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(TestInfo); -}; - -// A test case, which consists of a vector of TestInfos. -// -// TestCase is not copyable. -class GTEST_API_ TestCase { - public: - // Creates a TestCase with the given name. - // - // TestCase does NOT have a default constructor. Always use this - // constructor to create a TestCase object. - // - // Arguments: - // - // name: name of the test case - // a_type_param: the name of the test's type parameter, or NULL if - // this is not a type-parameterized test. - // set_up_tc: pointer to the function that sets up the test case - // tear_down_tc: pointer to the function that tears down the test case - TestCase(const char* name, const char* a_type_param, - Test::SetUpTestCaseFunc set_up_tc, - Test::TearDownTestCaseFunc tear_down_tc); - - // Destructor of TestCase. - virtual ~TestCase(); - - // Gets the name of the TestCase. - const char* name() const { return name_.c_str(); } - - // Returns the name of the parameter type, or NULL if this is not a - // type-parameterized test case. - const char* type_param() const { - if (type_param_.get() != NULL) - return type_param_->c_str(); - return NULL; - } - - // Returns true if any test in this test case should run. - bool should_run() const { return should_run_; } - - // Gets the number of successful tests in this test case. - int successful_test_count() const; - - // Gets the number of failed tests in this test case. - int failed_test_count() const; - - // Gets the number of disabled tests that will be reported in the XML report. - int reportable_disabled_test_count() const; - - // Gets the number of disabled tests in this test case. - int disabled_test_count() const; - - // Gets the number of tests to be printed in the XML report. - int reportable_test_count() const; - - // Get the number of tests in this test case that should run. - int test_to_run_count() const; - - // Gets the number of all tests in this test case. - int total_test_count() const; - - // Returns true iff the test case passed. - bool Passed() const { return !Failed(); } - - // Returns true iff the test case failed. - bool Failed() const { return failed_test_count() > 0; } - - // Returns the elapsed time, in milliseconds. - TimeInMillis elapsed_time() const { return elapsed_time_; } - - // Returns the i-th test among all the tests. i can range from 0 to - // total_test_count() - 1. If i is not in that range, returns NULL. - const TestInfo* GetTestInfo(int i) const; - - // Returns the TestResult that holds test properties recorded during - // execution of SetUpTestCase and TearDownTestCase. - const TestResult& ad_hoc_test_result() const { return ad_hoc_test_result_; } - - private: - friend class Test; - friend class internal::UnitTestImpl; - - // Gets the (mutable) vector of TestInfos in this TestCase. - std::vector& test_info_list() { return test_info_list_; } - - // Gets the (immutable) vector of TestInfos in this TestCase. - const std::vector& test_info_list() const { - return test_info_list_; - } - - // Returns the i-th test among all the tests. i can range from 0 to - // total_test_count() - 1. If i is not in that range, returns NULL. - TestInfo* GetMutableTestInfo(int i); - - // Sets the should_run member. - void set_should_run(bool should) { should_run_ = should; } - - // Adds a TestInfo to this test case. Will delete the TestInfo upon - // destruction of the TestCase object. - void AddTestInfo(TestInfo * test_info); - - // Clears the results of all tests in this test case. - void ClearResult(); - - // Clears the results of all tests in the given test case. - static void ClearTestCaseResult(TestCase* test_case) { - test_case->ClearResult(); - } - - // Runs every test in this TestCase. - void Run(); - - // Runs SetUpTestCase() for this TestCase. This wrapper is needed - // for catching exceptions thrown from SetUpTestCase(). - void RunSetUpTestCase() { (*set_up_tc_)(); } - - // Runs TearDownTestCase() for this TestCase. This wrapper is - // needed for catching exceptions thrown from TearDownTestCase(). - void RunTearDownTestCase() { (*tear_down_tc_)(); } - - // Returns true iff test passed. - static bool TestPassed(const TestInfo* test_info) { - return test_info->should_run() && test_info->result()->Passed(); - } - - // Returns true iff test failed. - static bool TestFailed(const TestInfo* test_info) { - return test_info->should_run() && test_info->result()->Failed(); - } - - // Returns true iff the test is disabled and will be reported in the XML - // report. - static bool TestReportableDisabled(const TestInfo* test_info) { - return test_info->is_reportable() && test_info->is_disabled_; - } - - // Returns true iff test is disabled. - static bool TestDisabled(const TestInfo* test_info) { - return test_info->is_disabled_; - } - - // Returns true iff this test will appear in the XML report. - static bool TestReportable(const TestInfo* test_info) { - return test_info->is_reportable(); - } - - // Returns true if the given test should run. - static bool ShouldRunTest(const TestInfo* test_info) { - return test_info->should_run(); - } - - // Shuffles the tests in this test case. - void ShuffleTests(internal::Random* random); - - // Restores the test order to before the first shuffle. - void UnshuffleTests(); - - // Name of the test case. - std::string name_; - // Name of the parameter type, or NULL if this is not a typed or a - // type-parameterized test. - const internal::scoped_ptr type_param_; - // The vector of TestInfos in their original order. It owns the - // elements in the vector. - std::vector test_info_list_; - // Provides a level of indirection for the test list to allow easy - // shuffling and restoring the test order. The i-th element in this - // vector is the index of the i-th test in the shuffled test list. - std::vector test_indices_; - // Pointer to the function that sets up the test case. - Test::SetUpTestCaseFunc set_up_tc_; - // Pointer to the function that tears down the test case. - Test::TearDownTestCaseFunc tear_down_tc_; - // True iff any test in this test case should run. - bool should_run_; - // Elapsed time, in milliseconds. - TimeInMillis elapsed_time_; - // Holds test properties recorded during execution of SetUpTestCase and - // TearDownTestCase. - TestResult ad_hoc_test_result_; - - // We disallow copying TestCases. - GTEST_DISALLOW_COPY_AND_ASSIGN_(TestCase); -}; - -// An Environment object is capable of setting up and tearing down an -// environment. The user should subclass this to define his own -// environment(s). -// -// An Environment object does the set-up and tear-down in virtual -// methods SetUp() and TearDown() instead of the constructor and the -// destructor, as: -// -// 1. You cannot safely throw from a destructor. This is a problem -// as in some cases Google Test is used where exceptions are enabled, and -// we may want to implement ASSERT_* using exceptions where they are -// available. -// 2. You cannot use ASSERT_* directly in a constructor or -// destructor. -class Environment { - public: - // The d'tor is virtual as we need to subclass Environment. - virtual ~Environment() {} - - // Override this to define how to set up the environment. - virtual void SetUp() {} - - // Override this to define how to tear down the environment. - virtual void TearDown() {} - private: - // If you see an error about overriding the following function or - // about it being private, you have mis-spelled SetUp() as Setup(). - struct Setup_should_be_spelled_SetUp {}; - virtual Setup_should_be_spelled_SetUp* Setup() { return NULL; } -}; - -// The interface for tracing execution of tests. The methods are organized in -// the order the corresponding events are fired. -class TestEventListener { - public: - virtual ~TestEventListener() {} - - // Fired before any test activity starts. - virtual void OnTestProgramStart(const UnitTest& unit_test) = 0; - - // Fired before each iteration of tests starts. There may be more than - // one iteration if GTEST_FLAG(repeat) is set. iteration is the iteration - // index, starting from 0. - virtual void OnTestIterationStart(const UnitTest& unit_test, - int iteration) = 0; - - // Fired before environment set-up for each iteration of tests starts. - virtual void OnEnvironmentsSetUpStart(const UnitTest& unit_test) = 0; - - // Fired after environment set-up for each iteration of tests ends. - virtual void OnEnvironmentsSetUpEnd(const UnitTest& unit_test) = 0; - - // Fired before the test case starts. - virtual void OnTestCaseStart(const TestCase& test_case) = 0; - - // Fired before the test starts. - virtual void OnTestStart(const TestInfo& test_info) = 0; - - // Fired after a failed assertion or a SUCCEED() invocation. - virtual void OnTestPartResult(const TestPartResult& test_part_result) = 0; - - // Fired after the test ends. - virtual void OnTestEnd(const TestInfo& test_info) = 0; - - // Fired after the test case ends. - virtual void OnTestCaseEnd(const TestCase& test_case) = 0; - - // Fired before environment tear-down for each iteration of tests starts. - virtual void OnEnvironmentsTearDownStart(const UnitTest& unit_test) = 0; - - // Fired after environment tear-down for each iteration of tests ends. - virtual void OnEnvironmentsTearDownEnd(const UnitTest& unit_test) = 0; - - // Fired after each iteration of tests finishes. - virtual void OnTestIterationEnd(const UnitTest& unit_test, - int iteration) = 0; - - // Fired after all test activities have ended. - virtual void OnTestProgramEnd(const UnitTest& unit_test) = 0; -}; - -// The convenience class for users who need to override just one or two -// methods and are not concerned that a possible change to a signature of -// the methods they override will not be caught during the build. For -// comments about each method please see the definition of TestEventListener -// above. -class EmptyTestEventListener : public TestEventListener { - public: - virtual void OnTestProgramStart(const UnitTest& /*unit_test*/) {} - virtual void OnTestIterationStart(const UnitTest& /*unit_test*/, - int /*iteration*/) {} - virtual void OnEnvironmentsSetUpStart(const UnitTest& /*unit_test*/) {} - virtual void OnEnvironmentsSetUpEnd(const UnitTest& /*unit_test*/) {} - virtual void OnTestCaseStart(const TestCase& /*test_case*/) {} - virtual void OnTestStart(const TestInfo& /*test_info*/) {} - virtual void OnTestPartResult(const TestPartResult& /*test_part_result*/) {} - virtual void OnTestEnd(const TestInfo& /*test_info*/) {} - virtual void OnTestCaseEnd(const TestCase& /*test_case*/) {} - virtual void OnEnvironmentsTearDownStart(const UnitTest& /*unit_test*/) {} - virtual void OnEnvironmentsTearDownEnd(const UnitTest& /*unit_test*/) {} - virtual void OnTestIterationEnd(const UnitTest& /*unit_test*/, - int /*iteration*/) {} - virtual void OnTestProgramEnd(const UnitTest& /*unit_test*/) {} -}; - -// TestEventListeners lets users add listeners to track events in Google Test. -class GTEST_API_ TestEventListeners { - public: - TestEventListeners(); - ~TestEventListeners(); - - // Appends an event listener to the end of the list. Google Test assumes - // the ownership of the listener (i.e. it will delete the listener when - // the test program finishes). - void Append(TestEventListener* listener); - - // Removes the given event listener from the list and returns it. It then - // becomes the caller's responsibility to delete the listener. Returns - // NULL if the listener is not found in the list. - TestEventListener* Release(TestEventListener* listener); - - // Returns the standard listener responsible for the default console - // output. Can be removed from the listeners list to shut down default - // console output. Note that removing this object from the listener list - // with Release transfers its ownership to the caller and makes this - // function return NULL the next time. - TestEventListener* default_result_printer() const { - return default_result_printer_; - } - - // Returns the standard listener responsible for the default XML output - // controlled by the --gtest_output=xml flag. Can be removed from the - // listeners list by users who want to shut down the default XML output - // controlled by this flag and substitute it with custom one. Note that - // removing this object from the listener list with Release transfers its - // ownership to the caller and makes this function return NULL the next - // time. - TestEventListener* default_xml_generator() const { - return default_xml_generator_; - } - - private: - friend class TestCase; - friend class TestInfo; - friend class internal::DefaultGlobalTestPartResultReporter; - friend class internal::NoExecDeathTest; - friend class internal::TestEventListenersAccessor; - friend class internal::UnitTestImpl; - - // Returns repeater that broadcasts the TestEventListener events to all - // subscribers. - TestEventListener* repeater(); - - // Sets the default_result_printer attribute to the provided listener. - // The listener is also added to the listener list and previous - // default_result_printer is removed from it and deleted. The listener can - // also be NULL in which case it will not be added to the list. Does - // nothing if the previous and the current listener objects are the same. - void SetDefaultResultPrinter(TestEventListener* listener); - - // Sets the default_xml_generator attribute to the provided listener. The - // listener is also added to the listener list and previous - // default_xml_generator is removed from it and deleted. The listener can - // also be NULL in which case it will not be added to the list. Does - // nothing if the previous and the current listener objects are the same. - void SetDefaultXmlGenerator(TestEventListener* listener); - - // Controls whether events will be forwarded by the repeater to the - // listeners in the list. - bool EventForwardingEnabled() const; - void SuppressEventForwarding(); - - // The actual list of listeners. - internal::TestEventRepeater* repeater_; - // Listener responsible for the standard result output. - TestEventListener* default_result_printer_; - // Listener responsible for the creation of the XML output file. - TestEventListener* default_xml_generator_; - - // We disallow copying TestEventListeners. - GTEST_DISALLOW_COPY_AND_ASSIGN_(TestEventListeners); -}; - -// A UnitTest consists of a vector of TestCases. -// -// This is a singleton class. The only instance of UnitTest is -// created when UnitTest::GetInstance() is first called. This -// instance is never deleted. -// -// UnitTest is not copyable. -// -// This class is thread-safe as long as the methods are called -// according to their specification. -class GTEST_API_ UnitTest { - public: - // Gets the singleton UnitTest object. The first time this method - // is called, a UnitTest object is constructed and returned. - // Consecutive calls will return the same object. - static UnitTest* GetInstance(); - - // Runs all tests in this UnitTest object and prints the result. - // Returns 0 if successful, or 1 otherwise. - // - // This method can only be called from the main thread. - // - // INTERNAL IMPLEMENTATION - DO NOT USE IN A USER PROGRAM. - int Run() GTEST_MUST_USE_RESULT_; - - // Returns the working directory when the first TEST() or TEST_F() - // was executed. The UnitTest object owns the string. - const char* original_working_dir() const; - - // Returns the TestCase object for the test that's currently running, - // or NULL if no test is running. - const TestCase* current_test_case() const - GTEST_LOCK_EXCLUDED_(mutex_); - - // Returns the TestInfo object for the test that's currently running, - // or NULL if no test is running. - const TestInfo* current_test_info() const - GTEST_LOCK_EXCLUDED_(mutex_); - - // Returns the random seed used at the start of the current test run. - int random_seed() const; - -#if GTEST_HAS_PARAM_TEST - // Returns the ParameterizedTestCaseRegistry object used to keep track of - // value-parameterized tests and instantiate and register them. - // - // INTERNAL IMPLEMENTATION - DO NOT USE IN A USER PROGRAM. - internal::ParameterizedTestCaseRegistry& parameterized_test_registry() - GTEST_LOCK_EXCLUDED_(mutex_); -#endif // GTEST_HAS_PARAM_TEST - - // Gets the number of successful test cases. - int successful_test_case_count() const; - - // Gets the number of failed test cases. - int failed_test_case_count() const; - - // Gets the number of all test cases. - int total_test_case_count() const; - - // Gets the number of all test cases that contain at least one test - // that should run. - int test_case_to_run_count() const; - - // Gets the number of successful tests. - int successful_test_count() const; - - // Gets the number of failed tests. - int failed_test_count() const; - - // Gets the number of disabled tests that will be reported in the XML report. - int reportable_disabled_test_count() const; - - // Gets the number of disabled tests. - int disabled_test_count() const; - - // Gets the number of tests to be printed in the XML report. - int reportable_test_count() const; - - // Gets the number of all tests. - int total_test_count() const; - - // Gets the number of tests that should run. - int test_to_run_count() const; - - // Gets the time of the test program start, in ms from the start of the - // UNIX epoch. - TimeInMillis start_timestamp() const; - - // Gets the elapsed time, in milliseconds. - TimeInMillis elapsed_time() const; - - // Returns true iff the unit test passed (i.e. all test cases passed). - bool Passed() const; - - // Returns true iff the unit test failed (i.e. some test case failed - // or something outside of all tests failed). - bool Failed() const; - - // Gets the i-th test case among all the test cases. i can range from 0 to - // total_test_case_count() - 1. If i is not in that range, returns NULL. - const TestCase* GetTestCase(int i) const; - - // Returns the TestResult containing information on test failures and - // properties logged outside of individual test cases. - const TestResult& ad_hoc_test_result() const; - - // Returns the list of event listeners that can be used to track events - // inside Google Test. - TestEventListeners& listeners(); - - private: - // Registers and returns a global test environment. When a test - // program is run, all global test environments will be set-up in - // the order they were registered. After all tests in the program - // have finished, all global test environments will be torn-down in - // the *reverse* order they were registered. - // - // The UnitTest object takes ownership of the given environment. - // - // This method can only be called from the main thread. - Environment* AddEnvironment(Environment* env); - - // Adds a TestPartResult to the current TestResult object. All - // Google Test assertion macros (e.g. ASSERT_TRUE, EXPECT_EQ, etc) - // eventually call this to report their results. The user code - // should use the assertion macros instead of calling this directly. - void AddTestPartResult(TestPartResult::Type result_type, - const char* file_name, - int line_number, - const std::string& message, - const std::string& os_stack_trace) - GTEST_LOCK_EXCLUDED_(mutex_); - - // Adds a TestProperty to the current TestResult object when invoked from - // inside a test, to current TestCase's ad_hoc_test_result_ when invoked - // from SetUpTestCase or TearDownTestCase, or to the global property set - // when invoked elsewhere. If the result already contains a property with - // the same key, the value will be updated. - void RecordProperty(const std::string& key, const std::string& value); - - // Gets the i-th test case among all the test cases. i can range from 0 to - // total_test_case_count() - 1. If i is not in that range, returns NULL. - TestCase* GetMutableTestCase(int i); - - // Accessors for the implementation object. - internal::UnitTestImpl* impl() { return impl_; } - const internal::UnitTestImpl* impl() const { return impl_; } - - // These classes and funcions are friends as they need to access private - // members of UnitTest. - friend class Test; - friend class internal::AssertHelper; - friend class internal::ScopedTrace; - friend class internal::StreamingListenerTest; - friend class internal::UnitTestRecordPropertyTestHelper; - friend Environment* AddGlobalTestEnvironment(Environment* env); - friend internal::UnitTestImpl* internal::GetUnitTestImpl(); - friend void internal::ReportFailureInUnknownLocation( - TestPartResult::Type result_type, - const std::string& message); - - // Creates an empty UnitTest. - UnitTest(); - - // D'tor - virtual ~UnitTest(); - - // Pushes a trace defined by SCOPED_TRACE() on to the per-thread - // Google Test trace stack. - void PushGTestTrace(const internal::TraceInfo& trace) - GTEST_LOCK_EXCLUDED_(mutex_); - - // Pops a trace from the per-thread Google Test trace stack. - void PopGTestTrace() - GTEST_LOCK_EXCLUDED_(mutex_); - - // Protects mutable state in *impl_. This is mutable as some const - // methods need to lock it too. - mutable internal::Mutex mutex_; - - // Opaque implementation object. This field is never changed once - // the object is constructed. We don't mark it as const here, as - // doing so will cause a warning in the constructor of UnitTest. - // Mutable state in *impl_ is protected by mutex_. - internal::UnitTestImpl* impl_; - - // We disallow copying UnitTest. - GTEST_DISALLOW_COPY_AND_ASSIGN_(UnitTest); -}; - -// A convenient wrapper for adding an environment for the test -// program. -// -// You should call this before RUN_ALL_TESTS() is called, probably in -// main(). If you use gtest_main, you need to call this before main() -// starts for it to take effect. For example, you can define a global -// variable like this: -// -// testing::Environment* const foo_env = -// testing::AddGlobalTestEnvironment(new FooEnvironment); -// -// However, we strongly recommend you to write your own main() and -// call AddGlobalTestEnvironment() there, as relying on initialization -// of global variables makes the code harder to read and may cause -// problems when you register multiple environments from different -// translation units and the environments have dependencies among them -// (remember that the compiler doesn't guarantee the order in which -// global variables from different translation units are initialized). -inline Environment* AddGlobalTestEnvironment(Environment* env) { - return UnitTest::GetInstance()->AddEnvironment(env); -} - -// Initializes Google Test. This must be called before calling -// RUN_ALL_TESTS(). In particular, it parses a command line for the -// flags that Google Test recognizes. Whenever a Google Test flag is -// seen, it is removed from argv, and *argc is decremented. -// -// No value is returned. Instead, the Google Test flag variables are -// updated. -// -// Calling the function for the second time has no user-visible effect. -GTEST_API_ void InitGoogleTest(int* argc, char** argv); - -// This overloaded version can be used in Windows programs compiled in -// UNICODE mode. -GTEST_API_ void InitGoogleTest(int* argc, wchar_t** argv); - -namespace internal { - -// FormatForComparison::Format(value) formats a -// value of type ToPrint that is an operand of a comparison assertion -// (e.g. ASSERT_EQ). OtherOperand is the type of the other operand in -// the comparison, and is used to help determine the best way to -// format the value. In particular, when the value is a C string -// (char pointer) and the other operand is an STL string object, we -// want to format the C string as a string, since we know it is -// compared by value with the string object. If the value is a char -// pointer but the other operand is not an STL string object, we don't -// know whether the pointer is supposed to point to a NUL-terminated -// string, and thus want to print it as a pointer to be safe. -// -// INTERNAL IMPLEMENTATION - DO NOT USE IN A USER PROGRAM. - -// The default case. -template -class FormatForComparison { - public: - static ::std::string Format(const ToPrint& value) { - return ::testing::PrintToString(value); - } -}; - -// Array. -template -class FormatForComparison { - public: - static ::std::string Format(const ToPrint* value) { - return FormatForComparison::Format(value); - } -}; - -// By default, print C string as pointers to be safe, as we don't know -// whether they actually point to a NUL-terminated string. - -#define GTEST_IMPL_FORMAT_C_STRING_AS_POINTER_(CharType) \ - template \ - class FormatForComparison { \ - public: \ - static ::std::string Format(CharType* value) { \ - return ::testing::PrintToString(static_cast(value)); \ - } \ - } - -GTEST_IMPL_FORMAT_C_STRING_AS_POINTER_(char); -GTEST_IMPL_FORMAT_C_STRING_AS_POINTER_(const char); -GTEST_IMPL_FORMAT_C_STRING_AS_POINTER_(wchar_t); -GTEST_IMPL_FORMAT_C_STRING_AS_POINTER_(const wchar_t); - -#undef GTEST_IMPL_FORMAT_C_STRING_AS_POINTER_ - -// If a C string is compared with an STL string object, we know it's meant -// to point to a NUL-terminated string, and thus can print it as a string. - -#define GTEST_IMPL_FORMAT_C_STRING_AS_STRING_(CharType, OtherStringType) \ - template <> \ - class FormatForComparison { \ - public: \ - static ::std::string Format(CharType* value) { \ - return ::testing::PrintToString(value); \ - } \ - } - -GTEST_IMPL_FORMAT_C_STRING_AS_STRING_(char, ::std::string); -GTEST_IMPL_FORMAT_C_STRING_AS_STRING_(const char, ::std::string); - -#if GTEST_HAS_GLOBAL_STRING -GTEST_IMPL_FORMAT_C_STRING_AS_STRING_(char, ::string); -GTEST_IMPL_FORMAT_C_STRING_AS_STRING_(const char, ::string); -#endif - -#if GTEST_HAS_GLOBAL_WSTRING -GTEST_IMPL_FORMAT_C_STRING_AS_STRING_(wchar_t, ::wstring); -GTEST_IMPL_FORMAT_C_STRING_AS_STRING_(const wchar_t, ::wstring); -#endif - -#if GTEST_HAS_STD_WSTRING -GTEST_IMPL_FORMAT_C_STRING_AS_STRING_(wchar_t, ::std::wstring); -GTEST_IMPL_FORMAT_C_STRING_AS_STRING_(const wchar_t, ::std::wstring); -#endif - -#undef GTEST_IMPL_FORMAT_C_STRING_AS_STRING_ - -// Formats a comparison assertion (e.g. ASSERT_EQ, EXPECT_LT, and etc) -// operand to be used in a failure message. The type (but not value) -// of the other operand may affect the format. This allows us to -// print a char* as a raw pointer when it is compared against another -// char* or void*, and print it as a C string when it is compared -// against an std::string object, for example. -// -// INTERNAL IMPLEMENTATION - DO NOT USE IN A USER PROGRAM. -template -std::string FormatForComparisonFailureMessage( - const T1& value, const T2& /* other_operand */) { - return FormatForComparison::Format(value); -} - -// The helper function for {ASSERT|EXPECT}_EQ. -template -AssertionResult CmpHelperEQ(const char* expected_expression, - const char* actual_expression, - const T1& expected, - const T2& actual) { -#ifdef _MSC_VER -# pragma warning(push) // Saves the current warning state. -# pragma warning(disable:4389) // Temporarily disables warning on - // signed/unsigned mismatch. -#endif - - if (expected == actual) { - return AssertionSuccess(); - } - -#ifdef _MSC_VER -# pragma warning(pop) // Restores the warning state. -#endif - - return EqFailure(expected_expression, - actual_expression, - FormatForComparisonFailureMessage(expected, actual), - FormatForComparisonFailureMessage(actual, expected), - false); -} - -// With this overloaded version, we allow anonymous enums to be used -// in {ASSERT|EXPECT}_EQ when compiled with gcc 4, as anonymous enums -// can be implicitly cast to BiggestInt. -GTEST_API_ AssertionResult CmpHelperEQ(const char* expected_expression, - const char* actual_expression, - BiggestInt expected, - BiggestInt actual); - -// The helper class for {ASSERT|EXPECT}_EQ. The template argument -// lhs_is_null_literal is true iff the first argument to ASSERT_EQ() -// is a null pointer literal. The following default implementation is -// for lhs_is_null_literal being false. -template -class EqHelper { - public: - // This templatized version is for the general case. - template - static AssertionResult Compare(const char* expected_expression, - const char* actual_expression, - const T1& expected, - const T2& actual) { - return CmpHelperEQ(expected_expression, actual_expression, expected, - actual); - } - - // With this overloaded version, we allow anonymous enums to be used - // in {ASSERT|EXPECT}_EQ when compiled with gcc 4, as anonymous - // enums can be implicitly cast to BiggestInt. - // - // Even though its body looks the same as the above version, we - // cannot merge the two, as it will make anonymous enums unhappy. - static AssertionResult Compare(const char* expected_expression, - const char* actual_expression, - BiggestInt expected, - BiggestInt actual) { - return CmpHelperEQ(expected_expression, actual_expression, expected, - actual); - } -}; - -// This specialization is used when the first argument to ASSERT_EQ() -// is a null pointer literal, like NULL, false, or 0. -template <> -class EqHelper { - public: - // We define two overloaded versions of Compare(). The first - // version will be picked when the second argument to ASSERT_EQ() is - // NOT a pointer, e.g. ASSERT_EQ(0, AnIntFunction()) or - // EXPECT_EQ(false, a_bool). - template - static AssertionResult Compare( - const char* expected_expression, - const char* actual_expression, - const T1& expected, - const T2& actual, - // The following line prevents this overload from being considered if T2 - // is not a pointer type. We need this because ASSERT_EQ(NULL, my_ptr) - // expands to Compare("", "", NULL, my_ptr), which requires a conversion - // to match the Secret* in the other overload, which would otherwise make - // this template match better. - typename EnableIf::value>::type* = 0) { - return CmpHelperEQ(expected_expression, actual_expression, expected, - actual); - } - - // This version will be picked when the second argument to ASSERT_EQ() is a - // pointer, e.g. ASSERT_EQ(NULL, a_pointer). - template - static AssertionResult Compare( - const char* expected_expression, - const char* actual_expression, - // We used to have a second template parameter instead of Secret*. That - // template parameter would deduce to 'long', making this a better match - // than the first overload even without the first overload's EnableIf. - // Unfortunately, gcc with -Wconversion-null warns when "passing NULL to - // non-pointer argument" (even a deduced integral argument), so the old - // implementation caused warnings in user code. - Secret* /* expected (NULL) */, - T* actual) { - // We already know that 'expected' is a null pointer. - return CmpHelperEQ(expected_expression, actual_expression, - static_cast(NULL), actual); - } -}; - -// A macro for implementing the helper functions needed to implement -// ASSERT_?? and EXPECT_??. It is here just to avoid copy-and-paste -// of similar code. -// -// For each templatized helper function, we also define an overloaded -// version for BiggestInt in order to reduce code bloat and allow -// anonymous enums to be used with {ASSERT|EXPECT}_?? when compiled -// with gcc 4. -// -// INTERNAL IMPLEMENTATION - DO NOT USE IN A USER PROGRAM. -#define GTEST_IMPL_CMP_HELPER_(op_name, op)\ -template \ -AssertionResult CmpHelper##op_name(const char* expr1, const char* expr2, \ - const T1& val1, const T2& val2) {\ - if (val1 op val2) {\ - return AssertionSuccess();\ - } else {\ - return AssertionFailure() \ - << "Expected: (" << expr1 << ") " #op " (" << expr2\ - << "), actual: " << FormatForComparisonFailureMessage(val1, val2)\ - << " vs " << FormatForComparisonFailureMessage(val2, val1);\ - }\ -}\ -GTEST_API_ AssertionResult CmpHelper##op_name(\ - const char* expr1, const char* expr2, BiggestInt val1, BiggestInt val2) - -// INTERNAL IMPLEMENTATION - DO NOT USE IN A USER PROGRAM. - -// Implements the helper function for {ASSERT|EXPECT}_NE -GTEST_IMPL_CMP_HELPER_(NE, !=); -// Implements the helper function for {ASSERT|EXPECT}_LE -GTEST_IMPL_CMP_HELPER_(LE, <=); -// Implements the helper function for {ASSERT|EXPECT}_LT -GTEST_IMPL_CMP_HELPER_(LT, <); -// Implements the helper function for {ASSERT|EXPECT}_GE -GTEST_IMPL_CMP_HELPER_(GE, >=); -// Implements the helper function for {ASSERT|EXPECT}_GT -GTEST_IMPL_CMP_HELPER_(GT, >); - -#undef GTEST_IMPL_CMP_HELPER_ - -// The helper function for {ASSERT|EXPECT}_STREQ. -// -// INTERNAL IMPLEMENTATION - DO NOT USE IN A USER PROGRAM. -GTEST_API_ AssertionResult CmpHelperSTREQ(const char* expected_expression, - const char* actual_expression, - const char* expected, - const char* actual); - -// The helper function for {ASSERT|EXPECT}_STRCASEEQ. -// -// INTERNAL IMPLEMENTATION - DO NOT USE IN A USER PROGRAM. -GTEST_API_ AssertionResult CmpHelperSTRCASEEQ(const char* expected_expression, - const char* actual_expression, - const char* expected, - const char* actual); - -// The helper function for {ASSERT|EXPECT}_STRNE. -// -// INTERNAL IMPLEMENTATION - DO NOT USE IN A USER PROGRAM. -GTEST_API_ AssertionResult CmpHelperSTRNE(const char* s1_expression, - const char* s2_expression, - const char* s1, - const char* s2); - -// The helper function for {ASSERT|EXPECT}_STRCASENE. -// -// INTERNAL IMPLEMENTATION - DO NOT USE IN A USER PROGRAM. -GTEST_API_ AssertionResult CmpHelperSTRCASENE(const char* s1_expression, - const char* s2_expression, - const char* s1, - const char* s2); - - -// Helper function for *_STREQ on wide strings. -// -// INTERNAL IMPLEMENTATION - DO NOT USE IN A USER PROGRAM. -GTEST_API_ AssertionResult CmpHelperSTREQ(const char* expected_expression, - const char* actual_expression, - const wchar_t* expected, - const wchar_t* actual); - -// Helper function for *_STRNE on wide strings. -// -// INTERNAL IMPLEMENTATION - DO NOT USE IN A USER PROGRAM. -GTEST_API_ AssertionResult CmpHelperSTRNE(const char* s1_expression, - const char* s2_expression, - const wchar_t* s1, - const wchar_t* s2); - -} // namespace internal - -// IsSubstring() and IsNotSubstring() are intended to be used as the -// first argument to {EXPECT,ASSERT}_PRED_FORMAT2(), not by -// themselves. They check whether needle is a substring of haystack -// (NULL is considered a substring of itself only), and return an -// appropriate error message when they fail. -// -// The {needle,haystack}_expr arguments are the stringified -// expressions that generated the two real arguments. -GTEST_API_ AssertionResult IsSubstring( - const char* needle_expr, const char* haystack_expr, - const char* needle, const char* haystack); -GTEST_API_ AssertionResult IsSubstring( - const char* needle_expr, const char* haystack_expr, - const wchar_t* needle, const wchar_t* haystack); -GTEST_API_ AssertionResult IsNotSubstring( - const char* needle_expr, const char* haystack_expr, - const char* needle, const char* haystack); -GTEST_API_ AssertionResult IsNotSubstring( - const char* needle_expr, const char* haystack_expr, - const wchar_t* needle, const wchar_t* haystack); -GTEST_API_ AssertionResult IsSubstring( - const char* needle_expr, const char* haystack_expr, - const ::std::string& needle, const ::std::string& haystack); -GTEST_API_ AssertionResult IsNotSubstring( - const char* needle_expr, const char* haystack_expr, - const ::std::string& needle, const ::std::string& haystack); - -#if GTEST_HAS_STD_WSTRING -GTEST_API_ AssertionResult IsSubstring( - const char* needle_expr, const char* haystack_expr, - const ::std::wstring& needle, const ::std::wstring& haystack); -GTEST_API_ AssertionResult IsNotSubstring( - const char* needle_expr, const char* haystack_expr, - const ::std::wstring& needle, const ::std::wstring& haystack); -#endif // GTEST_HAS_STD_WSTRING - -namespace internal { - -// Helper template function for comparing floating-points. -// -// Template parameter: -// -// RawType: the raw floating-point type (either float or double) -// -// INTERNAL IMPLEMENTATION - DO NOT USE IN A USER PROGRAM. -template -AssertionResult CmpHelperFloatingPointEQ(const char* expected_expression, - const char* actual_expression, - RawType expected, - RawType actual) { - const FloatingPoint lhs(expected), rhs(actual); - - if (lhs.AlmostEquals(rhs)) { - return AssertionSuccess(); - } - - ::std::stringstream expected_ss; - expected_ss << std::setprecision(std::numeric_limits::digits10 + 2) - << expected; - - ::std::stringstream actual_ss; - actual_ss << std::setprecision(std::numeric_limits::digits10 + 2) - << actual; - - return EqFailure(expected_expression, - actual_expression, - StringStreamToString(&expected_ss), - StringStreamToString(&actual_ss), - false); -} - -// Helper function for implementing ASSERT_NEAR. -// -// INTERNAL IMPLEMENTATION - DO NOT USE IN A USER PROGRAM. -GTEST_API_ AssertionResult DoubleNearPredFormat(const char* expr1, - const char* expr2, - const char* abs_error_expr, - double val1, - double val2, - double abs_error); - -// INTERNAL IMPLEMENTATION - DO NOT USE IN USER CODE. -// A class that enables one to stream messages to assertion macros -class GTEST_API_ AssertHelper { - public: - // Constructor. - AssertHelper(TestPartResult::Type type, - const char* file, - int line, - const char* message); - ~AssertHelper(); - - // Message assignment is a semantic trick to enable assertion - // streaming; see the GTEST_MESSAGE_ macro below. - void operator=(const Message& message) const; - - private: - // We put our data in a struct so that the size of the AssertHelper class can - // be as small as possible. This is important because gcc is incapable of - // re-using stack space even for temporary variables, so every EXPECT_EQ - // reserves stack space for another AssertHelper. - struct AssertHelperData { - AssertHelperData(TestPartResult::Type t, - const char* srcfile, - int line_num, - const char* msg) - : type(t), file(srcfile), line(line_num), message(msg) { } - - TestPartResult::Type const type; - const char* const file; - int const line; - std::string const message; - - private: - GTEST_DISALLOW_COPY_AND_ASSIGN_(AssertHelperData); - }; - - AssertHelperData* const data_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(AssertHelper); -}; - -} // namespace internal - -#if GTEST_HAS_PARAM_TEST -// The pure interface class that all value-parameterized tests inherit from. -// A value-parameterized class must inherit from both ::testing::Test and -// ::testing::WithParamInterface. In most cases that just means inheriting -// from ::testing::TestWithParam, but more complicated test hierarchies -// may need to inherit from Test and WithParamInterface at different levels. -// -// This interface has support for accessing the test parameter value via -// the GetParam() method. -// -// Use it with one of the parameter generator defining functions, like Range(), -// Values(), ValuesIn(), Bool(), and Combine(). -// -// class FooTest : public ::testing::TestWithParam { -// protected: -// FooTest() { -// // Can use GetParam() here. -// } -// virtual ~FooTest() { -// // Can use GetParam() here. -// } -// virtual void SetUp() { -// // Can use GetParam() here. -// } -// virtual void TearDown { -// // Can use GetParam() here. -// } -// }; -// TEST_P(FooTest, DoesBar) { -// // Can use GetParam() method here. -// Foo foo; -// ASSERT_TRUE(foo.DoesBar(GetParam())); -// } -// INSTANTIATE_TEST_CASE_P(OneToTenRange, FooTest, ::testing::Range(1, 10)); - -template -class WithParamInterface { - public: - typedef T ParamType; - virtual ~WithParamInterface() {} - - // The current parameter value. Is also available in the test fixture's - // constructor. This member function is non-static, even though it only - // references static data, to reduce the opportunity for incorrect uses - // like writing 'WithParamInterface::GetParam()' for a test that - // uses a fixture whose parameter type is int. - const ParamType& GetParam() const { - GTEST_CHECK_(parameter_ != NULL) - << "GetParam() can only be called inside a value-parameterized test " - << "-- did you intend to write TEST_P instead of TEST_F?"; - return *parameter_; - } - - private: - // Sets parameter value. The caller is responsible for making sure the value - // remains alive and unchanged throughout the current test. - static void SetParam(const ParamType* parameter) { - parameter_ = parameter; - } - - // Static value used for accessing parameter during a test lifetime. - static const ParamType* parameter_; - - // TestClass must be a subclass of WithParamInterface and Test. - template friend class internal::ParameterizedTestFactory; -}; - -template -const T* WithParamInterface::parameter_ = NULL; - -// Most value-parameterized classes can ignore the existence of -// WithParamInterface, and can just inherit from ::testing::TestWithParam. - -template -class TestWithParam : public Test, public WithParamInterface { -}; - -#endif // GTEST_HAS_PARAM_TEST - -// Macros for indicating success/failure in test code. - -// ADD_FAILURE unconditionally adds a failure to the current test. -// SUCCEED generates a success - it doesn't automatically make the -// current test successful, as a test is only successful when it has -// no failure. -// -// EXPECT_* verifies that a certain condition is satisfied. If not, -// it behaves like ADD_FAILURE. In particular: -// -// EXPECT_TRUE verifies that a Boolean condition is true. -// EXPECT_FALSE verifies that a Boolean condition is false. -// -// FAIL and ASSERT_* are similar to ADD_FAILURE and EXPECT_*, except -// that they will also abort the current function on failure. People -// usually want the fail-fast behavior of FAIL and ASSERT_*, but those -// writing data-driven tests often find themselves using ADD_FAILURE -// and EXPECT_* more. - -// Generates a nonfatal failure with a generic message. -#define ADD_FAILURE() GTEST_NONFATAL_FAILURE_("Failed") - -// Generates a nonfatal failure at the given source file location with -// a generic message. -#define ADD_FAILURE_AT(file, line) \ - GTEST_MESSAGE_AT_(file, line, "Failed", \ - ::testing::TestPartResult::kNonFatalFailure) - -// Generates a fatal failure with a generic message. -#define GTEST_FAIL() GTEST_FATAL_FAILURE_("Failed") - -// Define this macro to 1 to omit the definition of FAIL(), which is a -// generic name and clashes with some other libraries. -#if !GTEST_DONT_DEFINE_FAIL -# define FAIL() GTEST_FAIL() -#endif - -// Generates a success with a generic message. -#define GTEST_SUCCEED() GTEST_SUCCESS_("Succeeded") - -// Define this macro to 1 to omit the definition of SUCCEED(), which -// is a generic name and clashes with some other libraries. -#if !GTEST_DONT_DEFINE_SUCCEED -# define SUCCEED() GTEST_SUCCEED() -#endif - -// Macros for testing exceptions. -// -// * {ASSERT|EXPECT}_THROW(statement, expected_exception): -// Tests that the statement throws the expected exception. -// * {ASSERT|EXPECT}_NO_THROW(statement): -// Tests that the statement doesn't throw any exception. -// * {ASSERT|EXPECT}_ANY_THROW(statement): -// Tests that the statement throws an exception. - -#define EXPECT_THROW(statement, expected_exception) \ - GTEST_TEST_THROW_(statement, expected_exception, GTEST_NONFATAL_FAILURE_) -#define EXPECT_NO_THROW(statement) \ - GTEST_TEST_NO_THROW_(statement, GTEST_NONFATAL_FAILURE_) -#define EXPECT_ANY_THROW(statement) \ - GTEST_TEST_ANY_THROW_(statement, GTEST_NONFATAL_FAILURE_) -#define ASSERT_THROW(statement, expected_exception) \ - GTEST_TEST_THROW_(statement, expected_exception, GTEST_FATAL_FAILURE_) -#define ASSERT_NO_THROW(statement) \ - GTEST_TEST_NO_THROW_(statement, GTEST_FATAL_FAILURE_) -#define ASSERT_ANY_THROW(statement) \ - GTEST_TEST_ANY_THROW_(statement, GTEST_FATAL_FAILURE_) - -// Boolean assertions. Condition can be either a Boolean expression or an -// AssertionResult. For more information on how to use AssertionResult with -// these macros see comments on that class. -#define EXPECT_TRUE(condition) \ - GTEST_TEST_BOOLEAN_(condition, #condition, false, true, \ - GTEST_NONFATAL_FAILURE_) -#define EXPECT_FALSE(condition) \ - GTEST_TEST_BOOLEAN_(!(condition), #condition, true, false, \ - GTEST_NONFATAL_FAILURE_) -#define ASSERT_TRUE(condition) \ - GTEST_TEST_BOOLEAN_(condition, #condition, false, true, \ - GTEST_FATAL_FAILURE_) -#define ASSERT_FALSE(condition) \ - GTEST_TEST_BOOLEAN_(!(condition), #condition, true, false, \ - GTEST_FATAL_FAILURE_) - -// Includes the auto-generated header that implements a family of -// generic predicate assertion macros. -// Copyright 2006, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. - -// This file is AUTOMATICALLY GENERATED on 10/31/2011 by command -// 'gen_gtest_pred_impl.py 5'. DO NOT EDIT BY HAND! -// -// Implements a family of generic predicate assertion macros. - -#ifndef GTEST_INCLUDE_GTEST_GTEST_PRED_IMPL_H_ -#define GTEST_INCLUDE_GTEST_GTEST_PRED_IMPL_H_ - -// Makes sure this header is not included before gtest.h. -#ifndef GTEST_INCLUDE_GTEST_GTEST_H_ -# error Do not include gtest_pred_impl.h directly. Include gtest.h instead. -#endif // GTEST_INCLUDE_GTEST_GTEST_H_ - -// This header implements a family of generic predicate assertion -// macros: -// -// ASSERT_PRED_FORMAT1(pred_format, v1) -// ASSERT_PRED_FORMAT2(pred_format, v1, v2) -// ... -// -// where pred_format is a function or functor that takes n (in the -// case of ASSERT_PRED_FORMATn) values and their source expression -// text, and returns a testing::AssertionResult. See the definition -// of ASSERT_EQ in gtest.h for an example. -// -// If you don't care about formatting, you can use the more -// restrictive version: -// -// ASSERT_PRED1(pred, v1) -// ASSERT_PRED2(pred, v1, v2) -// ... -// -// where pred is an n-ary function or functor that returns bool, -// and the values v1, v2, ..., must support the << operator for -// streaming to std::ostream. -// -// We also define the EXPECT_* variations. -// -// For now we only support predicates whose arity is at most 5. -// Please email googletestframework@googlegroups.com if you need -// support for higher arities. - -// GTEST_ASSERT_ is the basic statement to which all of the assertions -// in this file reduce. Don't use this in your code. - -#define GTEST_ASSERT_(expression, on_failure) \ - GTEST_AMBIGUOUS_ELSE_BLOCKER_ \ - if (const ::testing::AssertionResult gtest_ar = (expression)) \ - ; \ - else \ - on_failure(gtest_ar.failure_message()) - - -// Helper function for implementing {EXPECT|ASSERT}_PRED1. Don't use -// this in your code. -template -AssertionResult AssertPred1Helper(const char* pred_text, - const char* e1, - Pred pred, - const T1& v1) { - if (pred(v1)) return AssertionSuccess(); - - return AssertionFailure() << pred_text << "(" - << e1 << ") evaluates to false, where" - << "\n" << e1 << " evaluates to " << v1; -} - -// Internal macro for implementing {EXPECT|ASSERT}_PRED_FORMAT1. -// Don't use this in your code. -#define GTEST_PRED_FORMAT1_(pred_format, v1, on_failure)\ - GTEST_ASSERT_(pred_format(#v1, v1), \ - on_failure) - -// Internal macro for implementing {EXPECT|ASSERT}_PRED1. Don't use -// this in your code. -#define GTEST_PRED1_(pred, v1, on_failure)\ - GTEST_ASSERT_(::testing::AssertPred1Helper(#pred, \ - #v1, \ - pred, \ - v1), on_failure) - -// Unary predicate assertion macros. -#define EXPECT_PRED_FORMAT1(pred_format, v1) \ - GTEST_PRED_FORMAT1_(pred_format, v1, GTEST_NONFATAL_FAILURE_) -#define EXPECT_PRED1(pred, v1) \ - GTEST_PRED1_(pred, v1, GTEST_NONFATAL_FAILURE_) -#define ASSERT_PRED_FORMAT1(pred_format, v1) \ - GTEST_PRED_FORMAT1_(pred_format, v1, GTEST_FATAL_FAILURE_) -#define ASSERT_PRED1(pred, v1) \ - GTEST_PRED1_(pred, v1, GTEST_FATAL_FAILURE_) - - - -// Helper function for implementing {EXPECT|ASSERT}_PRED2. Don't use -// this in your code. -template -AssertionResult AssertPred2Helper(const char* pred_text, - const char* e1, - const char* e2, - Pred pred, - const T1& v1, - const T2& v2) { - if (pred(v1, v2)) return AssertionSuccess(); - - return AssertionFailure() << pred_text << "(" - << e1 << ", " - << e2 << ") evaluates to false, where" - << "\n" << e1 << " evaluates to " << v1 - << "\n" << e2 << " evaluates to " << v2; -} - -// Internal macro for implementing {EXPECT|ASSERT}_PRED_FORMAT2. -// Don't use this in your code. -#define GTEST_PRED_FORMAT2_(pred_format, v1, v2, on_failure)\ - GTEST_ASSERT_(pred_format(#v1, #v2, v1, v2), \ - on_failure) - -// Internal macro for implementing {EXPECT|ASSERT}_PRED2. Don't use -// this in your code. -#define GTEST_PRED2_(pred, v1, v2, on_failure)\ - GTEST_ASSERT_(::testing::AssertPred2Helper(#pred, \ - #v1, \ - #v2, \ - pred, \ - v1, \ - v2), on_failure) - -// Binary predicate assertion macros. -#define EXPECT_PRED_FORMAT2(pred_format, v1, v2) \ - GTEST_PRED_FORMAT2_(pred_format, v1, v2, GTEST_NONFATAL_FAILURE_) -#define EXPECT_PRED2(pred, v1, v2) \ - GTEST_PRED2_(pred, v1, v2, GTEST_NONFATAL_FAILURE_) -#define ASSERT_PRED_FORMAT2(pred_format, v1, v2) \ - GTEST_PRED_FORMAT2_(pred_format, v1, v2, GTEST_FATAL_FAILURE_) -#define ASSERT_PRED2(pred, v1, v2) \ - GTEST_PRED2_(pred, v1, v2, GTEST_FATAL_FAILURE_) - - - -// Helper function for implementing {EXPECT|ASSERT}_PRED3. Don't use -// this in your code. -template -AssertionResult AssertPred3Helper(const char* pred_text, - const char* e1, - const char* e2, - const char* e3, - Pred pred, - const T1& v1, - const T2& v2, - const T3& v3) { - if (pred(v1, v2, v3)) return AssertionSuccess(); - - return AssertionFailure() << pred_text << "(" - << e1 << ", " - << e2 << ", " - << e3 << ") evaluates to false, where" - << "\n" << e1 << " evaluates to " << v1 - << "\n" << e2 << " evaluates to " << v2 - << "\n" << e3 << " evaluates to " << v3; -} - -// Internal macro for implementing {EXPECT|ASSERT}_PRED_FORMAT3. -// Don't use this in your code. -#define GTEST_PRED_FORMAT3_(pred_format, v1, v2, v3, on_failure)\ - GTEST_ASSERT_(pred_format(#v1, #v2, #v3, v1, v2, v3), \ - on_failure) - -// Internal macro for implementing {EXPECT|ASSERT}_PRED3. Don't use -// this in your code. -#define GTEST_PRED3_(pred, v1, v2, v3, on_failure)\ - GTEST_ASSERT_(::testing::AssertPred3Helper(#pred, \ - #v1, \ - #v2, \ - #v3, \ - pred, \ - v1, \ - v2, \ - v3), on_failure) - -// Ternary predicate assertion macros. -#define EXPECT_PRED_FORMAT3(pred_format, v1, v2, v3) \ - GTEST_PRED_FORMAT3_(pred_format, v1, v2, v3, GTEST_NONFATAL_FAILURE_) -#define EXPECT_PRED3(pred, v1, v2, v3) \ - GTEST_PRED3_(pred, v1, v2, v3, GTEST_NONFATAL_FAILURE_) -#define ASSERT_PRED_FORMAT3(pred_format, v1, v2, v3) \ - GTEST_PRED_FORMAT3_(pred_format, v1, v2, v3, GTEST_FATAL_FAILURE_) -#define ASSERT_PRED3(pred, v1, v2, v3) \ - GTEST_PRED3_(pred, v1, v2, v3, GTEST_FATAL_FAILURE_) - - - -// Helper function for implementing {EXPECT|ASSERT}_PRED4. Don't use -// this in your code. -template -AssertionResult AssertPred4Helper(const char* pred_text, - const char* e1, - const char* e2, - const char* e3, - const char* e4, - Pred pred, - const T1& v1, - const T2& v2, - const T3& v3, - const T4& v4) { - if (pred(v1, v2, v3, v4)) return AssertionSuccess(); - - return AssertionFailure() << pred_text << "(" - << e1 << ", " - << e2 << ", " - << e3 << ", " - << e4 << ") evaluates to false, where" - << "\n" << e1 << " evaluates to " << v1 - << "\n" << e2 << " evaluates to " << v2 - << "\n" << e3 << " evaluates to " << v3 - << "\n" << e4 << " evaluates to " << v4; -} - -// Internal macro for implementing {EXPECT|ASSERT}_PRED_FORMAT4. -// Don't use this in your code. -#define GTEST_PRED_FORMAT4_(pred_format, v1, v2, v3, v4, on_failure)\ - GTEST_ASSERT_(pred_format(#v1, #v2, #v3, #v4, v1, v2, v3, v4), \ - on_failure) - -// Internal macro for implementing {EXPECT|ASSERT}_PRED4. Don't use -// this in your code. -#define GTEST_PRED4_(pred, v1, v2, v3, v4, on_failure)\ - GTEST_ASSERT_(::testing::AssertPred4Helper(#pred, \ - #v1, \ - #v2, \ - #v3, \ - #v4, \ - pred, \ - v1, \ - v2, \ - v3, \ - v4), on_failure) - -// 4-ary predicate assertion macros. -#define EXPECT_PRED_FORMAT4(pred_format, v1, v2, v3, v4) \ - GTEST_PRED_FORMAT4_(pred_format, v1, v2, v3, v4, GTEST_NONFATAL_FAILURE_) -#define EXPECT_PRED4(pred, v1, v2, v3, v4) \ - GTEST_PRED4_(pred, v1, v2, v3, v4, GTEST_NONFATAL_FAILURE_) -#define ASSERT_PRED_FORMAT4(pred_format, v1, v2, v3, v4) \ - GTEST_PRED_FORMAT4_(pred_format, v1, v2, v3, v4, GTEST_FATAL_FAILURE_) -#define ASSERT_PRED4(pred, v1, v2, v3, v4) \ - GTEST_PRED4_(pred, v1, v2, v3, v4, GTEST_FATAL_FAILURE_) - - - -// Helper function for implementing {EXPECT|ASSERT}_PRED5. Don't use -// this in your code. -template -AssertionResult AssertPred5Helper(const char* pred_text, - const char* e1, - const char* e2, - const char* e3, - const char* e4, - const char* e5, - Pred pred, - const T1& v1, - const T2& v2, - const T3& v3, - const T4& v4, - const T5& v5) { - if (pred(v1, v2, v3, v4, v5)) return AssertionSuccess(); - - return AssertionFailure() << pred_text << "(" - << e1 << ", " - << e2 << ", " - << e3 << ", " - << e4 << ", " - << e5 << ") evaluates to false, where" - << "\n" << e1 << " evaluates to " << v1 - << "\n" << e2 << " evaluates to " << v2 - << "\n" << e3 << " evaluates to " << v3 - << "\n" << e4 << " evaluates to " << v4 - << "\n" << e5 << " evaluates to " << v5; -} - -// Internal macro for implementing {EXPECT|ASSERT}_PRED_FORMAT5. -// Don't use this in your code. -#define GTEST_PRED_FORMAT5_(pred_format, v1, v2, v3, v4, v5, on_failure)\ - GTEST_ASSERT_(pred_format(#v1, #v2, #v3, #v4, #v5, v1, v2, v3, v4, v5), \ - on_failure) - -// Internal macro for implementing {EXPECT|ASSERT}_PRED5. Don't use -// this in your code. -#define GTEST_PRED5_(pred, v1, v2, v3, v4, v5, on_failure)\ - GTEST_ASSERT_(::testing::AssertPred5Helper(#pred, \ - #v1, \ - #v2, \ - #v3, \ - #v4, \ - #v5, \ - pred, \ - v1, \ - v2, \ - v3, \ - v4, \ - v5), on_failure) - -// 5-ary predicate assertion macros. -#define EXPECT_PRED_FORMAT5(pred_format, v1, v2, v3, v4, v5) \ - GTEST_PRED_FORMAT5_(pred_format, v1, v2, v3, v4, v5, GTEST_NONFATAL_FAILURE_) -#define EXPECT_PRED5(pred, v1, v2, v3, v4, v5) \ - GTEST_PRED5_(pred, v1, v2, v3, v4, v5, GTEST_NONFATAL_FAILURE_) -#define ASSERT_PRED_FORMAT5(pred_format, v1, v2, v3, v4, v5) \ - GTEST_PRED_FORMAT5_(pred_format, v1, v2, v3, v4, v5, GTEST_FATAL_FAILURE_) -#define ASSERT_PRED5(pred, v1, v2, v3, v4, v5) \ - GTEST_PRED5_(pred, v1, v2, v3, v4, v5, GTEST_FATAL_FAILURE_) - - - -#endif // GTEST_INCLUDE_GTEST_GTEST_PRED_IMPL_H_ - -// Macros for testing equalities and inequalities. -// -// * {ASSERT|EXPECT}_EQ(expected, actual): Tests that expected == actual -// * {ASSERT|EXPECT}_NE(v1, v2): Tests that v1 != v2 -// * {ASSERT|EXPECT}_LT(v1, v2): Tests that v1 < v2 -// * {ASSERT|EXPECT}_LE(v1, v2): Tests that v1 <= v2 -// * {ASSERT|EXPECT}_GT(v1, v2): Tests that v1 > v2 -// * {ASSERT|EXPECT}_GE(v1, v2): Tests that v1 >= v2 -// -// When they are not, Google Test prints both the tested expressions and -// their actual values. The values must be compatible built-in types, -// or you will get a compiler error. By "compatible" we mean that the -// values can be compared by the respective operator. -// -// Note: -// -// 1. It is possible to make a user-defined type work with -// {ASSERT|EXPECT}_??(), but that requires overloading the -// comparison operators and is thus discouraged by the Google C++ -// Usage Guide. Therefore, you are advised to use the -// {ASSERT|EXPECT}_TRUE() macro to assert that two objects are -// equal. -// -// 2. The {ASSERT|EXPECT}_??() macros do pointer comparisons on -// pointers (in particular, C strings). Therefore, if you use it -// with two C strings, you are testing how their locations in memory -// are related, not how their content is related. To compare two C -// strings by content, use {ASSERT|EXPECT}_STR*(). -// -// 3. {ASSERT|EXPECT}_EQ(expected, actual) is preferred to -// {ASSERT|EXPECT}_TRUE(expected == actual), as the former tells you -// what the actual value is when it fails, and similarly for the -// other comparisons. -// -// 4. Do not depend on the order in which {ASSERT|EXPECT}_??() -// evaluate their arguments, which is undefined. -// -// 5. These macros evaluate their arguments exactly once. -// -// Examples: -// -// EXPECT_NE(5, Foo()); -// EXPECT_EQ(NULL, a_pointer); -// ASSERT_LT(i, array_size); -// ASSERT_GT(records.size(), 0) << "There is no record left."; - -#define EXPECT_EQ(expected, actual) \ - EXPECT_PRED_FORMAT2(::testing::internal:: \ - EqHelper::Compare, \ - expected, actual) -#define EXPECT_NE(expected, actual) \ - EXPECT_PRED_FORMAT2(::testing::internal::CmpHelperNE, expected, actual) -#define EXPECT_LE(val1, val2) \ - EXPECT_PRED_FORMAT2(::testing::internal::CmpHelperLE, val1, val2) -#define EXPECT_LT(val1, val2) \ - EXPECT_PRED_FORMAT2(::testing::internal::CmpHelperLT, val1, val2) -#define EXPECT_GE(val1, val2) \ - EXPECT_PRED_FORMAT2(::testing::internal::CmpHelperGE, val1, val2) -#define EXPECT_GT(val1, val2) \ - EXPECT_PRED_FORMAT2(::testing::internal::CmpHelperGT, val1, val2) - -#define GTEST_ASSERT_EQ(expected, actual) \ - ASSERT_PRED_FORMAT2(::testing::internal:: \ - EqHelper::Compare, \ - expected, actual) -#define GTEST_ASSERT_NE(val1, val2) \ - ASSERT_PRED_FORMAT2(::testing::internal::CmpHelperNE, val1, val2) -#define GTEST_ASSERT_LE(val1, val2) \ - ASSERT_PRED_FORMAT2(::testing::internal::CmpHelperLE, val1, val2) -#define GTEST_ASSERT_LT(val1, val2) \ - ASSERT_PRED_FORMAT2(::testing::internal::CmpHelperLT, val1, val2) -#define GTEST_ASSERT_GE(val1, val2) \ - ASSERT_PRED_FORMAT2(::testing::internal::CmpHelperGE, val1, val2) -#define GTEST_ASSERT_GT(val1, val2) \ - ASSERT_PRED_FORMAT2(::testing::internal::CmpHelperGT, val1, val2) - -// Define macro GTEST_DONT_DEFINE_ASSERT_XY to 1 to omit the definition of -// ASSERT_XY(), which clashes with some users' own code. - -#if !GTEST_DONT_DEFINE_ASSERT_EQ -# define ASSERT_EQ(val1, val2) GTEST_ASSERT_EQ(val1, val2) -#endif - -#if !GTEST_DONT_DEFINE_ASSERT_NE -# define ASSERT_NE(val1, val2) GTEST_ASSERT_NE(val1, val2) -#endif - -#if !GTEST_DONT_DEFINE_ASSERT_LE -# define ASSERT_LE(val1, val2) GTEST_ASSERT_LE(val1, val2) -#endif - -#if !GTEST_DONT_DEFINE_ASSERT_LT -# define ASSERT_LT(val1, val2) GTEST_ASSERT_LT(val1, val2) -#endif - -#if !GTEST_DONT_DEFINE_ASSERT_GE -# define ASSERT_GE(val1, val2) GTEST_ASSERT_GE(val1, val2) -#endif - -#if !GTEST_DONT_DEFINE_ASSERT_GT -# define ASSERT_GT(val1, val2) GTEST_ASSERT_GT(val1, val2) -#endif - -// C-string Comparisons. All tests treat NULL and any non-NULL string -// as different. Two NULLs are equal. -// -// * {ASSERT|EXPECT}_STREQ(s1, s2): Tests that s1 == s2 -// * {ASSERT|EXPECT}_STRNE(s1, s2): Tests that s1 != s2 -// * {ASSERT|EXPECT}_STRCASEEQ(s1, s2): Tests that s1 == s2, ignoring case -// * {ASSERT|EXPECT}_STRCASENE(s1, s2): Tests that s1 != s2, ignoring case -// -// For wide or narrow string objects, you can use the -// {ASSERT|EXPECT}_??() macros. -// -// Don't depend on the order in which the arguments are evaluated, -// which is undefined. -// -// These macros evaluate their arguments exactly once. - -#define EXPECT_STREQ(expected, actual) \ - EXPECT_PRED_FORMAT2(::testing::internal::CmpHelperSTREQ, expected, actual) -#define EXPECT_STRNE(s1, s2) \ - EXPECT_PRED_FORMAT2(::testing::internal::CmpHelperSTRNE, s1, s2) -#define EXPECT_STRCASEEQ(expected, actual) \ - EXPECT_PRED_FORMAT2(::testing::internal::CmpHelperSTRCASEEQ, expected, actual) -#define EXPECT_STRCASENE(s1, s2)\ - EXPECT_PRED_FORMAT2(::testing::internal::CmpHelperSTRCASENE, s1, s2) - -#define ASSERT_STREQ(expected, actual) \ - ASSERT_PRED_FORMAT2(::testing::internal::CmpHelperSTREQ, expected, actual) -#define ASSERT_STRNE(s1, s2) \ - ASSERT_PRED_FORMAT2(::testing::internal::CmpHelperSTRNE, s1, s2) -#define ASSERT_STRCASEEQ(expected, actual) \ - ASSERT_PRED_FORMAT2(::testing::internal::CmpHelperSTRCASEEQ, expected, actual) -#define ASSERT_STRCASENE(s1, s2)\ - ASSERT_PRED_FORMAT2(::testing::internal::CmpHelperSTRCASENE, s1, s2) - -// Macros for comparing floating-point numbers. -// -// * {ASSERT|EXPECT}_FLOAT_EQ(expected, actual): -// Tests that two float values are almost equal. -// * {ASSERT|EXPECT}_DOUBLE_EQ(expected, actual): -// Tests that two double values are almost equal. -// * {ASSERT|EXPECT}_NEAR(v1, v2, abs_error): -// Tests that v1 and v2 are within the given distance to each other. -// -// Google Test uses ULP-based comparison to automatically pick a default -// error bound that is appropriate for the operands. See the -// FloatingPoint template class in gtest-internal.h if you are -// interested in the implementation details. - -#define EXPECT_FLOAT_EQ(expected, actual)\ - EXPECT_PRED_FORMAT2(::testing::internal::CmpHelperFloatingPointEQ, \ - expected, actual) - -#define EXPECT_DOUBLE_EQ(expected, actual)\ - EXPECT_PRED_FORMAT2(::testing::internal::CmpHelperFloatingPointEQ, \ - expected, actual) - -#define ASSERT_FLOAT_EQ(expected, actual)\ - ASSERT_PRED_FORMAT2(::testing::internal::CmpHelperFloatingPointEQ, \ - expected, actual) - -#define ASSERT_DOUBLE_EQ(expected, actual)\ - ASSERT_PRED_FORMAT2(::testing::internal::CmpHelperFloatingPointEQ, \ - expected, actual) - -#define EXPECT_NEAR(val1, val2, abs_error)\ - EXPECT_PRED_FORMAT3(::testing::internal::DoubleNearPredFormat, \ - val1, val2, abs_error) - -#define ASSERT_NEAR(val1, val2, abs_error)\ - ASSERT_PRED_FORMAT3(::testing::internal::DoubleNearPredFormat, \ - val1, val2, abs_error) - -// These predicate format functions work on floating-point values, and -// can be used in {ASSERT|EXPECT}_PRED_FORMAT2*(), e.g. -// -// EXPECT_PRED_FORMAT2(testing::DoubleLE, Foo(), 5.0); - -// Asserts that val1 is less than, or almost equal to, val2. Fails -// otherwise. In particular, it fails if either val1 or val2 is NaN. -GTEST_API_ AssertionResult FloatLE(const char* expr1, const char* expr2, - float val1, float val2); -GTEST_API_ AssertionResult DoubleLE(const char* expr1, const char* expr2, - double val1, double val2); - - -#if GTEST_OS_WINDOWS - -// Macros that test for HRESULT failure and success, these are only useful -// on Windows, and rely on Windows SDK macros and APIs to compile. -// -// * {ASSERT|EXPECT}_HRESULT_{SUCCEEDED|FAILED}(expr) -// -// When expr unexpectedly fails or succeeds, Google Test prints the -// expected result and the actual result with both a human-readable -// string representation of the error, if available, as well as the -// hex result code. -# define EXPECT_HRESULT_SUCCEEDED(expr) \ - EXPECT_PRED_FORMAT1(::testing::internal::IsHRESULTSuccess, (expr)) - -# define ASSERT_HRESULT_SUCCEEDED(expr) \ - ASSERT_PRED_FORMAT1(::testing::internal::IsHRESULTSuccess, (expr)) - -# define EXPECT_HRESULT_FAILED(expr) \ - EXPECT_PRED_FORMAT1(::testing::internal::IsHRESULTFailure, (expr)) - -# define ASSERT_HRESULT_FAILED(expr) \ - ASSERT_PRED_FORMAT1(::testing::internal::IsHRESULTFailure, (expr)) - -#endif // GTEST_OS_WINDOWS - -// Macros that execute statement and check that it doesn't generate new fatal -// failures in the current thread. -// -// * {ASSERT|EXPECT}_NO_FATAL_FAILURE(statement); -// -// Examples: -// -// EXPECT_NO_FATAL_FAILURE(Process()); -// ASSERT_NO_FATAL_FAILURE(Process()) << "Process() failed"; -// -#define ASSERT_NO_FATAL_FAILURE(statement) \ - GTEST_TEST_NO_FATAL_FAILURE_(statement, GTEST_FATAL_FAILURE_) -#define EXPECT_NO_FATAL_FAILURE(statement) \ - GTEST_TEST_NO_FATAL_FAILURE_(statement, GTEST_NONFATAL_FAILURE_) - -// Causes a trace (including the source file path, the current line -// number, and the given message) to be included in every test failure -// message generated by code in the current scope. The effect is -// undone when the control leaves the current scope. -// -// The message argument can be anything streamable to std::ostream. -// -// In the implementation, we include the current line number as part -// of the dummy variable name, thus allowing multiple SCOPED_TRACE()s -// to appear in the same block - as long as they are on different -// lines. -#define SCOPED_TRACE(message) \ - ::testing::internal::ScopedTrace GTEST_CONCAT_TOKEN_(gtest_trace_, __LINE__)(\ - __FILE__, __LINE__, ::testing::Message() << (message)) - -// Compile-time assertion for type equality. -// StaticAssertTypeEq() compiles iff type1 and type2 are -// the same type. The value it returns is not interesting. -// -// Instead of making StaticAssertTypeEq a class template, we make it a -// function template that invokes a helper class template. This -// prevents a user from misusing StaticAssertTypeEq by -// defining objects of that type. -// -// CAVEAT: -// -// When used inside a method of a class template, -// StaticAssertTypeEq() is effective ONLY IF the method is -// instantiated. For example, given: -// -// template class Foo { -// public: -// void Bar() { testing::StaticAssertTypeEq(); } -// }; -// -// the code: -// -// void Test1() { Foo foo; } -// -// will NOT generate a compiler error, as Foo::Bar() is never -// actually instantiated. Instead, you need: -// -// void Test2() { Foo foo; foo.Bar(); } -// -// to cause a compiler error. -template -bool StaticAssertTypeEq() { - (void)internal::StaticAssertTypeEqHelper(); - return true; -} - -// Defines a test. -// -// The first parameter is the name of the test case, and the second -// parameter is the name of the test within the test case. -// -// The convention is to end the test case name with "Test". For -// example, a test case for the Foo class can be named FooTest. -// -// The user should put his test code between braces after using this -// macro. Example: -// -// TEST(FooTest, InitializesCorrectly) { -// Foo foo; -// EXPECT_TRUE(foo.StatusIsOK()); -// } - -// Note that we call GetTestTypeId() instead of GetTypeId< -// ::testing::Test>() here to get the type ID of testing::Test. This -// is to work around a suspected linker bug when using Google Test as -// a framework on Mac OS X. The bug causes GetTypeId< -// ::testing::Test>() to return different values depending on whether -// the call is from the Google Test framework itself or from user test -// code. GetTestTypeId() is guaranteed to always return the same -// value, as it always calls GetTypeId<>() from the Google Test -// framework. -#define GTEST_TEST(test_case_name, test_name)\ - GTEST_TEST_(test_case_name, test_name, \ - ::testing::Test, ::testing::internal::GetTestTypeId()) - -// Define this macro to 1 to omit the definition of TEST(), which -// is a generic name and clashes with some other libraries. -#if !GTEST_DONT_DEFINE_TEST -# define TEST(test_case_name, test_name) GTEST_TEST(test_case_name, test_name) -#endif - -// Defines a test that uses a test fixture. -// -// The first parameter is the name of the test fixture class, which -// also doubles as the test case name. The second parameter is the -// name of the test within the test case. -// -// A test fixture class must be declared earlier. The user should put -// his test code between braces after using this macro. Example: -// -// class FooTest : public testing::Test { -// protected: -// virtual void SetUp() { b_.AddElement(3); } -// -// Foo a_; -// Foo b_; -// }; -// -// TEST_F(FooTest, InitializesCorrectly) { -// EXPECT_TRUE(a_.StatusIsOK()); -// } -// -// TEST_F(FooTest, ReturnsElementCountCorrectly) { -// EXPECT_EQ(0, a_.size()); -// EXPECT_EQ(1, b_.size()); -// } - -#define TEST_F(test_fixture, test_name)\ - GTEST_TEST_(test_fixture, test_name, test_fixture, \ - ::testing::internal::GetTypeId()) - -} // namespace testing - -// Use this function in main() to run all tests. It returns 0 if all -// tests are successful, or 1 otherwise. -// -// RUN_ALL_TESTS() should be invoked after the command line has been -// parsed by InitGoogleTest(). -// -// This function was formerly a macro; thus, it is in the global -// namespace and has an all-caps name. -int RUN_ALL_TESTS() GTEST_MUST_USE_RESULT_; - -inline int RUN_ALL_TESTS() { - return ::testing::UnitTest::GetInstance()->Run(); -} - -#endif // GTEST_INCLUDE_GTEST_GTEST_H_ diff --git a/lib/test/gtest/src/gtest-all.cc b/lib/test/gtest/src/gtest-all.cc deleted file mode 100644 index a9a03b2e3b4..00000000000 --- a/lib/test/gtest/src/gtest-all.cc +++ /dev/null @@ -1,9592 +0,0 @@ -// Copyright 2008, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: mheule@google.com (Markus Heule) -// -// Google C++ Testing Framework (Google Test) -// -// Sometimes it's desirable to build Google Test by compiling a single file. -// This file serves this purpose. - -// This line ensures that gtest.h can be compiled on its own, even -// when it's fused. -#include "gtest/gtest.h" - -// The following lines pull in the real gtest *.cc files. -// Copyright 2005, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: wan@google.com (Zhanyong Wan) -// -// The Google C++ Testing Framework (Google Test) - -// Copyright 2007, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: wan@google.com (Zhanyong Wan) -// -// Utilities for testing Google Test itself and code that uses Google Test -// (e.g. frameworks built on top of Google Test). - -#ifndef GTEST_INCLUDE_GTEST_GTEST_SPI_H_ -#define GTEST_INCLUDE_GTEST_GTEST_SPI_H_ - - -namespace testing { - -// This helper class can be used to mock out Google Test failure reporting -// so that we can test Google Test or code that builds on Google Test. -// -// An object of this class appends a TestPartResult object to the -// TestPartResultArray object given in the constructor whenever a Google Test -// failure is reported. It can either intercept only failures that are -// generated in the same thread that created this object or it can intercept -// all generated failures. The scope of this mock object can be controlled with -// the second argument to the two arguments constructor. -class GTEST_API_ ScopedFakeTestPartResultReporter - : public TestPartResultReporterInterface { - public: - // The two possible mocking modes of this object. - enum InterceptMode { - INTERCEPT_ONLY_CURRENT_THREAD, // Intercepts only thread local failures. - INTERCEPT_ALL_THREADS // Intercepts all failures. - }; - - // The c'tor sets this object as the test part result reporter used - // by Google Test. The 'result' parameter specifies where to report the - // results. This reporter will only catch failures generated in the current - // thread. DEPRECATED - explicit ScopedFakeTestPartResultReporter(TestPartResultArray* result); - - // Same as above, but you can choose the interception scope of this object. - ScopedFakeTestPartResultReporter(InterceptMode intercept_mode, - TestPartResultArray* result); - - // The d'tor restores the previous test part result reporter. - virtual ~ScopedFakeTestPartResultReporter(); - - // Appends the TestPartResult object to the TestPartResultArray - // received in the constructor. - // - // This method is from the TestPartResultReporterInterface - // interface. - virtual void ReportTestPartResult(const TestPartResult& result); - private: - void Init(); - - const InterceptMode intercept_mode_; - TestPartResultReporterInterface* old_reporter_; - TestPartResultArray* const result_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(ScopedFakeTestPartResultReporter); -}; - -namespace internal { - -// A helper class for implementing EXPECT_FATAL_FAILURE() and -// EXPECT_NONFATAL_FAILURE(). Its destructor verifies that the given -// TestPartResultArray contains exactly one failure that has the given -// type and contains the given substring. If that's not the case, a -// non-fatal failure will be generated. -class GTEST_API_ SingleFailureChecker { - public: - // The constructor remembers the arguments. - SingleFailureChecker(const TestPartResultArray* results, - TestPartResult::Type type, - const string& substr); - ~SingleFailureChecker(); - private: - const TestPartResultArray* const results_; - const TestPartResult::Type type_; - const string substr_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(SingleFailureChecker); -}; - -} // namespace internal - -} // namespace testing - -// A set of macros for testing Google Test assertions or code that's expected -// to generate Google Test fatal failures. It verifies that the given -// statement will cause exactly one fatal Google Test failure with 'substr' -// being part of the failure message. -// -// There are two different versions of this macro. EXPECT_FATAL_FAILURE only -// affects and considers failures generated in the current thread and -// EXPECT_FATAL_FAILURE_ON_ALL_THREADS does the same but for all threads. -// -// The verification of the assertion is done correctly even when the statement -// throws an exception or aborts the current function. -// -// Known restrictions: -// - 'statement' cannot reference local non-static variables or -// non-static members of the current object. -// - 'statement' cannot return a value. -// - You cannot stream a failure message to this macro. -// -// Note that even though the implementations of the following two -// macros are much alike, we cannot refactor them to use a common -// helper macro, due to some peculiarity in how the preprocessor -// works. The AcceptsMacroThatExpandsToUnprotectedComma test in -// gtest_unittest.cc will fail to compile if we do that. -#define EXPECT_FATAL_FAILURE(statement, substr) \ - do { \ - class GTestExpectFatalFailureHelper {\ - public:\ - static void Execute() { statement; }\ - };\ - ::testing::TestPartResultArray gtest_failures;\ - ::testing::internal::SingleFailureChecker gtest_checker(\ - >est_failures, ::testing::TestPartResult::kFatalFailure, (substr));\ - {\ - ::testing::ScopedFakeTestPartResultReporter gtest_reporter(\ - ::testing::ScopedFakeTestPartResultReporter:: \ - INTERCEPT_ONLY_CURRENT_THREAD, >est_failures);\ - GTestExpectFatalFailureHelper::Execute();\ - }\ - } while (::testing::internal::AlwaysFalse()) - -#define EXPECT_FATAL_FAILURE_ON_ALL_THREADS(statement, substr) \ - do { \ - class GTestExpectFatalFailureHelper {\ - public:\ - static void Execute() { statement; }\ - };\ - ::testing::TestPartResultArray gtest_failures;\ - ::testing::internal::SingleFailureChecker gtest_checker(\ - >est_failures, ::testing::TestPartResult::kFatalFailure, (substr));\ - {\ - ::testing::ScopedFakeTestPartResultReporter gtest_reporter(\ - ::testing::ScopedFakeTestPartResultReporter:: \ - INTERCEPT_ALL_THREADS, >est_failures);\ - GTestExpectFatalFailureHelper::Execute();\ - }\ - } while (::testing::internal::AlwaysFalse()) - -// A macro for testing Google Test assertions or code that's expected to -// generate Google Test non-fatal failures. It asserts that the given -// statement will cause exactly one non-fatal Google Test failure with 'substr' -// being part of the failure message. -// -// There are two different versions of this macro. EXPECT_NONFATAL_FAILURE only -// affects and considers failures generated in the current thread and -// EXPECT_NONFATAL_FAILURE_ON_ALL_THREADS does the same but for all threads. -// -// 'statement' is allowed to reference local variables and members of -// the current object. -// -// The verification of the assertion is done correctly even when the statement -// throws an exception or aborts the current function. -// -// Known restrictions: -// - You cannot stream a failure message to this macro. -// -// Note that even though the implementations of the following two -// macros are much alike, we cannot refactor them to use a common -// helper macro, due to some peculiarity in how the preprocessor -// works. If we do that, the code won't compile when the user gives -// EXPECT_NONFATAL_FAILURE() a statement that contains a macro that -// expands to code containing an unprotected comma. The -// AcceptsMacroThatExpandsToUnprotectedComma test in gtest_unittest.cc -// catches that. -// -// For the same reason, we have to write -// if (::testing::internal::AlwaysTrue()) { statement; } -// instead of -// GTEST_SUPPRESS_UNREACHABLE_CODE_WARNING_BELOW_(statement) -// to avoid an MSVC warning on unreachable code. -#define EXPECT_NONFATAL_FAILURE(statement, substr) \ - do {\ - ::testing::TestPartResultArray gtest_failures;\ - ::testing::internal::SingleFailureChecker gtest_checker(\ - >est_failures, ::testing::TestPartResult::kNonFatalFailure, \ - (substr));\ - {\ - ::testing::ScopedFakeTestPartResultReporter gtest_reporter(\ - ::testing::ScopedFakeTestPartResultReporter:: \ - INTERCEPT_ONLY_CURRENT_THREAD, >est_failures);\ - if (::testing::internal::AlwaysTrue()) { statement; }\ - }\ - } while (::testing::internal::AlwaysFalse()) - -#define EXPECT_NONFATAL_FAILURE_ON_ALL_THREADS(statement, substr) \ - do {\ - ::testing::TestPartResultArray gtest_failures;\ - ::testing::internal::SingleFailureChecker gtest_checker(\ - >est_failures, ::testing::TestPartResult::kNonFatalFailure, \ - (substr));\ - {\ - ::testing::ScopedFakeTestPartResultReporter gtest_reporter(\ - ::testing::ScopedFakeTestPartResultReporter::INTERCEPT_ALL_THREADS, \ - >est_failures);\ - if (::testing::internal::AlwaysTrue()) { statement; }\ - }\ - } while (::testing::internal::AlwaysFalse()) - -#endif // GTEST_INCLUDE_GTEST_GTEST_SPI_H_ - -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include // NOLINT -#include -#include - -#if GTEST_OS_LINUX - -// TODO(kenton@google.com): Use autoconf to detect availability of -// gettimeofday(). -# define GTEST_HAS_GETTIMEOFDAY_ 1 - -# include // NOLINT -# include // NOLINT -# include // NOLINT -// Declares vsnprintf(). This header is not available on Windows. -# include // NOLINT -# include // NOLINT -# include // NOLINT -# include // NOLINT -# include - -#elif GTEST_OS_SYMBIAN -# define GTEST_HAS_GETTIMEOFDAY_ 1 -# include // NOLINT - -#elif GTEST_OS_ZOS -# define GTEST_HAS_GETTIMEOFDAY_ 1 -# include // NOLINT - -// On z/OS we additionally need strings.h for strcasecmp. -# include // NOLINT - -#elif GTEST_OS_WINDOWS_MOBILE // We are on Windows CE. - -# include // NOLINT - -#elif GTEST_OS_WINDOWS // We are on Windows proper. - -# include // NOLINT -# include // NOLINT -# include // NOLINT -# include // NOLINT - -# if GTEST_OS_WINDOWS_MINGW -// MinGW has gettimeofday() but not _ftime64(). -// TODO(kenton@google.com): Use autoconf to detect availability of -// gettimeofday(). -// TODO(kenton@google.com): There are other ways to get the time on -// Windows, like GetTickCount() or GetSystemTimeAsFileTime(). MinGW -// supports these. consider using them instead. -# define GTEST_HAS_GETTIMEOFDAY_ 1 -# include // NOLINT -# endif // GTEST_OS_WINDOWS_MINGW - -// cpplint thinks that the header is already included, so we want to -// silence it. -# include // NOLINT - -#else - -// Assume other platforms have gettimeofday(). -// TODO(kenton@google.com): Use autoconf to detect availability of -// gettimeofday(). -# define GTEST_HAS_GETTIMEOFDAY_ 1 - -// cpplint thinks that the header is already included, so we want to -// silence it. -# include // NOLINT -# include // NOLINT - -#endif // GTEST_OS_LINUX - -#if GTEST_HAS_EXCEPTIONS -# include -#endif - -#if GTEST_CAN_STREAM_RESULTS_ -# include // NOLINT -# include // NOLINT -#endif - -// Indicates that this translation unit is part of Google Test's -// implementation. It must come before gtest-internal-inl.h is -// included, or there will be a compiler error. This trick is to -// prevent a user from accidentally including gtest-internal-inl.h in -// his code. -#define GTEST_IMPLEMENTATION_ 1 -// Copyright 2005, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. - -// Utility functions and classes used by the Google C++ testing framework. -// -// Author: wan@google.com (Zhanyong Wan) -// -// This file contains purely Google Test's internal implementation. Please -// DO NOT #INCLUDE IT IN A USER PROGRAM. - -#ifndef GTEST_SRC_GTEST_INTERNAL_INL_H_ -#define GTEST_SRC_GTEST_INTERNAL_INL_H_ - -// GTEST_IMPLEMENTATION_ is defined to 1 iff the current translation unit is -// part of Google Test's implementation; otherwise it's undefined. -#if !GTEST_IMPLEMENTATION_ -// A user is trying to include this from his code - just say no. -# error "gtest-internal-inl.h is part of Google Test's internal implementation." -# error "It must not be included except by Google Test itself." -#endif // GTEST_IMPLEMENTATION_ - -#ifndef _WIN32_WCE -# include -#endif // !_WIN32_WCE -#include -#include // For strtoll/_strtoul64/malloc/free. -#include // For memmove. - -#include -#include -#include - - -#if GTEST_CAN_STREAM_RESULTS_ -# include // NOLINT -# include // NOLINT -#endif - -#if GTEST_OS_WINDOWS -# include // NOLINT -#endif // GTEST_OS_WINDOWS - - -namespace testing { - -// Declares the flags. -// -// We don't want the users to modify this flag in the code, but want -// Google Test's own unit tests to be able to access it. Therefore we -// declare it here as opposed to in gtest.h. -GTEST_DECLARE_bool_(death_test_use_fork); - -namespace internal { - -// The value of GetTestTypeId() as seen from within the Google Test -// library. This is solely for testing GetTestTypeId(). -GTEST_API_ extern const TypeId kTestTypeIdInGoogleTest; - -// Names of the flags (needed for parsing Google Test flags). -const char kAlsoRunDisabledTestsFlag[] = "also_run_disabled_tests"; -const char kBreakOnFailureFlag[] = "break_on_failure"; -const char kCatchExceptionsFlag[] = "catch_exceptions"; -const char kColorFlag[] = "color"; -const char kFilterFlag[] = "filter"; -const char kListTestsFlag[] = "list_tests"; -const char kOutputFlag[] = "output"; -const char kPrintTimeFlag[] = "print_time"; -const char kRandomSeedFlag[] = "random_seed"; -const char kRepeatFlag[] = "repeat"; -const char kShuffleFlag[] = "shuffle"; -const char kStackTraceDepthFlag[] = "stack_trace_depth"; -const char kStreamResultToFlag[] = "stream_result_to"; -const char kThrowOnFailureFlag[] = "throw_on_failure"; - -// A valid random seed must be in [1, kMaxRandomSeed]. -const int kMaxRandomSeed = 99999; - -// g_help_flag is true iff the --help flag or an equivalent form is -// specified on the command line. -GTEST_API_ extern bool g_help_flag; - -// Returns the current time in milliseconds. -GTEST_API_ TimeInMillis GetTimeInMillis(); - -// Returns true iff Google Test should use colors in the output. -GTEST_API_ bool ShouldUseColor(bool stdout_is_tty); - -// Formats the given time in milliseconds as seconds. -GTEST_API_ std::string FormatTimeInMillisAsSeconds(TimeInMillis ms); - -// Converts the given time in milliseconds to a date string in the ISO 8601 -// format, without the timezone information. N.B.: due to the use the -// non-reentrant localtime() function, this function is not thread safe. Do -// not use it in any code that can be called from multiple threads. -GTEST_API_ std::string FormatEpochTimeInMillisAsIso8601(TimeInMillis ms); - -// Parses a string for an Int32 flag, in the form of "--flag=value". -// -// On success, stores the value of the flag in *value, and returns -// true. On failure, returns false without changing *value. -GTEST_API_ bool ParseInt32Flag( - const char* str, const char* flag, Int32* value); - -// Returns a random seed in range [1, kMaxRandomSeed] based on the -// given --gtest_random_seed flag value. -inline int GetRandomSeedFromFlag(Int32 random_seed_flag) { - const unsigned int raw_seed = (random_seed_flag == 0) ? - static_cast(GetTimeInMillis()) : - static_cast(random_seed_flag); - - // Normalizes the actual seed to range [1, kMaxRandomSeed] such that - // it's easy to type. - const int normalized_seed = - static_cast((raw_seed - 1U) % - static_cast(kMaxRandomSeed)) + 1; - return normalized_seed; -} - -// Returns the first valid random seed after 'seed'. The behavior is -// undefined if 'seed' is invalid. The seed after kMaxRandomSeed is -// considered to be 1. -inline int GetNextRandomSeed(int seed) { - GTEST_CHECK_(1 <= seed && seed <= kMaxRandomSeed) - << "Invalid random seed " << seed << " - must be in [1, " - << kMaxRandomSeed << "]."; - const int next_seed = seed + 1; - return (next_seed > kMaxRandomSeed) ? 1 : next_seed; -} - -// This class saves the values of all Google Test flags in its c'tor, and -// restores them in its d'tor. -class GTestFlagSaver { - public: - // The c'tor. - GTestFlagSaver() { - also_run_disabled_tests_ = GTEST_FLAG(also_run_disabled_tests); - break_on_failure_ = GTEST_FLAG(break_on_failure); - catch_exceptions_ = GTEST_FLAG(catch_exceptions); - color_ = GTEST_FLAG(color); - death_test_style_ = GTEST_FLAG(death_test_style); - death_test_use_fork_ = GTEST_FLAG(death_test_use_fork); - filter_ = GTEST_FLAG(filter); - internal_run_death_test_ = GTEST_FLAG(internal_run_death_test); - list_tests_ = GTEST_FLAG(list_tests); - output_ = GTEST_FLAG(output); - print_time_ = GTEST_FLAG(print_time); - random_seed_ = GTEST_FLAG(random_seed); - repeat_ = GTEST_FLAG(repeat); - shuffle_ = GTEST_FLAG(shuffle); - stack_trace_depth_ = GTEST_FLAG(stack_trace_depth); - stream_result_to_ = GTEST_FLAG(stream_result_to); - throw_on_failure_ = GTEST_FLAG(throw_on_failure); - } - - // The d'tor is not virtual. DO NOT INHERIT FROM THIS CLASS. - ~GTestFlagSaver() { - GTEST_FLAG(also_run_disabled_tests) = also_run_disabled_tests_; - GTEST_FLAG(break_on_failure) = break_on_failure_; - GTEST_FLAG(catch_exceptions) = catch_exceptions_; - GTEST_FLAG(color) = color_; - GTEST_FLAG(death_test_style) = death_test_style_; - GTEST_FLAG(death_test_use_fork) = death_test_use_fork_; - GTEST_FLAG(filter) = filter_; - GTEST_FLAG(internal_run_death_test) = internal_run_death_test_; - GTEST_FLAG(list_tests) = list_tests_; - GTEST_FLAG(output) = output_; - GTEST_FLAG(print_time) = print_time_; - GTEST_FLAG(random_seed) = random_seed_; - GTEST_FLAG(repeat) = repeat_; - GTEST_FLAG(shuffle) = shuffle_; - GTEST_FLAG(stack_trace_depth) = stack_trace_depth_; - GTEST_FLAG(stream_result_to) = stream_result_to_; - GTEST_FLAG(throw_on_failure) = throw_on_failure_; - } - - private: - // Fields for saving the original values of flags. - bool also_run_disabled_tests_; - bool break_on_failure_; - bool catch_exceptions_; - std::string color_; - std::string death_test_style_; - bool death_test_use_fork_; - std::string filter_; - std::string internal_run_death_test_; - bool list_tests_; - std::string output_; - bool print_time_; - internal::Int32 random_seed_; - internal::Int32 repeat_; - bool shuffle_; - internal::Int32 stack_trace_depth_; - std::string stream_result_to_; - bool throw_on_failure_; -} GTEST_ATTRIBUTE_UNUSED_; - -// Converts a Unicode code point to a narrow string in UTF-8 encoding. -// code_point parameter is of type UInt32 because wchar_t may not be -// wide enough to contain a code point. -// If the code_point is not a valid Unicode code point -// (i.e. outside of Unicode range U+0 to U+10FFFF) it will be converted -// to "(Invalid Unicode 0xXXXXXXXX)". -GTEST_API_ std::string CodePointToUtf8(UInt32 code_point); - -// Converts a wide string to a narrow string in UTF-8 encoding. -// The wide string is assumed to have the following encoding: -// UTF-16 if sizeof(wchar_t) == 2 (on Windows, Cygwin, Symbian OS) -// UTF-32 if sizeof(wchar_t) == 4 (on Linux) -// Parameter str points to a null-terminated wide string. -// Parameter num_chars may additionally limit the number -// of wchar_t characters processed. -1 is used when the entire string -// should be processed. -// If the string contains code points that are not valid Unicode code points -// (i.e. outside of Unicode range U+0 to U+10FFFF) they will be output -// as '(Invalid Unicode 0xXXXXXXXX)'. If the string is in UTF16 encoding -// and contains invalid UTF-16 surrogate pairs, values in those pairs -// will be encoded as individual Unicode characters from Basic Normal Plane. -GTEST_API_ std::string WideStringToUtf8(const wchar_t* str, int num_chars); - -// Reads the GTEST_SHARD_STATUS_FILE environment variable, and creates the file -// if the variable is present. If a file already exists at this location, this -// function will write over it. If the variable is present, but the file cannot -// be created, prints an error and exits. -void WriteToShardStatusFileIfNeeded(); - -// Checks whether sharding is enabled by examining the relevant -// environment variable values. If the variables are present, -// but inconsistent (e.g., shard_index >= total_shards), prints -// an error and exits. If in_subprocess_for_death_test, sharding is -// disabled because it must only be applied to the original test -// process. Otherwise, we could filter out death tests we intended to execute. -GTEST_API_ bool ShouldShard(const char* total_shards_str, - const char* shard_index_str, - bool in_subprocess_for_death_test); - -// Parses the environment variable var as an Int32. If it is unset, -// returns default_val. If it is not an Int32, prints an error and -// and aborts. -GTEST_API_ Int32 Int32FromEnvOrDie(const char* env_var, Int32 default_val); - -// Given the total number of shards, the shard index, and the test id, -// returns true iff the test should be run on this shard. The test id is -// some arbitrary but unique non-negative integer assigned to each test -// method. Assumes that 0 <= shard_index < total_shards. -GTEST_API_ bool ShouldRunTestOnShard( - int total_shards, int shard_index, int test_id); - -// STL container utilities. - -// Returns the number of elements in the given container that satisfy -// the given predicate. -template -inline int CountIf(const Container& c, Predicate predicate) { - // Implemented as an explicit loop since std::count_if() in libCstd on - // Solaris has a non-standard signature. - int count = 0; - for (typename Container::const_iterator it = c.begin(); it != c.end(); ++it) { - if (predicate(*it)) - ++count; - } - return count; -} - -// Applies a function/functor to each element in the container. -template -void ForEach(const Container& c, Functor functor) { - std::for_each(c.begin(), c.end(), functor); -} - -// Returns the i-th element of the vector, or default_value if i is not -// in range [0, v.size()). -template -inline E GetElementOr(const std::vector& v, int i, E default_value) { - return (i < 0 || i >= static_cast(v.size())) ? default_value : v[i]; -} - -// Performs an in-place shuffle of a range of the vector's elements. -// 'begin' and 'end' are element indices as an STL-style range; -// i.e. [begin, end) are shuffled, where 'end' == size() means to -// shuffle to the end of the vector. -template -void ShuffleRange(internal::Random* random, int begin, int end, - std::vector* v) { - const int size = static_cast(v->size()); - GTEST_CHECK_(0 <= begin && begin <= size) - << "Invalid shuffle range start " << begin << ": must be in range [0, " - << size << "]."; - GTEST_CHECK_(begin <= end && end <= size) - << "Invalid shuffle range finish " << end << ": must be in range [" - << begin << ", " << size << "]."; - - // Fisher-Yates shuffle, from - // http://en.wikipedia.org/wiki/Fisher-Yates_shuffle - for (int range_width = end - begin; range_width >= 2; range_width--) { - const int last_in_range = begin + range_width - 1; - const int selected = begin + random->Generate(range_width); - std::swap((*v)[selected], (*v)[last_in_range]); - } -} - -// Performs an in-place shuffle of the vector's elements. -template -inline void Shuffle(internal::Random* random, std::vector* v) { - ShuffleRange(random, 0, static_cast(v->size()), v); -} - -// A function for deleting an object. Handy for being used as a -// functor. -template -static void Delete(T* x) { - delete x; -} - -// A predicate that checks the key of a TestProperty against a known key. -// -// TestPropertyKeyIs is copyable. -class TestPropertyKeyIs { - public: - // Constructor. - // - // TestPropertyKeyIs has NO default constructor. - explicit TestPropertyKeyIs(const std::string& key) : key_(key) {} - - // Returns true iff the test name of test property matches on key_. - bool operator()(const TestProperty& test_property) const { - return test_property.key() == key_; - } - - private: - std::string key_; -}; - -// Class UnitTestOptions. -// -// This class contains functions for processing options the user -// specifies when running the tests. It has only static members. -// -// In most cases, the user can specify an option using either an -// environment variable or a command line flag. E.g. you can set the -// test filter using either GTEST_FILTER or --gtest_filter. If both -// the variable and the flag are present, the latter overrides the -// former. -class GTEST_API_ UnitTestOptions { - public: - // Functions for processing the gtest_output flag. - - // Returns the output format, or "" for normal printed output. - static std::string GetOutputFormat(); - - // Returns the absolute path of the requested output file, or the - // default (test_detail.xml in the original working directory) if - // none was explicitly specified. - static std::string GetAbsolutePathToOutputFile(); - - // Functions for processing the gtest_filter flag. - - // Returns true iff the wildcard pattern matches the string. The - // first ':' or '\0' character in pattern marks the end of it. - // - // This recursive algorithm isn't very efficient, but is clear and - // works well enough for matching test names, which are short. - static bool PatternMatchesString(const char *pattern, const char *str); - - // Returns true iff the user-specified filter matches the test case - // name and the test name. - static bool FilterMatchesTest(const std::string &test_case_name, - const std::string &test_name); - -#if GTEST_OS_WINDOWS - // Function for supporting the gtest_catch_exception flag. - - // Returns EXCEPTION_EXECUTE_HANDLER if Google Test should handle the - // given SEH exception, or EXCEPTION_CONTINUE_SEARCH otherwise. - // This function is useful as an __except condition. - static int GTestShouldProcessSEH(DWORD exception_code); -#endif // GTEST_OS_WINDOWS - - // Returns true if "name" matches the ':' separated list of glob-style - // filters in "filter". - static bool MatchesFilter(const std::string& name, const char* filter); -}; - -// Returns the current application's name, removing directory path if that -// is present. Used by UnitTestOptions::GetOutputFile. -GTEST_API_ FilePath GetCurrentExecutableName(); - -// The role interface for getting the OS stack trace as a string. -class OsStackTraceGetterInterface { - public: - OsStackTraceGetterInterface() {} - virtual ~OsStackTraceGetterInterface() {} - - // Returns the current OS stack trace as an std::string. Parameters: - // - // max_depth - the maximum number of stack frames to be included - // in the trace. - // skip_count - the number of top frames to be skipped; doesn't count - // against max_depth. - virtual string CurrentStackTrace(int max_depth, int skip_count) = 0; - - // UponLeavingGTest() should be called immediately before Google Test calls - // user code. It saves some information about the current stack that - // CurrentStackTrace() will use to find and hide Google Test stack frames. - virtual void UponLeavingGTest() = 0; - - private: - GTEST_DISALLOW_COPY_AND_ASSIGN_(OsStackTraceGetterInterface); -}; - -// A working implementation of the OsStackTraceGetterInterface interface. -class OsStackTraceGetter : public OsStackTraceGetterInterface { - public: - OsStackTraceGetter() : caller_frame_(NULL) {} - - virtual string CurrentStackTrace(int max_depth, int skip_count) - GTEST_LOCK_EXCLUDED_(mutex_); - - virtual void UponLeavingGTest() GTEST_LOCK_EXCLUDED_(mutex_); - - // This string is inserted in place of stack frames that are part of - // Google Test's implementation. - static const char* const kElidedFramesMarker; - - private: - Mutex mutex_; // protects all internal state - - // We save the stack frame below the frame that calls user code. - // We do this because the address of the frame immediately below - // the user code changes between the call to UponLeavingGTest() - // and any calls to CurrentStackTrace() from within the user code. - void* caller_frame_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(OsStackTraceGetter); -}; - -// Information about a Google Test trace point. -struct TraceInfo { - const char* file; - int line; - std::string message; -}; - -// This is the default global test part result reporter used in UnitTestImpl. -// This class should only be used by UnitTestImpl. -class DefaultGlobalTestPartResultReporter - : public TestPartResultReporterInterface { - public: - explicit DefaultGlobalTestPartResultReporter(UnitTestImpl* unit_test); - // Implements the TestPartResultReporterInterface. Reports the test part - // result in the current test. - virtual void ReportTestPartResult(const TestPartResult& result); - - private: - UnitTestImpl* const unit_test_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(DefaultGlobalTestPartResultReporter); -}; - -// This is the default per thread test part result reporter used in -// UnitTestImpl. This class should only be used by UnitTestImpl. -class DefaultPerThreadTestPartResultReporter - : public TestPartResultReporterInterface { - public: - explicit DefaultPerThreadTestPartResultReporter(UnitTestImpl* unit_test); - // Implements the TestPartResultReporterInterface. The implementation just - // delegates to the current global test part result reporter of *unit_test_. - virtual void ReportTestPartResult(const TestPartResult& result); - - private: - UnitTestImpl* const unit_test_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(DefaultPerThreadTestPartResultReporter); -}; - -// The private implementation of the UnitTest class. We don't protect -// the methods under a mutex, as this class is not accessible by a -// user and the UnitTest class that delegates work to this class does -// proper locking. -class GTEST_API_ UnitTestImpl { - public: - explicit UnitTestImpl(UnitTest* parent); - virtual ~UnitTestImpl(); - - // There are two different ways to register your own TestPartResultReporter. - // You can register your own repoter to listen either only for test results - // from the current thread or for results from all threads. - // By default, each per-thread test result repoter just passes a new - // TestPartResult to the global test result reporter, which registers the - // test part result for the currently running test. - - // Returns the global test part result reporter. - TestPartResultReporterInterface* GetGlobalTestPartResultReporter(); - - // Sets the global test part result reporter. - void SetGlobalTestPartResultReporter( - TestPartResultReporterInterface* reporter); - - // Returns the test part result reporter for the current thread. - TestPartResultReporterInterface* GetTestPartResultReporterForCurrentThread(); - - // Sets the test part result reporter for the current thread. - void SetTestPartResultReporterForCurrentThread( - TestPartResultReporterInterface* reporter); - - // Gets the number of successful test cases. - int successful_test_case_count() const; - - // Gets the number of failed test cases. - int failed_test_case_count() const; - - // Gets the number of all test cases. - int total_test_case_count() const; - - // Gets the number of all test cases that contain at least one test - // that should run. - int test_case_to_run_count() const; - - // Gets the number of successful tests. - int successful_test_count() const; - - // Gets the number of failed tests. - int failed_test_count() const; - - // Gets the number of disabled tests that will be reported in the XML report. - int reportable_disabled_test_count() const; - - // Gets the number of disabled tests. - int disabled_test_count() const; - - // Gets the number of tests to be printed in the XML report. - int reportable_test_count() const; - - // Gets the number of all tests. - int total_test_count() const; - - // Gets the number of tests that should run. - int test_to_run_count() const; - - // Gets the time of the test program start, in ms from the start of the - // UNIX epoch. - TimeInMillis start_timestamp() const { return start_timestamp_; } - - // Gets the elapsed time, in milliseconds. - TimeInMillis elapsed_time() const { return elapsed_time_; } - - // Returns true iff the unit test passed (i.e. all test cases passed). - bool Passed() const { return !Failed(); } - - // Returns true iff the unit test failed (i.e. some test case failed - // or something outside of all tests failed). - bool Failed() const { - return failed_test_case_count() > 0 || ad_hoc_test_result()->Failed(); - } - - // Gets the i-th test case among all the test cases. i can range from 0 to - // total_test_case_count() - 1. If i is not in that range, returns NULL. - const TestCase* GetTestCase(int i) const { - const int index = GetElementOr(test_case_indices_, i, -1); - return index < 0 ? NULL : test_cases_[i]; - } - - // Gets the i-th test case among all the test cases. i can range from 0 to - // total_test_case_count() - 1. If i is not in that range, returns NULL. - TestCase* GetMutableTestCase(int i) { - const int index = GetElementOr(test_case_indices_, i, -1); - return index < 0 ? NULL : test_cases_[index]; - } - - // Provides access to the event listener list. - TestEventListeners* listeners() { return &listeners_; } - - // Returns the TestResult for the test that's currently running, or - // the TestResult for the ad hoc test if no test is running. - TestResult* current_test_result(); - - // Returns the TestResult for the ad hoc test. - const TestResult* ad_hoc_test_result() const { return &ad_hoc_test_result_; } - - // Sets the OS stack trace getter. - // - // Does nothing if the input and the current OS stack trace getter - // are the same; otherwise, deletes the old getter and makes the - // input the current getter. - void set_os_stack_trace_getter(OsStackTraceGetterInterface* getter); - - // Returns the current OS stack trace getter if it is not NULL; - // otherwise, creates an OsStackTraceGetter, makes it the current - // getter, and returns it. - OsStackTraceGetterInterface* os_stack_trace_getter(); - - // Returns the current OS stack trace as an std::string. - // - // The maximum number of stack frames to be included is specified by - // the gtest_stack_trace_depth flag. The skip_count parameter - // specifies the number of top frames to be skipped, which doesn't - // count against the number of frames to be included. - // - // For example, if Foo() calls Bar(), which in turn calls - // CurrentOsStackTraceExceptTop(1), Foo() will be included in the - // trace but Bar() and CurrentOsStackTraceExceptTop() won't. - std::string CurrentOsStackTraceExceptTop(int skip_count) GTEST_NO_INLINE_; - - // Finds and returns a TestCase with the given name. If one doesn't - // exist, creates one and returns it. - // - // Arguments: - // - // test_case_name: name of the test case - // type_param: the name of the test's type parameter, or NULL if - // this is not a typed or a type-parameterized test. - // set_up_tc: pointer to the function that sets up the test case - // tear_down_tc: pointer to the function that tears down the test case - TestCase* GetTestCase(const char* test_case_name, - const char* type_param, - Test::SetUpTestCaseFunc set_up_tc, - Test::TearDownTestCaseFunc tear_down_tc); - - // Adds a TestInfo to the unit test. - // - // Arguments: - // - // set_up_tc: pointer to the function that sets up the test case - // tear_down_tc: pointer to the function that tears down the test case - // test_info: the TestInfo object - void AddTestInfo(Test::SetUpTestCaseFunc set_up_tc, - Test::TearDownTestCaseFunc tear_down_tc, - TestInfo* test_info) { - // In order to support thread-safe death tests, we need to - // remember the original working directory when the test program - // was first invoked. We cannot do this in RUN_ALL_TESTS(), as - // the user may have changed the current directory before calling - // RUN_ALL_TESTS(). Therefore we capture the current directory in - // AddTestInfo(), which is called to register a TEST or TEST_F - // before main() is reached. - if (original_working_dir_.IsEmpty()) { - original_working_dir_.Set(FilePath::GetCurrentDir()); - GTEST_CHECK_(!original_working_dir_.IsEmpty()) - << "Failed to get the current working directory."; - } - - GetTestCase(test_info->test_case_name(), - test_info->type_param(), - set_up_tc, - tear_down_tc)->AddTestInfo(test_info); - } - -#if GTEST_HAS_PARAM_TEST - // Returns ParameterizedTestCaseRegistry object used to keep track of - // value-parameterized tests and instantiate and register them. - internal::ParameterizedTestCaseRegistry& parameterized_test_registry() { - return parameterized_test_registry_; - } -#endif // GTEST_HAS_PARAM_TEST - - // Sets the TestCase object for the test that's currently running. - void set_current_test_case(TestCase* a_current_test_case) { - current_test_case_ = a_current_test_case; - } - - // Sets the TestInfo object for the test that's currently running. If - // current_test_info is NULL, the assertion results will be stored in - // ad_hoc_test_result_. - void set_current_test_info(TestInfo* a_current_test_info) { - current_test_info_ = a_current_test_info; - } - - // Registers all parameterized tests defined using TEST_P and - // INSTANTIATE_TEST_CASE_P, creating regular tests for each test/parameter - // combination. This method can be called more then once; it has guards - // protecting from registering the tests more then once. If - // value-parameterized tests are disabled, RegisterParameterizedTests is - // present but does nothing. - void RegisterParameterizedTests(); - - // Runs all tests in this UnitTest object, prints the result, and - // returns true if all tests are successful. If any exception is - // thrown during a test, this test is considered to be failed, but - // the rest of the tests will still be run. - bool RunAllTests(); - - // Clears the results of all tests, except the ad hoc tests. - void ClearNonAdHocTestResult() { - ForEach(test_cases_, TestCase::ClearTestCaseResult); - } - - // Clears the results of ad-hoc test assertions. - void ClearAdHocTestResult() { - ad_hoc_test_result_.Clear(); - } - - // Adds a TestProperty to the current TestResult object when invoked in a - // context of a test or a test case, or to the global property set. If the - // result already contains a property with the same key, the value will be - // updated. - void RecordProperty(const TestProperty& test_property); - - enum ReactionToSharding { - HONOR_SHARDING_PROTOCOL, - IGNORE_SHARDING_PROTOCOL - }; - - // Matches the full name of each test against the user-specified - // filter to decide whether the test should run, then records the - // result in each TestCase and TestInfo object. - // If shard_tests == HONOR_SHARDING_PROTOCOL, further filters tests - // based on sharding variables in the environment. - // Returns the number of tests that should run. - int FilterTests(ReactionToSharding shard_tests); - - // Prints the names of the tests matching the user-specified filter flag. - void ListTestsMatchingFilter(); - - const TestCase* current_test_case() const { return current_test_case_; } - TestInfo* current_test_info() { return current_test_info_; } - const TestInfo* current_test_info() const { return current_test_info_; } - - // Returns the vector of environments that need to be set-up/torn-down - // before/after the tests are run. - std::vector& environments() { return environments_; } - - // Getters for the per-thread Google Test trace stack. - std::vector& gtest_trace_stack() { - return *(gtest_trace_stack_.pointer()); - } - const std::vector& gtest_trace_stack() const { - return gtest_trace_stack_.get(); - } - -#if GTEST_HAS_DEATH_TEST - void InitDeathTestSubprocessControlInfo() { - internal_run_death_test_flag_.reset(ParseInternalRunDeathTestFlag()); - } - // Returns a pointer to the parsed --gtest_internal_run_death_test - // flag, or NULL if that flag was not specified. - // This information is useful only in a death test child process. - // Must not be called before a call to InitGoogleTest. - const InternalRunDeathTestFlag* internal_run_death_test_flag() const { - return internal_run_death_test_flag_.get(); - } - - // Returns a pointer to the current death test factory. - internal::DeathTestFactory* death_test_factory() { - return death_test_factory_.get(); - } - - void SuppressTestEventsIfInSubprocess(); - - friend class ReplaceDeathTestFactory; -#endif // GTEST_HAS_DEATH_TEST - - // Initializes the event listener performing XML output as specified by - // UnitTestOptions. Must not be called before InitGoogleTest. - void ConfigureXmlOutput(); - -#if GTEST_CAN_STREAM_RESULTS_ - // Initializes the event listener for streaming test results to a socket. - // Must not be called before InitGoogleTest. - void ConfigureStreamingOutput(); -#endif - - // Performs initialization dependent upon flag values obtained in - // ParseGoogleTestFlagsOnly. Is called from InitGoogleTest after the call to - // ParseGoogleTestFlagsOnly. In case a user neglects to call InitGoogleTest - // this function is also called from RunAllTests. Since this function can be - // called more than once, it has to be idempotent. - void PostFlagParsingInit(); - - // Gets the random seed used at the start of the current test iteration. - int random_seed() const { return random_seed_; } - - // Gets the random number generator. - internal::Random* random() { return &random_; } - - // Shuffles all test cases, and the tests within each test case, - // making sure that death tests are still run first. - void ShuffleTests(); - - // Restores the test cases and tests to their order before the first shuffle. - void UnshuffleTests(); - - // Returns the value of GTEST_FLAG(catch_exceptions) at the moment - // UnitTest::Run() starts. - bool catch_exceptions() const { return catch_exceptions_; } - - private: - friend class ::testing::UnitTest; - - // Used by UnitTest::Run() to capture the state of - // GTEST_FLAG(catch_exceptions) at the moment it starts. - void set_catch_exceptions(bool value) { catch_exceptions_ = value; } - - // The UnitTest object that owns this implementation object. - UnitTest* const parent_; - - // The working directory when the first TEST() or TEST_F() was - // executed. - internal::FilePath original_working_dir_; - - // The default test part result reporters. - DefaultGlobalTestPartResultReporter default_global_test_part_result_reporter_; - DefaultPerThreadTestPartResultReporter - default_per_thread_test_part_result_reporter_; - - // Points to (but doesn't own) the global test part result reporter. - TestPartResultReporterInterface* global_test_part_result_repoter_; - - // Protects read and write access to global_test_part_result_reporter_. - internal::Mutex global_test_part_result_reporter_mutex_; - - // Points to (but doesn't own) the per-thread test part result reporter. - internal::ThreadLocal - per_thread_test_part_result_reporter_; - - // The vector of environments that need to be set-up/torn-down - // before/after the tests are run. - std::vector environments_; - - // The vector of TestCases in their original order. It owns the - // elements in the vector. - std::vector test_cases_; - - // Provides a level of indirection for the test case list to allow - // easy shuffling and restoring the test case order. The i-th - // element of this vector is the index of the i-th test case in the - // shuffled order. - std::vector test_case_indices_; - -#if GTEST_HAS_PARAM_TEST - // ParameterizedTestRegistry object used to register value-parameterized - // tests. - internal::ParameterizedTestCaseRegistry parameterized_test_registry_; - - // Indicates whether RegisterParameterizedTests() has been called already. - bool parameterized_tests_registered_; -#endif // GTEST_HAS_PARAM_TEST - - // Index of the last death test case registered. Initially -1. - int last_death_test_case_; - - // This points to the TestCase for the currently running test. It - // changes as Google Test goes through one test case after another. - // When no test is running, this is set to NULL and Google Test - // stores assertion results in ad_hoc_test_result_. Initially NULL. - TestCase* current_test_case_; - - // This points to the TestInfo for the currently running test. It - // changes as Google Test goes through one test after another. When - // no test is running, this is set to NULL and Google Test stores - // assertion results in ad_hoc_test_result_. Initially NULL. - TestInfo* current_test_info_; - - // Normally, a user only writes assertions inside a TEST or TEST_F, - // or inside a function called by a TEST or TEST_F. Since Google - // Test keeps track of which test is current running, it can - // associate such an assertion with the test it belongs to. - // - // If an assertion is encountered when no TEST or TEST_F is running, - // Google Test attributes the assertion result to an imaginary "ad hoc" - // test, and records the result in ad_hoc_test_result_. - TestResult ad_hoc_test_result_; - - // The list of event listeners that can be used to track events inside - // Google Test. - TestEventListeners listeners_; - - // The OS stack trace getter. Will be deleted when the UnitTest - // object is destructed. By default, an OsStackTraceGetter is used, - // but the user can set this field to use a custom getter if that is - // desired. - OsStackTraceGetterInterface* os_stack_trace_getter_; - - // True iff PostFlagParsingInit() has been called. - bool post_flag_parse_init_performed_; - - // The random number seed used at the beginning of the test run. - int random_seed_; - - // Our random number generator. - internal::Random random_; - - // The time of the test program start, in ms from the start of the - // UNIX epoch. - TimeInMillis start_timestamp_; - - // How long the test took to run, in milliseconds. - TimeInMillis elapsed_time_; - -#if GTEST_HAS_DEATH_TEST - // The decomposed components of the gtest_internal_run_death_test flag, - // parsed when RUN_ALL_TESTS is called. - internal::scoped_ptr internal_run_death_test_flag_; - internal::scoped_ptr death_test_factory_; -#endif // GTEST_HAS_DEATH_TEST - - // A per-thread stack of traces created by the SCOPED_TRACE() macro. - internal::ThreadLocal > gtest_trace_stack_; - - // The value of GTEST_FLAG(catch_exceptions) at the moment RunAllTests() - // starts. - bool catch_exceptions_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(UnitTestImpl); -}; // class UnitTestImpl - -// Convenience function for accessing the global UnitTest -// implementation object. -inline UnitTestImpl* GetUnitTestImpl() { - return UnitTest::GetInstance()->impl(); -} - -#if GTEST_USES_SIMPLE_RE - -// Internal helper functions for implementing the simple regular -// expression matcher. -GTEST_API_ bool IsInSet(char ch, const char* str); -GTEST_API_ bool IsAsciiDigit(char ch); -GTEST_API_ bool IsAsciiPunct(char ch); -GTEST_API_ bool IsRepeat(char ch); -GTEST_API_ bool IsAsciiWhiteSpace(char ch); -GTEST_API_ bool IsAsciiWordChar(char ch); -GTEST_API_ bool IsValidEscape(char ch); -GTEST_API_ bool AtomMatchesChar(bool escaped, char pattern, char ch); -GTEST_API_ bool ValidateRegex(const char* regex); -GTEST_API_ bool MatchRegexAtHead(const char* regex, const char* str); -GTEST_API_ bool MatchRepetitionAndRegexAtHead( - bool escaped, char ch, char repeat, const char* regex, const char* str); -GTEST_API_ bool MatchRegexAnywhere(const char* regex, const char* str); - -#endif // GTEST_USES_SIMPLE_RE - -// Parses the command line for Google Test flags, without initializing -// other parts of Google Test. -GTEST_API_ void ParseGoogleTestFlagsOnly(int* argc, char** argv); -GTEST_API_ void ParseGoogleTestFlagsOnly(int* argc, wchar_t** argv); - -#if GTEST_HAS_DEATH_TEST - -// Returns the message describing the last system error, regardless of the -// platform. -GTEST_API_ std::string GetLastErrnoDescription(); - -# if GTEST_OS_WINDOWS -// Provides leak-safe Windows kernel handle ownership. -class AutoHandle { - public: - AutoHandle() : handle_(INVALID_HANDLE_VALUE) {} - explicit AutoHandle(HANDLE handle) : handle_(handle) {} - - ~AutoHandle() { Reset(); } - - HANDLE Get() const { return handle_; } - void Reset() { Reset(INVALID_HANDLE_VALUE); } - void Reset(HANDLE handle) { - if (handle != handle_) { - if (handle_ != INVALID_HANDLE_VALUE) - ::CloseHandle(handle_); - handle_ = handle; - } - } - - private: - HANDLE handle_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(AutoHandle); -}; -# endif // GTEST_OS_WINDOWS - -// Attempts to parse a string into a positive integer pointed to by the -// number parameter. Returns true if that is possible. -// GTEST_HAS_DEATH_TEST implies that we have ::std::string, so we can use -// it here. -template -bool ParseNaturalNumber(const ::std::string& str, Integer* number) { - // Fail fast if the given string does not begin with a digit; - // this bypasses strtoXXX's "optional leading whitespace and plus - // or minus sign" semantics, which are undesirable here. - if (str.empty() || !IsDigit(str[0])) { - return false; - } - errno = 0; - - char* end; - // BiggestConvertible is the largest integer type that system-provided - // string-to-number conversion routines can return. - -# if GTEST_OS_WINDOWS && !defined(__GNUC__) - - // MSVC and C++ Builder define __int64 instead of the standard long long. - typedef unsigned __int64 BiggestConvertible; - const BiggestConvertible parsed = _strtoui64(str.c_str(), &end, 10); - -# else - - typedef unsigned long long BiggestConvertible; // NOLINT - const BiggestConvertible parsed = strtoull(str.c_str(), &end, 10); - -# endif // GTEST_OS_WINDOWS && !defined(__GNUC__) - - const bool parse_success = *end == '\0' && errno == 0; - - // TODO(vladl@google.com): Convert this to compile time assertion when it is - // available. - GTEST_CHECK_(sizeof(Integer) <= sizeof(parsed)); - - const Integer result = static_cast(parsed); - if (parse_success && static_cast(result) == parsed) { - *number = result; - return true; - } - return false; -} -#endif // GTEST_HAS_DEATH_TEST - -// TestResult contains some private methods that should be hidden from -// Google Test user but are required for testing. This class allow our tests -// to access them. -// -// This class is supplied only for the purpose of testing Google Test's own -// constructs. Do not use it in user tests, either directly or indirectly. -class TestResultAccessor { - public: - static void RecordProperty(TestResult* test_result, - const std::string& xml_element, - const TestProperty& property) { - test_result->RecordProperty(xml_element, property); - } - - static void ClearTestPartResults(TestResult* test_result) { - test_result->ClearTestPartResults(); - } - - static const std::vector& test_part_results( - const TestResult& test_result) { - return test_result.test_part_results(); - } -}; - -#if GTEST_CAN_STREAM_RESULTS_ - -// Streams test results to the given port on the given host machine. -class StreamingListener : public EmptyTestEventListener { - public: - // Abstract base class for writing strings to a socket. - class AbstractSocketWriter { - public: - virtual ~AbstractSocketWriter() {} - - // Sends a string to the socket. - virtual void Send(const string& message) = 0; - - // Closes the socket. - virtual void CloseConnection() {} - - // Sends a string and a newline to the socket. - void SendLn(const string& message) { - Send(message + "\n"); - } - }; - - // Concrete class for actually writing strings to a socket. - class SocketWriter : public AbstractSocketWriter { - public: - SocketWriter(const string& host, const string& port) - : sockfd_(-1), host_name_(host), port_num_(port) { - MakeConnection(); - } - - virtual ~SocketWriter() { - if (sockfd_ != -1) - CloseConnection(); - } - - // Sends a string to the socket. - virtual void Send(const string& message) { - GTEST_CHECK_(sockfd_ != -1) - << "Send() can be called only when there is a connection."; - - const int len = static_cast(message.length()); - if (write(sockfd_, message.c_str(), len) != len) { - GTEST_LOG_(WARNING) - << "stream_result_to: failed to stream to " - << host_name_ << ":" << port_num_; - } - } - - private: - // Creates a client socket and connects to the server. - void MakeConnection(); - - // Closes the socket. - void CloseConnection() { - GTEST_CHECK_(sockfd_ != -1) - << "CloseConnection() can be called only when there is a connection."; - - close(sockfd_); - sockfd_ = -1; - } - - int sockfd_; // socket file descriptor - const string host_name_; - const string port_num_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(SocketWriter); - }; // class SocketWriter - - // Escapes '=', '&', '%', and '\n' characters in str as "%xx". - static string UrlEncode(const char* str); - - StreamingListener(const string& host, const string& port) - : socket_writer_(new SocketWriter(host, port)) { Start(); } - - explicit StreamingListener(AbstractSocketWriter* socket_writer) - : socket_writer_(socket_writer) { Start(); } - - void OnTestProgramStart(const UnitTest& /* unit_test */) { - SendLn("event=TestProgramStart"); - } - - void OnTestProgramEnd(const UnitTest& unit_test) { - // Note that Google Test current only report elapsed time for each - // test iteration, not for the entire test program. - SendLn("event=TestProgramEnd&passed=" + FormatBool(unit_test.Passed())); - - // Notify the streaming server to stop. - socket_writer_->CloseConnection(); - } - - void OnTestIterationStart(const UnitTest& /* unit_test */, int iteration) { - SendLn("event=TestIterationStart&iteration=" + - StreamableToString(iteration)); - } - - void OnTestIterationEnd(const UnitTest& unit_test, int /* iteration */) { - SendLn("event=TestIterationEnd&passed=" + - FormatBool(unit_test.Passed()) + "&elapsed_time=" + - StreamableToString(unit_test.elapsed_time()) + "ms"); - } - - void OnTestCaseStart(const TestCase& test_case) { - SendLn(std::string("event=TestCaseStart&name=") + test_case.name()); - } - - void OnTestCaseEnd(const TestCase& test_case) { - SendLn("event=TestCaseEnd&passed=" + FormatBool(test_case.Passed()) - + "&elapsed_time=" + StreamableToString(test_case.elapsed_time()) - + "ms"); - } - - void OnTestStart(const TestInfo& test_info) { - SendLn(std::string("event=TestStart&name=") + test_info.name()); - } - - void OnTestEnd(const TestInfo& test_info) { - SendLn("event=TestEnd&passed=" + - FormatBool((test_info.result())->Passed()) + - "&elapsed_time=" + - StreamableToString((test_info.result())->elapsed_time()) + "ms"); - } - - void OnTestPartResult(const TestPartResult& test_part_result) { - const char* file_name = test_part_result.file_name(); - if (file_name == NULL) - file_name = ""; - SendLn("event=TestPartResult&file=" + UrlEncode(file_name) + - "&line=" + StreamableToString(test_part_result.line_number()) + - "&message=" + UrlEncode(test_part_result.message())); - } - - private: - // Sends the given message and a newline to the socket. - void SendLn(const string& message) { socket_writer_->SendLn(message); } - - // Called at the start of streaming to notify the receiver what - // protocol we are using. - void Start() { SendLn("gtest_streaming_protocol_version=1.0"); } - - string FormatBool(bool value) { return value ? "1" : "0"; } - - const scoped_ptr socket_writer_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(StreamingListener); -}; // class StreamingListener - -#endif // GTEST_CAN_STREAM_RESULTS_ - -} // namespace internal -} // namespace testing - -#endif // GTEST_SRC_GTEST_INTERNAL_INL_H_ -#undef GTEST_IMPLEMENTATION_ - -#if GTEST_OS_WINDOWS -# define vsnprintf _vsnprintf -#endif // GTEST_OS_WINDOWS - -namespace testing { - -using internal::CountIf; -using internal::ForEach; -using internal::GetElementOr; -using internal::Shuffle; - -// Constants. - -// A test whose test case name or test name matches this filter is -// disabled and not run. -static const char kDisableTestFilter[] = "DISABLED_*:*/DISABLED_*"; - -// A test case whose name matches this filter is considered a death -// test case and will be run before test cases whose name doesn't -// match this filter. -static const char kDeathTestCaseFilter[] = "*DeathTest:*DeathTest/*"; - -// A test filter that matches everything. -static const char kUniversalFilter[] = "*"; - -// The default output file for XML output. -static const char kDefaultOutputFile[] = "test_detail.xml"; - -// The environment variable name for the test shard index. -static const char kTestShardIndex[] = "GTEST_SHARD_INDEX"; -// The environment variable name for the total number of test shards. -static const char kTestTotalShards[] = "GTEST_TOTAL_SHARDS"; -// The environment variable name for the test shard status file. -static const char kTestShardStatusFile[] = "GTEST_SHARD_STATUS_FILE"; - -namespace internal { - -// The text used in failure messages to indicate the start of the -// stack trace. -const char kStackTraceMarker[] = "\nStack trace:\n"; - -// g_help_flag is true iff the --help flag or an equivalent form is -// specified on the command line. -bool g_help_flag = false; - -} // namespace internal - -static const char* GetDefaultFilter() { - return kUniversalFilter; -} - -GTEST_DEFINE_bool_( - also_run_disabled_tests, - internal::BoolFromGTestEnv("also_run_disabled_tests", false), - "Run disabled tests too, in addition to the tests normally being run."); - -GTEST_DEFINE_bool_( - break_on_failure, - internal::BoolFromGTestEnv("break_on_failure", false), - "True iff a failed assertion should be a debugger break-point."); - -GTEST_DEFINE_bool_( - catch_exceptions, - internal::BoolFromGTestEnv("catch_exceptions", true), - "True iff " GTEST_NAME_ - " should catch exceptions and treat them as test failures."); - -GTEST_DEFINE_string_( - color, - internal::StringFromGTestEnv("color", "auto"), - "Whether to use colors in the output. Valid values: yes, no, " - "and auto. 'auto' means to use colors if the output is " - "being sent to a terminal and the TERM environment variable " - "is set to a terminal type that supports colors."); - -GTEST_DEFINE_string_( - filter, - internal::StringFromGTestEnv("filter", GetDefaultFilter()), - "A colon-separated list of glob (not regex) patterns " - "for filtering the tests to run, optionally followed by a " - "'-' and a : separated list of negative patterns (tests to " - "exclude). A test is run if it matches one of the positive " - "patterns and does not match any of the negative patterns."); - -GTEST_DEFINE_bool_(list_tests, false, - "List all tests without running them."); - -GTEST_DEFINE_string_( - output, - internal::StringFromGTestEnv("output", ""), - "A format (currently must be \"xml\"), optionally followed " - "by a colon and an output file name or directory. A directory " - "is indicated by a trailing pathname separator. " - "Examples: \"xml:filename.xml\", \"xml::directoryname/\". " - "If a directory is specified, output files will be created " - "within that directory, with file-names based on the test " - "executable's name and, if necessary, made unique by adding " - "digits."); - -GTEST_DEFINE_bool_( - print_time, - internal::BoolFromGTestEnv("print_time", true), - "True iff " GTEST_NAME_ - " should display elapsed time in text output."); - -GTEST_DEFINE_int32_( - random_seed, - internal::Int32FromGTestEnv("random_seed", 0), - "Random number seed to use when shuffling test orders. Must be in range " - "[1, 99999], or 0 to use a seed based on the current time."); - -GTEST_DEFINE_int32_( - repeat, - internal::Int32FromGTestEnv("repeat", 1), - "How many times to repeat each test. Specify a negative number " - "for repeating forever. Useful for shaking out flaky tests."); - -GTEST_DEFINE_bool_( - show_internal_stack_frames, false, - "True iff " GTEST_NAME_ " should include internal stack frames when " - "printing test failure stack traces."); - -GTEST_DEFINE_bool_( - shuffle, - internal::BoolFromGTestEnv("shuffle", false), - "True iff " GTEST_NAME_ - " should randomize tests' order on every run."); - -GTEST_DEFINE_int32_( - stack_trace_depth, - internal::Int32FromGTestEnv("stack_trace_depth", kMaxStackTraceDepth), - "The maximum number of stack frames to print when an " - "assertion fails. The valid range is 0 through 100, inclusive."); - -GTEST_DEFINE_string_( - stream_result_to, - internal::StringFromGTestEnv("stream_result_to", ""), - "This flag specifies the host name and the port number on which to stream " - "test results. Example: \"localhost:555\". The flag is effective only on " - "Linux."); - -GTEST_DEFINE_bool_( - throw_on_failure, - internal::BoolFromGTestEnv("throw_on_failure", false), - "When this flag is specified, a failed assertion will throw an exception " - "if exceptions are enabled or exit the program with a non-zero code " - "otherwise."); - -namespace internal { - -// Generates a random number from [0, range), using a Linear -// Congruential Generator (LCG). Crashes if 'range' is 0 or greater -// than kMaxRange. -UInt32 Random::Generate(UInt32 range) { - // These constants are the same as are used in glibc's rand(3). - state_ = (1103515245U*state_ + 12345U) % kMaxRange; - - GTEST_CHECK_(range > 0) - << "Cannot generate a number in the range [0, 0)."; - GTEST_CHECK_(range <= kMaxRange) - << "Generation of a number in [0, " << range << ") was requested, " - << "but this can only generate numbers in [0, " << kMaxRange << ")."; - - // Converting via modulus introduces a bit of downward bias, but - // it's simple, and a linear congruential generator isn't too good - // to begin with. - return state_ % range; -} - -// GTestIsInitialized() returns true iff the user has initialized -// Google Test. Useful for catching the user mistake of not initializing -// Google Test before calling RUN_ALL_TESTS(). -// -// A user must call testing::InitGoogleTest() to initialize Google -// Test. g_init_gtest_count is set to the number of times -// InitGoogleTest() has been called. We don't protect this variable -// under a mutex as it is only accessed in the main thread. -GTEST_API_ int g_init_gtest_count = 0; -static bool GTestIsInitialized() { return g_init_gtest_count != 0; } - -// Iterates over a vector of TestCases, keeping a running sum of the -// results of calling a given int-returning method on each. -// Returns the sum. -static int SumOverTestCaseList(const std::vector& case_list, - int (TestCase::*method)() const) { - int sum = 0; - for (size_t i = 0; i < case_list.size(); i++) { - sum += (case_list[i]->*method)(); - } - return sum; -} - -// Returns true iff the test case passed. -static bool TestCasePassed(const TestCase* test_case) { - return test_case->should_run() && test_case->Passed(); -} - -// Returns true iff the test case failed. -static bool TestCaseFailed(const TestCase* test_case) { - return test_case->should_run() && test_case->Failed(); -} - -// Returns true iff test_case contains at least one test that should -// run. -static bool ShouldRunTestCase(const TestCase* test_case) { - return test_case->should_run(); -} - -// AssertHelper constructor. -AssertHelper::AssertHelper(TestPartResult::Type type, - const char* file, - int line, - const char* message) - : data_(new AssertHelperData(type, file, line, message)) { -} - -AssertHelper::~AssertHelper() { - delete data_; -} - -// Message assignment, for assertion streaming support. -void AssertHelper::operator=(const Message& message) const { - UnitTest::GetInstance()-> - AddTestPartResult(data_->type, data_->file, data_->line, - AppendUserMessage(data_->message, message), - UnitTest::GetInstance()->impl() - ->CurrentOsStackTraceExceptTop(1) - // Skips the stack frame for this function itself. - ); // NOLINT -} - -// Mutex for linked pointers. -GTEST_API_ GTEST_DEFINE_STATIC_MUTEX_(g_linked_ptr_mutex); - -// Application pathname gotten in InitGoogleTest. -std::string g_executable_path; - -// Returns the current application's name, removing directory path if that -// is present. -FilePath GetCurrentExecutableName() { - FilePath result; - -#if GTEST_OS_WINDOWS - result.Set(FilePath(g_executable_path).RemoveExtension("exe")); -#else - result.Set(FilePath(g_executable_path)); -#endif // GTEST_OS_WINDOWS - - return result.RemoveDirectoryName(); -} - -// Functions for processing the gtest_output flag. - -// Returns the output format, or "" for normal printed output. -std::string UnitTestOptions::GetOutputFormat() { - const char* const gtest_output_flag = GTEST_FLAG(output).c_str(); - if (gtest_output_flag == NULL) return std::string(""); - - const char* const colon = strchr(gtest_output_flag, ':'); - return (colon == NULL) ? - std::string(gtest_output_flag) : - std::string(gtest_output_flag, colon - gtest_output_flag); -} - -// Returns the name of the requested output file, or the default if none -// was explicitly specified. -std::string UnitTestOptions::GetAbsolutePathToOutputFile() { - const char* const gtest_output_flag = GTEST_FLAG(output).c_str(); - if (gtest_output_flag == NULL) - return ""; - - const char* const colon = strchr(gtest_output_flag, ':'); - if (colon == NULL) - return internal::FilePath::ConcatPaths( - internal::FilePath( - UnitTest::GetInstance()->original_working_dir()), - internal::FilePath(kDefaultOutputFile)).string(); - - internal::FilePath output_name(colon + 1); - if (!output_name.IsAbsolutePath()) - // TODO(wan@google.com): on Windows \some\path is not an absolute - // path (as its meaning depends on the current drive), yet the - // following logic for turning it into an absolute path is wrong. - // Fix it. - output_name = internal::FilePath::ConcatPaths( - internal::FilePath(UnitTest::GetInstance()->original_working_dir()), - internal::FilePath(colon + 1)); - - if (!output_name.IsDirectory()) - return output_name.string(); - - internal::FilePath result(internal::FilePath::GenerateUniqueFileName( - output_name, internal::GetCurrentExecutableName(), - GetOutputFormat().c_str())); - return result.string(); -} - -// Returns true iff the wildcard pattern matches the string. The -// first ':' or '\0' character in pattern marks the end of it. -// -// This recursive algorithm isn't very efficient, but is clear and -// works well enough for matching test names, which are short. -bool UnitTestOptions::PatternMatchesString(const char *pattern, - const char *str) { - switch (*pattern) { - case '\0': - case ':': // Either ':' or '\0' marks the end of the pattern. - return *str == '\0'; - case '?': // Matches any single character. - return *str != '\0' && PatternMatchesString(pattern + 1, str + 1); - case '*': // Matches any string (possibly empty) of characters. - return (*str != '\0' && PatternMatchesString(pattern, str + 1)) || - PatternMatchesString(pattern + 1, str); - default: // Non-special character. Matches itself. - return *pattern == *str && - PatternMatchesString(pattern + 1, str + 1); - } -} - -bool UnitTestOptions::MatchesFilter( - const std::string& name, const char* filter) { - const char *cur_pattern = filter; - for (;;) { - if (PatternMatchesString(cur_pattern, name.c_str())) { - return true; - } - - // Finds the next pattern in the filter. - cur_pattern = strchr(cur_pattern, ':'); - - // Returns if no more pattern can be found. - if (cur_pattern == NULL) { - return false; - } - - // Skips the pattern separater (the ':' character). - cur_pattern++; - } -} - -// Returns true iff the user-specified filter matches the test case -// name and the test name. -bool UnitTestOptions::FilterMatchesTest(const std::string &test_case_name, - const std::string &test_name) { - const std::string& full_name = test_case_name + "." + test_name.c_str(); - - // Split --gtest_filter at '-', if there is one, to separate into - // positive filter and negative filter portions - const char* const p = GTEST_FLAG(filter).c_str(); - const char* const dash = strchr(p, '-'); - std::string positive; - std::string negative; - if (dash == NULL) { - positive = GTEST_FLAG(filter).c_str(); // Whole string is a positive filter - negative = ""; - } else { - positive = std::string(p, dash); // Everything up to the dash - negative = std::string(dash + 1); // Everything after the dash - if (positive.empty()) { - // Treat '-test1' as the same as '*-test1' - positive = kUniversalFilter; - } - } - - // A filter is a colon-separated list of patterns. It matches a - // test if any pattern in it matches the test. - return (MatchesFilter(full_name, positive.c_str()) && - !MatchesFilter(full_name, negative.c_str())); -} - -#if GTEST_HAS_SEH -// Returns EXCEPTION_EXECUTE_HANDLER if Google Test should handle the -// given SEH exception, or EXCEPTION_CONTINUE_SEARCH otherwise. -// This function is useful as an __except condition. -int UnitTestOptions::GTestShouldProcessSEH(DWORD exception_code) { - // Google Test should handle a SEH exception if: - // 1. the user wants it to, AND - // 2. this is not a breakpoint exception, AND - // 3. this is not a C++ exception (VC++ implements them via SEH, - // apparently). - // - // SEH exception code for C++ exceptions. - // (see http://support.microsoft.com/kb/185294 for more information). - const DWORD kCxxExceptionCode = 0xe06d7363; - - bool should_handle = true; - - if (!GTEST_FLAG(catch_exceptions)) - should_handle = false; - else if (exception_code == EXCEPTION_BREAKPOINT) - should_handle = false; - else if (exception_code == kCxxExceptionCode) - should_handle = false; - - return should_handle ? EXCEPTION_EXECUTE_HANDLER : EXCEPTION_CONTINUE_SEARCH; -} -#endif // GTEST_HAS_SEH - -} // namespace internal - -// The c'tor sets this object as the test part result reporter used by -// Google Test. The 'result' parameter specifies where to report the -// results. Intercepts only failures from the current thread. -ScopedFakeTestPartResultReporter::ScopedFakeTestPartResultReporter( - TestPartResultArray* result) - : intercept_mode_(INTERCEPT_ONLY_CURRENT_THREAD), - result_(result) { - Init(); -} - -// The c'tor sets this object as the test part result reporter used by -// Google Test. The 'result' parameter specifies where to report the -// results. -ScopedFakeTestPartResultReporter::ScopedFakeTestPartResultReporter( - InterceptMode intercept_mode, TestPartResultArray* result) - : intercept_mode_(intercept_mode), - result_(result) { - Init(); -} - -void ScopedFakeTestPartResultReporter::Init() { - internal::UnitTestImpl* const impl = internal::GetUnitTestImpl(); - if (intercept_mode_ == INTERCEPT_ALL_THREADS) { - old_reporter_ = impl->GetGlobalTestPartResultReporter(); - impl->SetGlobalTestPartResultReporter(this); - } else { - old_reporter_ = impl->GetTestPartResultReporterForCurrentThread(); - impl->SetTestPartResultReporterForCurrentThread(this); - } -} - -// The d'tor restores the test part result reporter used by Google Test -// before. -ScopedFakeTestPartResultReporter::~ScopedFakeTestPartResultReporter() { - internal::UnitTestImpl* const impl = internal::GetUnitTestImpl(); - if (intercept_mode_ == INTERCEPT_ALL_THREADS) { - impl->SetGlobalTestPartResultReporter(old_reporter_); - } else { - impl->SetTestPartResultReporterForCurrentThread(old_reporter_); - } -} - -// Increments the test part result count and remembers the result. -// This method is from the TestPartResultReporterInterface interface. -void ScopedFakeTestPartResultReporter::ReportTestPartResult( - const TestPartResult& result) { - result_->Append(result); -} - -namespace internal { - -// Returns the type ID of ::testing::Test. We should always call this -// instead of GetTypeId< ::testing::Test>() to get the type ID of -// testing::Test. This is to work around a suspected linker bug when -// using Google Test as a framework on Mac OS X. The bug causes -// GetTypeId< ::testing::Test>() to return different values depending -// on whether the call is from the Google Test framework itself or -// from user test code. GetTestTypeId() is guaranteed to always -// return the same value, as it always calls GetTypeId<>() from the -// gtest.cc, which is within the Google Test framework. -TypeId GetTestTypeId() { - return GetTypeId(); -} - -// The value of GetTestTypeId() as seen from within the Google Test -// library. This is solely for testing GetTestTypeId(). -extern const TypeId kTestTypeIdInGoogleTest = GetTestTypeId(); - -// This predicate-formatter checks that 'results' contains a test part -// failure of the given type and that the failure message contains the -// given substring. -AssertionResult HasOneFailure(const char* /* results_expr */, - const char* /* type_expr */, - const char* /* substr_expr */, - const TestPartResultArray& results, - TestPartResult::Type type, - const string& substr) { - const std::string expected(type == TestPartResult::kFatalFailure ? - "1 fatal failure" : - "1 non-fatal failure"); - Message msg; - if (results.size() != 1) { - msg << "Expected: " << expected << "\n" - << " Actual: " << results.size() << " failures"; - for (int i = 0; i < results.size(); i++) { - msg << "\n" << results.GetTestPartResult(i); - } - return AssertionFailure() << msg; - } - - const TestPartResult& r = results.GetTestPartResult(0); - if (r.type() != type) { - return AssertionFailure() << "Expected: " << expected << "\n" - << " Actual:\n" - << r; - } - - if (strstr(r.message(), substr.c_str()) == NULL) { - return AssertionFailure() << "Expected: " << expected << " containing \"" - << substr << "\"\n" - << " Actual:\n" - << r; - } - - return AssertionSuccess(); -} - -// The constructor of SingleFailureChecker remembers where to look up -// test part results, what type of failure we expect, and what -// substring the failure message should contain. -SingleFailureChecker:: SingleFailureChecker( - const TestPartResultArray* results, - TestPartResult::Type type, - const string& substr) - : results_(results), - type_(type), - substr_(substr) {} - -// The destructor of SingleFailureChecker verifies that the given -// TestPartResultArray contains exactly one failure that has the given -// type and contains the given substring. If that's not the case, a -// non-fatal failure will be generated. -SingleFailureChecker::~SingleFailureChecker() { - EXPECT_PRED_FORMAT3(HasOneFailure, *results_, type_, substr_); -} - -DefaultGlobalTestPartResultReporter::DefaultGlobalTestPartResultReporter( - UnitTestImpl* unit_test) : unit_test_(unit_test) {} - -void DefaultGlobalTestPartResultReporter::ReportTestPartResult( - const TestPartResult& result) { - unit_test_->current_test_result()->AddTestPartResult(result); - unit_test_->listeners()->repeater()->OnTestPartResult(result); -} - -DefaultPerThreadTestPartResultReporter::DefaultPerThreadTestPartResultReporter( - UnitTestImpl* unit_test) : unit_test_(unit_test) {} - -void DefaultPerThreadTestPartResultReporter::ReportTestPartResult( - const TestPartResult& result) { - unit_test_->GetGlobalTestPartResultReporter()->ReportTestPartResult(result); -} - -// Returns the global test part result reporter. -TestPartResultReporterInterface* -UnitTestImpl::GetGlobalTestPartResultReporter() { - internal::MutexLock lock(&global_test_part_result_reporter_mutex_); - return global_test_part_result_repoter_; -} - -// Sets the global test part result reporter. -void UnitTestImpl::SetGlobalTestPartResultReporter( - TestPartResultReporterInterface* reporter) { - internal::MutexLock lock(&global_test_part_result_reporter_mutex_); - global_test_part_result_repoter_ = reporter; -} - -// Returns the test part result reporter for the current thread. -TestPartResultReporterInterface* -UnitTestImpl::GetTestPartResultReporterForCurrentThread() { - return per_thread_test_part_result_reporter_.get(); -} - -// Sets the test part result reporter for the current thread. -void UnitTestImpl::SetTestPartResultReporterForCurrentThread( - TestPartResultReporterInterface* reporter) { - per_thread_test_part_result_reporter_.set(reporter); -} - -// Gets the number of successful test cases. -int UnitTestImpl::successful_test_case_count() const { - return CountIf(test_cases_, TestCasePassed); -} - -// Gets the number of failed test cases. -int UnitTestImpl::failed_test_case_count() const { - return CountIf(test_cases_, TestCaseFailed); -} - -// Gets the number of all test cases. -int UnitTestImpl::total_test_case_count() const { - return static_cast(test_cases_.size()); -} - -// Gets the number of all test cases that contain at least one test -// that should run. -int UnitTestImpl::test_case_to_run_count() const { - return CountIf(test_cases_, ShouldRunTestCase); -} - -// Gets the number of successful tests. -int UnitTestImpl::successful_test_count() const { - return SumOverTestCaseList(test_cases_, &TestCase::successful_test_count); -} - -// Gets the number of failed tests. -int UnitTestImpl::failed_test_count() const { - return SumOverTestCaseList(test_cases_, &TestCase::failed_test_count); -} - -// Gets the number of disabled tests that will be reported in the XML report. -int UnitTestImpl::reportable_disabled_test_count() const { - return SumOverTestCaseList(test_cases_, - &TestCase::reportable_disabled_test_count); -} - -// Gets the number of disabled tests. -int UnitTestImpl::disabled_test_count() const { - return SumOverTestCaseList(test_cases_, &TestCase::disabled_test_count); -} - -// Gets the number of tests to be printed in the XML report. -int UnitTestImpl::reportable_test_count() const { - return SumOverTestCaseList(test_cases_, &TestCase::reportable_test_count); -} - -// Gets the number of all tests. -int UnitTestImpl::total_test_count() const { - return SumOverTestCaseList(test_cases_, &TestCase::total_test_count); -} - -// Gets the number of tests that should run. -int UnitTestImpl::test_to_run_count() const { - return SumOverTestCaseList(test_cases_, &TestCase::test_to_run_count); -} - -// Returns the current OS stack trace as an std::string. -// -// The maximum number of stack frames to be included is specified by -// the gtest_stack_trace_depth flag. The skip_count parameter -// specifies the number of top frames to be skipped, which doesn't -// count against the number of frames to be included. -// -// For example, if Foo() calls Bar(), which in turn calls -// CurrentOsStackTraceExceptTop(1), Foo() will be included in the -// trace but Bar() and CurrentOsStackTraceExceptTop() won't. -std::string UnitTestImpl::CurrentOsStackTraceExceptTop(int skip_count) { - (void)skip_count; - return ""; -} - -// Returns the current time in milliseconds. -TimeInMillis GetTimeInMillis() { -#if GTEST_OS_WINDOWS_MOBILE || defined(__BORLANDC__) - // Difference between 1970-01-01 and 1601-01-01 in milliseconds. - // http://analogous.blogspot.com/2005/04/epoch.html - const TimeInMillis kJavaEpochToWinFileTimeDelta = - static_cast(116444736UL) * 100000UL; - const DWORD kTenthMicrosInMilliSecond = 10000; - - SYSTEMTIME now_systime; - FILETIME now_filetime; - ULARGE_INTEGER now_int64; - // TODO(kenton@google.com): Shouldn't this just use - // GetSystemTimeAsFileTime()? - GetSystemTime(&now_systime); - if (SystemTimeToFileTime(&now_systime, &now_filetime)) { - now_int64.LowPart = now_filetime.dwLowDateTime; - now_int64.HighPart = now_filetime.dwHighDateTime; - now_int64.QuadPart = (now_int64.QuadPart / kTenthMicrosInMilliSecond) - - kJavaEpochToWinFileTimeDelta; - return now_int64.QuadPart; - } - return 0; -#elif GTEST_OS_WINDOWS && !GTEST_HAS_GETTIMEOFDAY_ - __timeb64 now; - -# ifdef _MSC_VER - - // MSVC 8 deprecates _ftime64(), so we want to suppress warning 4996 - // (deprecated function) there. - // TODO(kenton@google.com): Use GetTickCount()? Or use - // SystemTimeToFileTime() -# pragma warning(push) // Saves the current warning state. -# pragma warning(disable:4996) // Temporarily disables warning 4996. - _ftime64(&now); -# pragma warning(pop) // Restores the warning state. -# else - - _ftime64(&now); - -# endif // _MSC_VER - - return static_cast(now.time) * 1000 + now.millitm; -#elif GTEST_HAS_GETTIMEOFDAY_ - struct timeval now; - gettimeofday(&now, NULL); - return static_cast(now.tv_sec) * 1000 + now.tv_usec / 1000; -#else -# error "Don't know how to get the current time on your system." -#endif -} - -// Utilities - -// class String. - -#if GTEST_OS_WINDOWS_MOBILE -// Creates a UTF-16 wide string from the given ANSI string, allocating -// memory using new. The caller is responsible for deleting the return -// value using delete[]. Returns the wide string, or NULL if the -// input is NULL. -LPCWSTR String::AnsiToUtf16(const char* ansi) { - if (!ansi) return NULL; - const int length = strlen(ansi); - const int unicode_length = - MultiByteToWideChar(CP_ACP, 0, ansi, length, - NULL, 0); - WCHAR* unicode = new WCHAR[unicode_length + 1]; - MultiByteToWideChar(CP_ACP, 0, ansi, length, - unicode, unicode_length); - unicode[unicode_length] = 0; - return unicode; -} - -// Creates an ANSI string from the given wide string, allocating -// memory using new. The caller is responsible for deleting the return -// value using delete[]. Returns the ANSI string, or NULL if the -// input is NULL. -const char* String::Utf16ToAnsi(LPCWSTR utf16_str) { - if (!utf16_str) return NULL; - const int ansi_length = - WideCharToMultiByte(CP_ACP, 0, utf16_str, -1, - NULL, 0, NULL, NULL); - char* ansi = new char[ansi_length + 1]; - WideCharToMultiByte(CP_ACP, 0, utf16_str, -1, - ansi, ansi_length, NULL, NULL); - ansi[ansi_length] = 0; - return ansi; -} - -#endif // GTEST_OS_WINDOWS_MOBILE - -// Compares two C strings. Returns true iff they have the same content. -// -// Unlike strcmp(), this function can handle NULL argument(s). A NULL -// C string is considered different to any non-NULL C string, -// including the empty string. -bool String::CStringEquals(const char * lhs, const char * rhs) { - if ( lhs == NULL ) return rhs == NULL; - - if ( rhs == NULL ) return false; - - return strcmp(lhs, rhs) == 0; -} - -#if GTEST_HAS_STD_WSTRING || GTEST_HAS_GLOBAL_WSTRING - -// Converts an array of wide chars to a narrow string using the UTF-8 -// encoding, and streams the result to the given Message object. -static void StreamWideCharsToMessage(const wchar_t* wstr, size_t length, - Message* msg) { - for (size_t i = 0; i != length; ) { // NOLINT - if (wstr[i] != L'\0') { - *msg << WideStringToUtf8(wstr + i, static_cast(length - i)); - while (i != length && wstr[i] != L'\0') - i++; - } else { - *msg << '\0'; - i++; - } - } -} - -#endif // GTEST_HAS_STD_WSTRING || GTEST_HAS_GLOBAL_WSTRING - -} // namespace internal - -// Constructs an empty Message. -// We allocate the stringstream separately because otherwise each use of -// ASSERT/EXPECT in a procedure adds over 200 bytes to the procedure's -// stack frame leading to huge stack frames in some cases; gcc does not reuse -// the stack space. -Message::Message() : ss_(new ::std::stringstream) { - // By default, we want there to be enough precision when printing - // a double to a Message. - *ss_ << std::setprecision(std::numeric_limits::digits10 + 2); -} - -// These two overloads allow streaming a wide C string to a Message -// using the UTF-8 encoding. -Message& Message::operator <<(const wchar_t* wide_c_str) { - return *this << internal::String::ShowWideCString(wide_c_str); -} -Message& Message::operator <<(wchar_t* wide_c_str) { - return *this << internal::String::ShowWideCString(wide_c_str); -} - -#if GTEST_HAS_STD_WSTRING -// Converts the given wide string to a narrow string using the UTF-8 -// encoding, and streams the result to this Message object. -Message& Message::operator <<(const ::std::wstring& wstr) { - internal::StreamWideCharsToMessage(wstr.c_str(), wstr.length(), this); - return *this; -} -#endif // GTEST_HAS_STD_WSTRING - -#if GTEST_HAS_GLOBAL_WSTRING -// Converts the given wide string to a narrow string using the UTF-8 -// encoding, and streams the result to this Message object. -Message& Message::operator <<(const ::wstring& wstr) { - internal::StreamWideCharsToMessage(wstr.c_str(), wstr.length(), this); - return *this; -} -#endif // GTEST_HAS_GLOBAL_WSTRING - -// Gets the text streamed to this object so far as an std::string. -// Each '\0' character in the buffer is replaced with "\\0". -std::string Message::GetString() const { - return internal::StringStreamToString(ss_.get()); -} - -// AssertionResult constructors. -// Used in EXPECT_TRUE/FALSE(assertion_result). -AssertionResult::AssertionResult(const AssertionResult& other) - : success_(other.success_), - message_(other.message_.get() != NULL ? - new ::std::string(*other.message_) : - static_cast< ::std::string*>(NULL)) { -} - -// Returns the assertion's negation. Used with EXPECT/ASSERT_FALSE. -AssertionResult AssertionResult::operator!() const { - AssertionResult negation(!success_); - if (message_.get() != NULL) - negation << *message_; - return negation; -} - -// Makes a successful assertion result. -AssertionResult AssertionSuccess() { - return AssertionResult(true); -} - -// Makes a failed assertion result. -AssertionResult AssertionFailure() { - return AssertionResult(false); -} - -// Makes a failed assertion result with the given failure message. -// Deprecated; use AssertionFailure() << message. -AssertionResult AssertionFailure(const Message& message) { - return AssertionFailure() << message; -} - -namespace internal { - -// Constructs and returns the message for an equality assertion -// (e.g. ASSERT_EQ, EXPECT_STREQ, etc) failure. -// -// The first four parameters are the expressions used in the assertion -// and their values, as strings. For example, for ASSERT_EQ(foo, bar) -// where foo is 5 and bar is 6, we have: -// -// expected_expression: "foo" -// actual_expression: "bar" -// expected_value: "5" -// actual_value: "6" -// -// The ignoring_case parameter is true iff the assertion is a -// *_STRCASEEQ*. When it's true, the string " (ignoring case)" will -// be inserted into the message. -AssertionResult EqFailure(const char* expected_expression, - const char* actual_expression, - const std::string& expected_value, - const std::string& actual_value, - bool ignoring_case) { - Message msg; - msg << "Value of: " << actual_expression; - if (actual_value != actual_expression) { - msg << "\n Actual: " << actual_value; - } - - msg << "\nExpected: " << expected_expression; - if (ignoring_case) { - msg << " (ignoring case)"; - } - if (expected_value != expected_expression) { - msg << "\nWhich is: " << expected_value; - } - - return AssertionFailure() << msg; -} - -// Constructs a failure message for Boolean assertions such as EXPECT_TRUE. -std::string GetBoolAssertionFailureMessage( - const AssertionResult& assertion_result, - const char* expression_text, - const char* actual_predicate_value, - const char* expected_predicate_value) { - const char* actual_message = assertion_result.message(); - Message msg; - msg << "Value of: " << expression_text - << "\n Actual: " << actual_predicate_value; - if (actual_message[0] != '\0') - msg << " (" << actual_message << ")"; - msg << "\nExpected: " << expected_predicate_value; - return msg.GetString(); -} - -// Helper function for implementing ASSERT_NEAR. -AssertionResult DoubleNearPredFormat(const char* expr1, - const char* expr2, - const char* abs_error_expr, - double val1, - double val2, - double abs_error) { - const double diff = fabs(val1 - val2); - if (diff <= abs_error) return AssertionSuccess(); - - // TODO(wan): do not print the value of an expression if it's - // already a literal. - return AssertionFailure() - << "The difference between " << expr1 << " and " << expr2 - << " is " << diff << ", which exceeds " << abs_error_expr << ", where\n" - << expr1 << " evaluates to " << val1 << ",\n" - << expr2 << " evaluates to " << val2 << ", and\n" - << abs_error_expr << " evaluates to " << abs_error << "."; -} - - -// Helper template for implementing FloatLE() and DoubleLE(). -template -AssertionResult FloatingPointLE(const char* expr1, - const char* expr2, - RawType val1, - RawType val2) { - // Returns success if val1 is less than val2, - if (val1 < val2) { - return AssertionSuccess(); - } - - // or if val1 is almost equal to val2. - const FloatingPoint lhs(val1), rhs(val2); - if (lhs.AlmostEquals(rhs)) { - return AssertionSuccess(); - } - - // Note that the above two checks will both fail if either val1 or - // val2 is NaN, as the IEEE floating-point standard requires that - // any predicate involving a NaN must return false. - - ::std::stringstream val1_ss; - val1_ss << std::setprecision(std::numeric_limits::digits10 + 2) - << val1; - - ::std::stringstream val2_ss; - val2_ss << std::setprecision(std::numeric_limits::digits10 + 2) - << val2; - - return AssertionFailure() - << "Expected: (" << expr1 << ") <= (" << expr2 << ")\n" - << " Actual: " << StringStreamToString(&val1_ss) << " vs " - << StringStreamToString(&val2_ss); -} - -} // namespace internal - -// Asserts that val1 is less than, or almost equal to, val2. Fails -// otherwise. In particular, it fails if either val1 or val2 is NaN. -AssertionResult FloatLE(const char* expr1, const char* expr2, - float val1, float val2) { - return internal::FloatingPointLE(expr1, expr2, val1, val2); -} - -// Asserts that val1 is less than, or almost equal to, val2. Fails -// otherwise. In particular, it fails if either val1 or val2 is NaN. -AssertionResult DoubleLE(const char* expr1, const char* expr2, - double val1, double val2) { - return internal::FloatingPointLE(expr1, expr2, val1, val2); -} - -namespace internal { - -// The helper function for {ASSERT|EXPECT}_EQ with int or enum -// arguments. -AssertionResult CmpHelperEQ(const char* expected_expression, - const char* actual_expression, - BiggestInt expected, - BiggestInt actual) { - if (expected == actual) { - return AssertionSuccess(); - } - - return EqFailure(expected_expression, - actual_expression, - FormatForComparisonFailureMessage(expected, actual), - FormatForComparisonFailureMessage(actual, expected), - false); -} - -// A macro for implementing the helper functions needed to implement -// ASSERT_?? and EXPECT_?? with integer or enum arguments. It is here -// just to avoid copy-and-paste of similar code. -#define GTEST_IMPL_CMP_HELPER_(op_name, op)\ -AssertionResult CmpHelper##op_name(const char* expr1, const char* expr2, \ - BiggestInt val1, BiggestInt val2) {\ - if (val1 op val2) {\ - return AssertionSuccess();\ - } else {\ - return AssertionFailure() \ - << "Expected: (" << expr1 << ") " #op " (" << expr2\ - << "), actual: " << FormatForComparisonFailureMessage(val1, val2)\ - << " vs " << FormatForComparisonFailureMessage(val2, val1);\ - }\ -} - -// Implements the helper function for {ASSERT|EXPECT}_NE with int or -// enum arguments. -GTEST_IMPL_CMP_HELPER_(NE, !=) -// Implements the helper function for {ASSERT|EXPECT}_LE with int or -// enum arguments. -GTEST_IMPL_CMP_HELPER_(LE, <=) -// Implements the helper function for {ASSERT|EXPECT}_LT with int or -// enum arguments. -GTEST_IMPL_CMP_HELPER_(LT, < ) -// Implements the helper function for {ASSERT|EXPECT}_GE with int or -// enum arguments. -GTEST_IMPL_CMP_HELPER_(GE, >=) -// Implements the helper function for {ASSERT|EXPECT}_GT with int or -// enum arguments. -GTEST_IMPL_CMP_HELPER_(GT, > ) - -#undef GTEST_IMPL_CMP_HELPER_ - -// The helper function for {ASSERT|EXPECT}_STREQ. -AssertionResult CmpHelperSTREQ(const char* expected_expression, - const char* actual_expression, - const char* expected, - const char* actual) { - if (String::CStringEquals(expected, actual)) { - return AssertionSuccess(); - } - - return EqFailure(expected_expression, - actual_expression, - PrintToString(expected), - PrintToString(actual), - false); -} - -// The helper function for {ASSERT|EXPECT}_STRCASEEQ. -AssertionResult CmpHelperSTRCASEEQ(const char* expected_expression, - const char* actual_expression, - const char* expected, - const char* actual) { - if (String::CaseInsensitiveCStringEquals(expected, actual)) { - return AssertionSuccess(); - } - - return EqFailure(expected_expression, - actual_expression, - PrintToString(expected), - PrintToString(actual), - true); -} - -// The helper function for {ASSERT|EXPECT}_STRNE. -AssertionResult CmpHelperSTRNE(const char* s1_expression, - const char* s2_expression, - const char* s1, - const char* s2) { - if (!String::CStringEquals(s1, s2)) { - return AssertionSuccess(); - } else { - return AssertionFailure() << "Expected: (" << s1_expression << ") != (" - << s2_expression << "), actual: \"" - << s1 << "\" vs \"" << s2 << "\""; - } -} - -// The helper function for {ASSERT|EXPECT}_STRCASENE. -AssertionResult CmpHelperSTRCASENE(const char* s1_expression, - const char* s2_expression, - const char* s1, - const char* s2) { - if (!String::CaseInsensitiveCStringEquals(s1, s2)) { - return AssertionSuccess(); - } else { - return AssertionFailure() - << "Expected: (" << s1_expression << ") != (" - << s2_expression << ") (ignoring case), actual: \"" - << s1 << "\" vs \"" << s2 << "\""; - } -} - -} // namespace internal - -namespace { - -// Helper functions for implementing IsSubString() and IsNotSubstring(). - -// This group of overloaded functions return true iff needle is a -// substring of haystack. NULL is considered a substring of itself -// only. - -bool IsSubstringPred(const char* needle, const char* haystack) { - if (needle == NULL || haystack == NULL) - return needle == haystack; - - return strstr(haystack, needle) != NULL; -} - -bool IsSubstringPred(const wchar_t* needle, const wchar_t* haystack) { - if (needle == NULL || haystack == NULL) - return needle == haystack; - - return wcsstr(haystack, needle) != NULL; -} - -// StringType here can be either ::std::string or ::std::wstring. -template -bool IsSubstringPred(const StringType& needle, - const StringType& haystack) { - return haystack.find(needle) != StringType::npos; -} - -// This function implements either IsSubstring() or IsNotSubstring(), -// depending on the value of the expected_to_be_substring parameter. -// StringType here can be const char*, const wchar_t*, ::std::string, -// or ::std::wstring. -template -AssertionResult IsSubstringImpl( - bool expected_to_be_substring, - const char* needle_expr, const char* haystack_expr, - const StringType& needle, const StringType& haystack) { - if (IsSubstringPred(needle, haystack) == expected_to_be_substring) - return AssertionSuccess(); - - const bool is_wide_string = sizeof(needle[0]) > 1; - const char* const begin_string_quote = is_wide_string ? "L\"" : "\""; - return AssertionFailure() - << "Value of: " << needle_expr << "\n" - << " Actual: " << begin_string_quote << needle << "\"\n" - << "Expected: " << (expected_to_be_substring ? "" : "not ") - << "a substring of " << haystack_expr << "\n" - << "Which is: " << begin_string_quote << haystack << "\""; -} - -} // namespace - -// IsSubstring() and IsNotSubstring() check whether needle is a -// substring of haystack (NULL is considered a substring of itself -// only), and return an appropriate error message when they fail. - -AssertionResult IsSubstring( - const char* needle_expr, const char* haystack_expr, - const char* needle, const char* haystack) { - return IsSubstringImpl(true, needle_expr, haystack_expr, needle, haystack); -} - -AssertionResult IsSubstring( - const char* needle_expr, const char* haystack_expr, - const wchar_t* needle, const wchar_t* haystack) { - return IsSubstringImpl(true, needle_expr, haystack_expr, needle, haystack); -} - -AssertionResult IsNotSubstring( - const char* needle_expr, const char* haystack_expr, - const char* needle, const char* haystack) { - return IsSubstringImpl(false, needle_expr, haystack_expr, needle, haystack); -} - -AssertionResult IsNotSubstring( - const char* needle_expr, const char* haystack_expr, - const wchar_t* needle, const wchar_t* haystack) { - return IsSubstringImpl(false, needle_expr, haystack_expr, needle, haystack); -} - -AssertionResult IsSubstring( - const char* needle_expr, const char* haystack_expr, - const ::std::string& needle, const ::std::string& haystack) { - return IsSubstringImpl(true, needle_expr, haystack_expr, needle, haystack); -} - -AssertionResult IsNotSubstring( - const char* needle_expr, const char* haystack_expr, - const ::std::string& needle, const ::std::string& haystack) { - return IsSubstringImpl(false, needle_expr, haystack_expr, needle, haystack); -} - -#if GTEST_HAS_STD_WSTRING -AssertionResult IsSubstring( - const char* needle_expr, const char* haystack_expr, - const ::std::wstring& needle, const ::std::wstring& haystack) { - return IsSubstringImpl(true, needle_expr, haystack_expr, needle, haystack); -} - -AssertionResult IsNotSubstring( - const char* needle_expr, const char* haystack_expr, - const ::std::wstring& needle, const ::std::wstring& haystack) { - return IsSubstringImpl(false, needle_expr, haystack_expr, needle, haystack); -} -#endif // GTEST_HAS_STD_WSTRING - -namespace internal { - -#if GTEST_OS_WINDOWS - -namespace { - -// Helper function for IsHRESULT{SuccessFailure} predicates -AssertionResult HRESULTFailureHelper(const char* expr, - const char* expected, - long hr) { // NOLINT -# if GTEST_OS_WINDOWS_MOBILE - - // Windows CE doesn't support FormatMessage. - const char error_text[] = ""; - -# else - - // Looks up the human-readable system message for the HRESULT code - // and since we're not passing any params to FormatMessage, we don't - // want inserts expanded. - const DWORD kFlags = FORMAT_MESSAGE_FROM_SYSTEM | - FORMAT_MESSAGE_IGNORE_INSERTS; - const DWORD kBufSize = 4096; - // Gets the system's human readable message string for this HRESULT. - char error_text[kBufSize] = { '\0' }; - DWORD message_length = ::FormatMessageA(kFlags, - 0, // no source, we're asking system - hr, // the error - 0, // no line width restrictions - error_text, // output buffer - kBufSize, // buf size - NULL); // no arguments for inserts - // Trims tailing white space (FormatMessage leaves a trailing CR-LF) - for (; message_length && IsSpace(error_text[message_length - 1]); - --message_length) { - error_text[message_length - 1] = '\0'; - } - -# endif // GTEST_OS_WINDOWS_MOBILE - - const std::string error_hex("0x" + String::FormatHexInt(hr)); - return ::testing::AssertionFailure() - << "Expected: " << expr << " " << expected << ".\n" - << " Actual: " << error_hex << " " << error_text << "\n"; -} - -} // namespace - -AssertionResult IsHRESULTSuccess(const char* expr, long hr) { // NOLINT - if (SUCCEEDED(hr)) { - return AssertionSuccess(); - } - return HRESULTFailureHelper(expr, "succeeds", hr); -} - -AssertionResult IsHRESULTFailure(const char* expr, long hr) { // NOLINT - if (FAILED(hr)) { - return AssertionSuccess(); - } - return HRESULTFailureHelper(expr, "fails", hr); -} - -#endif // GTEST_OS_WINDOWS - -// Utility functions for encoding Unicode text (wide strings) in -// UTF-8. - -// A Unicode code-point can have upto 21 bits, and is encoded in UTF-8 -// like this: -// -// Code-point length Encoding -// 0 - 7 bits 0xxxxxxx -// 8 - 11 bits 110xxxxx 10xxxxxx -// 12 - 16 bits 1110xxxx 10xxxxxx 10xxxxxx -// 17 - 21 bits 11110xxx 10xxxxxx 10xxxxxx 10xxxxxx - -// The maximum code-point a one-byte UTF-8 sequence can represent. -const UInt32 kMaxCodePoint1 = (static_cast(1) << 7) - 1; - -// The maximum code-point a two-byte UTF-8 sequence can represent. -const UInt32 kMaxCodePoint2 = (static_cast(1) << (5 + 6)) - 1; - -// The maximum code-point a three-byte UTF-8 sequence can represent. -const UInt32 kMaxCodePoint3 = (static_cast(1) << (4 + 2*6)) - 1; - -// The maximum code-point a four-byte UTF-8 sequence can represent. -const UInt32 kMaxCodePoint4 = (static_cast(1) << (3 + 3*6)) - 1; - -// Chops off the n lowest bits from a bit pattern. Returns the n -// lowest bits. As a side effect, the original bit pattern will be -// shifted to the right by n bits. -inline UInt32 ChopLowBits(UInt32* bits, int n) { - const UInt32 low_bits = *bits & ((static_cast(1) << n) - 1); - *bits >>= n; - return low_bits; -} - -// Converts a Unicode code point to a narrow string in UTF-8 encoding. -// code_point parameter is of type UInt32 because wchar_t may not be -// wide enough to contain a code point. -// If the code_point is not a valid Unicode code point -// (i.e. outside of Unicode range U+0 to U+10FFFF) it will be converted -// to "(Invalid Unicode 0xXXXXXXXX)". -std::string CodePointToUtf8(UInt32 code_point) { - if (code_point > kMaxCodePoint4) { - return "(Invalid Unicode 0x" + String::FormatHexInt(code_point) + ")"; - } - - char str[5]; // Big enough for the largest valid code point. - if (code_point <= kMaxCodePoint1) { - str[1] = '\0'; - str[0] = static_cast(code_point); // 0xxxxxxx - } else if (code_point <= kMaxCodePoint2) { - str[2] = '\0'; - str[1] = static_cast(0x80 | ChopLowBits(&code_point, 6)); // 10xxxxxx - str[0] = static_cast(0xC0 | code_point); // 110xxxxx - } else if (code_point <= kMaxCodePoint3) { - str[3] = '\0'; - str[2] = static_cast(0x80 | ChopLowBits(&code_point, 6)); // 10xxxxxx - str[1] = static_cast(0x80 | ChopLowBits(&code_point, 6)); // 10xxxxxx - str[0] = static_cast(0xE0 | code_point); // 1110xxxx - } else { // code_point <= kMaxCodePoint4 - str[4] = '\0'; - str[3] = static_cast(0x80 | ChopLowBits(&code_point, 6)); // 10xxxxxx - str[2] = static_cast(0x80 | ChopLowBits(&code_point, 6)); // 10xxxxxx - str[1] = static_cast(0x80 | ChopLowBits(&code_point, 6)); // 10xxxxxx - str[0] = static_cast(0xF0 | code_point); // 11110xxx - } - return str; -} - -// The following two functions only make sense if the the system -// uses UTF-16 for wide string encoding. All supported systems -// with 16 bit wchar_t (Windows, Cygwin, Symbian OS) do use UTF-16. - -// Determines if the arguments constitute UTF-16 surrogate pair -// and thus should be combined into a single Unicode code point -// using CreateCodePointFromUtf16SurrogatePair. -inline bool IsUtf16SurrogatePair(wchar_t first, wchar_t second) { - return sizeof(wchar_t) == 2 && - (first & 0xFC00) == 0xD800 && (second & 0xFC00) == 0xDC00; -} - -// Creates a Unicode code point from UTF16 surrogate pair. -inline UInt32 CreateCodePointFromUtf16SurrogatePair(wchar_t first, - wchar_t second) { - const UInt32 mask = (1 << 10) - 1; - return (sizeof(wchar_t) == 2) ? - (((first & mask) << 10) | (second & mask)) + 0x10000 : - // This function should not be called when the condition is - // false, but we provide a sensible default in case it is. - static_cast(first); -} - -// Converts a wide string to a narrow string in UTF-8 encoding. -// The wide string is assumed to have the following encoding: -// UTF-16 if sizeof(wchar_t) == 2 (on Windows, Cygwin, Symbian OS) -// UTF-32 if sizeof(wchar_t) == 4 (on Linux) -// Parameter str points to a null-terminated wide string. -// Parameter num_chars may additionally limit the number -// of wchar_t characters processed. -1 is used when the entire string -// should be processed. -// If the string contains code points that are not valid Unicode code points -// (i.e. outside of Unicode range U+0 to U+10FFFF) they will be output -// as '(Invalid Unicode 0xXXXXXXXX)'. If the string is in UTF16 encoding -// and contains invalid UTF-16 surrogate pairs, values in those pairs -// will be encoded as individual Unicode characters from Basic Normal Plane. -std::string WideStringToUtf8(const wchar_t* str, int num_chars) { - if (num_chars == -1) - num_chars = static_cast(wcslen(str)); - - ::std::stringstream stream; - for (int i = 0; i < num_chars; ++i) { - UInt32 unicode_code_point; - - if (str[i] == L'\0') { - break; - } else if (i + 1 < num_chars && IsUtf16SurrogatePair(str[i], str[i + 1])) { - unicode_code_point = CreateCodePointFromUtf16SurrogatePair(str[i], - str[i + 1]); - i++; - } else { - unicode_code_point = static_cast(str[i]); - } - - stream << CodePointToUtf8(unicode_code_point); - } - return StringStreamToString(&stream); -} - -// Converts a wide C string to an std::string using the UTF-8 encoding. -// NULL will be converted to "(null)". -std::string String::ShowWideCString(const wchar_t * wide_c_str) { - if (wide_c_str == NULL) return "(null)"; - - return internal::WideStringToUtf8(wide_c_str, -1); -} - -// Compares two wide C strings. Returns true iff they have the same -// content. -// -// Unlike wcscmp(), this function can handle NULL argument(s). A NULL -// C string is considered different to any non-NULL C string, -// including the empty string. -bool String::WideCStringEquals(const wchar_t * lhs, const wchar_t * rhs) { - if (lhs == NULL) return rhs == NULL; - - if (rhs == NULL) return false; - - return wcscmp(lhs, rhs) == 0; -} - -// Helper function for *_STREQ on wide strings. -AssertionResult CmpHelperSTREQ(const char* expected_expression, - const char* actual_expression, - const wchar_t* expected, - const wchar_t* actual) { - if (String::WideCStringEquals(expected, actual)) { - return AssertionSuccess(); - } - - return EqFailure(expected_expression, - actual_expression, - PrintToString(expected), - PrintToString(actual), - false); -} - -// Helper function for *_STRNE on wide strings. -AssertionResult CmpHelperSTRNE(const char* s1_expression, - const char* s2_expression, - const wchar_t* s1, - const wchar_t* s2) { - if (!String::WideCStringEquals(s1, s2)) { - return AssertionSuccess(); - } - - return AssertionFailure() << "Expected: (" << s1_expression << ") != (" - << s2_expression << "), actual: " - << PrintToString(s1) - << " vs " << PrintToString(s2); -} - -// Compares two C strings, ignoring case. Returns true iff they have -// the same content. -// -// Unlike strcasecmp(), this function can handle NULL argument(s). A -// NULL C string is considered different to any non-NULL C string, -// including the empty string. -bool String::CaseInsensitiveCStringEquals(const char * lhs, const char * rhs) { - if (lhs == NULL) - return rhs == NULL; - if (rhs == NULL) - return false; - return posix::StrCaseCmp(lhs, rhs) == 0; -} - - // Compares two wide C strings, ignoring case. Returns true iff they - // have the same content. - // - // Unlike wcscasecmp(), this function can handle NULL argument(s). - // A NULL C string is considered different to any non-NULL wide C string, - // including the empty string. - // NB: The implementations on different platforms slightly differ. - // On windows, this method uses _wcsicmp which compares according to LC_CTYPE - // environment variable. On GNU platform this method uses wcscasecmp - // which compares according to LC_CTYPE category of the current locale. - // On MacOS X, it uses towlower, which also uses LC_CTYPE category of the - // current locale. -bool String::CaseInsensitiveWideCStringEquals(const wchar_t* lhs, - const wchar_t* rhs) { - if (lhs == NULL) return rhs == NULL; - - if (rhs == NULL) return false; - -#if GTEST_OS_WINDOWS - return _wcsicmp(lhs, rhs) == 0; -#elif GTEST_OS_LINUX && !GTEST_OS_LINUX_ANDROID - return wcscasecmp(lhs, rhs) == 0; -#else - // Android, Mac OS X and Cygwin don't define wcscasecmp. - // Other unknown OSes may not define it either. - wint_t left, right; - do { - left = towlower(*lhs++); - right = towlower(*rhs++); - } while (left && left == right); - return left == right; -#endif // OS selector -} - -// Returns true iff str ends with the given suffix, ignoring case. -// Any string is considered to end with an empty suffix. -bool String::EndsWithCaseInsensitive( - const std::string& str, const std::string& suffix) { - const size_t str_len = str.length(); - const size_t suffix_len = suffix.length(); - return (str_len >= suffix_len) && - CaseInsensitiveCStringEquals(str.c_str() + str_len - suffix_len, - suffix.c_str()); -} - -// Formats an int value as "%02d". -std::string String::FormatIntWidth2(int value) { - std::stringstream ss; - ss << std::setfill('0') << std::setw(2) << value; - return ss.str(); -} - -// Formats an int value as "%X". -std::string String::FormatHexInt(int value) { - std::stringstream ss; - ss << std::hex << std::uppercase << value; - return ss.str(); -} - -// Formats a byte as "%02X". -std::string String::FormatByte(unsigned char value) { - std::stringstream ss; - ss << std::setfill('0') << std::setw(2) << std::hex << std::uppercase - << static_cast(value); - return ss.str(); -} - -// Converts the buffer in a stringstream to an std::string, converting NUL -// bytes to "\\0" along the way. -std::string StringStreamToString(::std::stringstream* ss) { - const ::std::string& str = ss->str(); - const char* const start = str.c_str(); - const char* const end = start + str.length(); - - std::string result; - result.reserve(2 * (end - start)); - for (const char* ch = start; ch != end; ++ch) { - if (*ch == '\0') { - result += "\\0"; // Replaces NUL with "\\0"; - } else { - result += *ch; - } - } - - return result; -} - -// Appends the user-supplied message to the Google-Test-generated message. -std::string AppendUserMessage(const std::string& gtest_msg, - const Message& user_msg) { - // Appends the user message if it's non-empty. - const std::string user_msg_string = user_msg.GetString(); - if (user_msg_string.empty()) { - return gtest_msg; - } - - return gtest_msg + "\n" + user_msg_string; -} - -} // namespace internal - -// class TestResult - -// Creates an empty TestResult. -TestResult::TestResult() - : death_test_count_(0), - elapsed_time_(0) { -} - -// D'tor. -TestResult::~TestResult() { -} - -// Returns the i-th test part result among all the results. i can -// range from 0 to total_part_count() - 1. If i is not in that range, -// aborts the program. -const TestPartResult& TestResult::GetTestPartResult(int i) const { - if (i < 0 || i >= total_part_count()) - internal::posix::Abort(); - return test_part_results_.at(i); -} - -// Returns the i-th test property. i can range from 0 to -// test_property_count() - 1. If i is not in that range, aborts the -// program. -const TestProperty& TestResult::GetTestProperty(int i) const { - if (i < 0 || i >= test_property_count()) - internal::posix::Abort(); - return test_properties_.at(i); -} - -// Clears the test part results. -void TestResult::ClearTestPartResults() { - test_part_results_.clear(); -} - -// Adds a test part result to the list. -void TestResult::AddTestPartResult(const TestPartResult& test_part_result) { - test_part_results_.push_back(test_part_result); -} - -// Adds a test property to the list. If a property with the same key as the -// supplied property is already represented, the value of this test_property -// replaces the old value for that key. -void TestResult::RecordProperty(const std::string& xml_element, - const TestProperty& test_property) { - if (!ValidateTestProperty(xml_element, test_property)) { - return; - } - internal::MutexLock lock(&test_properites_mutex_); - const std::vector::iterator property_with_matching_key = - std::find_if(test_properties_.begin(), test_properties_.end(), - internal::TestPropertyKeyIs(test_property.key())); - if (property_with_matching_key == test_properties_.end()) { - test_properties_.push_back(test_property); - return; - } - property_with_matching_key->SetValue(test_property.value()); -} - -// The list of reserved attributes used in the element of XML -// output. -static const char* const kReservedTestSuitesAttributes[] = { - "disabled", - "errors", - "failures", - "name", - "random_seed", - "tests", - "time", - "timestamp" -}; - -// The list of reserved attributes used in the element of XML -// output. -static const char* const kReservedTestSuiteAttributes[] = { - "disabled", - "errors", - "failures", - "name", - "tests", - "time" -}; - -// The list of reserved attributes used in the element of XML output. -static const char* const kReservedTestCaseAttributes[] = { - "classname", - "name", - "status", - "time", - "type_param", - "value_param" -}; - -template -std::vector ArrayAsVector(const char* const (&array)[kSize]) { - return std::vector(array, array + kSize); -} - -static std::vector GetReservedAttributesForElement( - const std::string& xml_element) { - if (xml_element == "testsuites") { - return ArrayAsVector(kReservedTestSuitesAttributes); - } else if (xml_element == "testsuite") { - return ArrayAsVector(kReservedTestSuiteAttributes); - } else if (xml_element == "testcase") { - return ArrayAsVector(kReservedTestCaseAttributes); - } else { - GTEST_CHECK_(false) << "Unrecognized xml_element provided: " << xml_element; - } - // This code is unreachable but some compilers may not realizes that. - return std::vector(); -} - -static std::string FormatWordList(const std::vector& words) { - Message word_list; - for (size_t i = 0; i < words.size(); ++i) { - if (i > 0 && words.size() > 2) { - word_list << ", "; - } - if (i == words.size() - 1) { - word_list << "and "; - } - word_list << "'" << words[i] << "'"; - } - return word_list.GetString(); -} - -bool ValidateTestPropertyName(const std::string& property_name, - const std::vector& reserved_names) { - if (std::find(reserved_names.begin(), reserved_names.end(), property_name) != - reserved_names.end()) { - ADD_FAILURE() << "Reserved key used in RecordProperty(): " << property_name - << " (" << FormatWordList(reserved_names) - << " are reserved by " << GTEST_NAME_ << ")"; - return false; - } - return true; -} - -// Adds a failure if the key is a reserved attribute of the element named -// xml_element. Returns true if the property is valid. -bool TestResult::ValidateTestProperty(const std::string& xml_element, - const TestProperty& test_property) { - return ValidateTestPropertyName(test_property.key(), - GetReservedAttributesForElement(xml_element)); -} - -// Clears the object. -void TestResult::Clear() { - test_part_results_.clear(); - test_properties_.clear(); - death_test_count_ = 0; - elapsed_time_ = 0; -} - -// Returns true iff the test failed. -bool TestResult::Failed() const { - for (int i = 0; i < total_part_count(); ++i) { - if (GetTestPartResult(i).failed()) - return true; - } - return false; -} - -// Returns true iff the test part fatally failed. -static bool TestPartFatallyFailed(const TestPartResult& result) { - return result.fatally_failed(); -} - -// Returns true iff the test fatally failed. -bool TestResult::HasFatalFailure() const { - return CountIf(test_part_results_, TestPartFatallyFailed) > 0; -} - -// Returns true iff the test part non-fatally failed. -static bool TestPartNonfatallyFailed(const TestPartResult& result) { - return result.nonfatally_failed(); -} - -// Returns true iff the test has a non-fatal failure. -bool TestResult::HasNonfatalFailure() const { - return CountIf(test_part_results_, TestPartNonfatallyFailed) > 0; -} - -// Gets the number of all test parts. This is the sum of the number -// of successful test parts and the number of failed test parts. -int TestResult::total_part_count() const { - return static_cast(test_part_results_.size()); -} - -// Returns the number of the test properties. -int TestResult::test_property_count() const { - return static_cast(test_properties_.size()); -} - -// class Test - -// Creates a Test object. - -// The c'tor saves the values of all Google Test flags. -Test::Test() - : gtest_flag_saver_(new internal::GTestFlagSaver) { -} - -// The d'tor restores the values of all Google Test flags. -Test::~Test() { - delete gtest_flag_saver_; -} - -// Sets up the test fixture. -// -// A sub-class may override this. -void Test::SetUp() { -} - -// Tears down the test fixture. -// -// A sub-class may override this. -void Test::TearDown() { -} - -// Allows user supplied key value pairs to be recorded for later output. -void Test::RecordProperty(const std::string& key, const std::string& value) { - UnitTest::GetInstance()->RecordProperty(key, value); -} - -// Allows user supplied key value pairs to be recorded for later output. -void Test::RecordProperty(const std::string& key, int value) { - Message value_message; - value_message << value; - RecordProperty(key, value_message.GetString().c_str()); -} - -namespace internal { - -void ReportFailureInUnknownLocation(TestPartResult::Type result_type, - const std::string& message) { - // This function is a friend of UnitTest and as such has access to - // AddTestPartResult. - UnitTest::GetInstance()->AddTestPartResult( - result_type, - NULL, // No info about the source file where the exception occurred. - -1, // We have no info on which line caused the exception. - message, - ""); // No stack trace, either. -} - -} // namespace internal - -// Google Test requires all tests in the same test case to use the same test -// fixture class. This function checks if the current test has the -// same fixture class as the first test in the current test case. If -// yes, it returns true; otherwise it generates a Google Test failure and -// returns false. -bool Test::HasSameFixtureClass() { - internal::UnitTestImpl* const impl = internal::GetUnitTestImpl(); - const TestCase* const test_case = impl->current_test_case(); - - // Info about the first test in the current test case. - const TestInfo* const first_test_info = test_case->test_info_list()[0]; - const internal::TypeId first_fixture_id = first_test_info->fixture_class_id_; - const char* const first_test_name = first_test_info->name(); - - // Info about the current test. - const TestInfo* const this_test_info = impl->current_test_info(); - const internal::TypeId this_fixture_id = this_test_info->fixture_class_id_; - const char* const this_test_name = this_test_info->name(); - - if (this_fixture_id != first_fixture_id) { - // Is the first test defined using TEST? - const bool first_is_TEST = first_fixture_id == internal::GetTestTypeId(); - // Is this test defined using TEST? - const bool this_is_TEST = this_fixture_id == internal::GetTestTypeId(); - - if (first_is_TEST || this_is_TEST) { - // The user mixed TEST and TEST_F in this test case - we'll tell - // him/her how to fix it. - - // Gets the name of the TEST and the name of the TEST_F. Note - // that first_is_TEST and this_is_TEST cannot both be true, as - // the fixture IDs are different for the two tests. - const char* const TEST_name = - first_is_TEST ? first_test_name : this_test_name; - const char* const TEST_F_name = - first_is_TEST ? this_test_name : first_test_name; - - ADD_FAILURE() - << "All tests in the same test case must use the same test fixture\n" - << "class, so mixing TEST_F and TEST in the same test case is\n" - << "illegal. In test case " << this_test_info->test_case_name() - << ",\n" - << "test " << TEST_F_name << " is defined using TEST_F but\n" - << "test " << TEST_name << " is defined using TEST. You probably\n" - << "want to change the TEST to TEST_F or move it to another test\n" - << "case."; - } else { - // The user defined two fixture classes with the same name in - // two namespaces - we'll tell him/her how to fix it. - ADD_FAILURE() - << "All tests in the same test case must use the same test fixture\n" - << "class. However, in test case " - << this_test_info->test_case_name() << ",\n" - << "you defined test " << first_test_name - << " and test " << this_test_name << "\n" - << "using two different test fixture classes. This can happen if\n" - << "the two classes are from different namespaces or translation\n" - << "units and have the same name. You should probably rename one\n" - << "of the classes to put the tests into different test cases."; - } - return false; - } - - return true; -} - -#if GTEST_HAS_SEH - -// Adds an "exception thrown" fatal failure to the current test. This -// function returns its result via an output parameter pointer because VC++ -// prohibits creation of objects with destructors on stack in functions -// using __try (see error C2712). -static std::string* FormatSehExceptionMessage(DWORD exception_code, - const char* location) { - Message message; - message << "SEH exception with code 0x" << std::setbase(16) << - exception_code << std::setbase(10) << " thrown in " << location << "."; - - return new std::string(message.GetString()); -} - -#endif // GTEST_HAS_SEH - -namespace internal { - -#if GTEST_HAS_EXCEPTIONS - -// Adds an "exception thrown" fatal failure to the current test. -static std::string FormatCxxExceptionMessage(const char* description, - const char* location) { - Message message; - if (description != NULL) { - message << "C++ exception with description \"" << description << "\""; - } else { - message << "Unknown C++ exception"; - } - message << " thrown in " << location << "."; - - return message.GetString(); -} - -static std::string PrintTestPartResultToString( - const TestPartResult& test_part_result); - -GoogleTestFailureException::GoogleTestFailureException( - const TestPartResult& failure) - : ::std::runtime_error(PrintTestPartResultToString(failure).c_str()) {} - -#endif // GTEST_HAS_EXCEPTIONS - -// We put these helper functions in the internal namespace as IBM's xlC -// compiler rejects the code if they were declared static. - -// Runs the given method and handles SEH exceptions it throws, when -// SEH is supported; returns the 0-value for type Result in case of an -// SEH exception. (Microsoft compilers cannot handle SEH and C++ -// exceptions in the same function. Therefore, we provide a separate -// wrapper function for handling SEH exceptions.) -template -Result HandleSehExceptionsInMethodIfSupported( - T* object, Result (T::*method)(), const char* location) { -#if GTEST_HAS_SEH - __try { - return (object->*method)(); - } __except (internal::UnitTestOptions::GTestShouldProcessSEH( // NOLINT - GetExceptionCode())) { - // We create the exception message on the heap because VC++ prohibits - // creation of objects with destructors on stack in functions using __try - // (see error C2712). - std::string* exception_message = FormatSehExceptionMessage( - GetExceptionCode(), location); - internal::ReportFailureInUnknownLocation(TestPartResult::kFatalFailure, - *exception_message); - delete exception_message; - return static_cast(0); - } -#else - (void)location; - return (object->*method)(); -#endif // GTEST_HAS_SEH -} - -// Runs the given method and catches and reports C++ and/or SEH-style -// exceptions, if they are supported; returns the 0-value for type -// Result in case of an SEH exception. -template -Result HandleExceptionsInMethodIfSupported( - T* object, Result (T::*method)(), const char* location) { - // NOTE: The user code can affect the way in which Google Test handles - // exceptions by setting GTEST_FLAG(catch_exceptions), but only before - // RUN_ALL_TESTS() starts. It is technically possible to check the flag - // after the exception is caught and either report or re-throw the - // exception based on the flag's value: - // - // try { - // // Perform the test method. - // } catch (...) { - // if (GTEST_FLAG(catch_exceptions)) - // // Report the exception as failure. - // else - // throw; // Re-throws the original exception. - // } - // - // However, the purpose of this flag is to allow the program to drop into - // the debugger when the exception is thrown. On most platforms, once the - // control enters the catch block, the exception origin information is - // lost and the debugger will stop the program at the point of the - // re-throw in this function -- instead of at the point of the original - // throw statement in the code under test. For this reason, we perform - // the check early, sacrificing the ability to affect Google Test's - // exception handling in the method where the exception is thrown. - if (internal::GetUnitTestImpl()->catch_exceptions()) { -#if GTEST_HAS_EXCEPTIONS - try { - return HandleSehExceptionsInMethodIfSupported(object, method, location); - } catch (const internal::GoogleTestFailureException&) { // NOLINT - // This exception type can only be thrown by a failed Google - // Test assertion with the intention of letting another testing - // framework catch it. Therefore we just re-throw it. - throw; - } catch (const std::exception& e) { // NOLINT - internal::ReportFailureInUnknownLocation( - TestPartResult::kFatalFailure, - FormatCxxExceptionMessage(e.what(), location)); - } catch (...) { // NOLINT - internal::ReportFailureInUnknownLocation( - TestPartResult::kFatalFailure, - FormatCxxExceptionMessage(NULL, location)); - } - return static_cast(0); -#else - return HandleSehExceptionsInMethodIfSupported(object, method, location); -#endif // GTEST_HAS_EXCEPTIONS - } else { - return (object->*method)(); - } -} - -} // namespace internal - -// Runs the test and updates the test result. -void Test::Run() { - if (!HasSameFixtureClass()) return; - - internal::UnitTestImpl* const impl = internal::GetUnitTestImpl(); - impl->os_stack_trace_getter()->UponLeavingGTest(); - internal::HandleExceptionsInMethodIfSupported(this, &Test::SetUp, "SetUp()"); - // We will run the test only if SetUp() was successful. - if (!HasFatalFailure()) { - impl->os_stack_trace_getter()->UponLeavingGTest(); - internal::HandleExceptionsInMethodIfSupported( - this, &Test::TestBody, "the test body"); - } - - // However, we want to clean up as much as possible. Hence we will - // always call TearDown(), even if SetUp() or the test body has - // failed. - impl->os_stack_trace_getter()->UponLeavingGTest(); - internal::HandleExceptionsInMethodIfSupported( - this, &Test::TearDown, "TearDown()"); -} - -// Returns true iff the current test has a fatal failure. -bool Test::HasFatalFailure() { - return internal::GetUnitTestImpl()->current_test_result()->HasFatalFailure(); -} - -// Returns true iff the current test has a non-fatal failure. -bool Test::HasNonfatalFailure() { - return internal::GetUnitTestImpl()->current_test_result()-> - HasNonfatalFailure(); -} - -// class TestInfo - -// Constructs a TestInfo object. It assumes ownership of the test factory -// object. -TestInfo::TestInfo(const std::string& a_test_case_name, - const std::string& a_name, - const char* a_type_param, - const char* a_value_param, - internal::TypeId fixture_class_id, - internal::TestFactoryBase* factory) - : test_case_name_(a_test_case_name), - name_(a_name), - type_param_(a_type_param ? new std::string(a_type_param) : NULL), - value_param_(a_value_param ? new std::string(a_value_param) : NULL), - fixture_class_id_(fixture_class_id), - should_run_(false), - is_disabled_(false), - matches_filter_(false), - factory_(factory), - result_() {} - -// Destructs a TestInfo object. -TestInfo::~TestInfo() { delete factory_; } - -namespace internal { - -// Creates a new TestInfo object and registers it with Google Test; -// returns the created object. -// -// Arguments: -// -// test_case_name: name of the test case -// name: name of the test -// type_param: the name of the test's type parameter, or NULL if -// this is not a typed or a type-parameterized test. -// value_param: text representation of the test's value parameter, -// or NULL if this is not a value-parameterized test. -// fixture_class_id: ID of the test fixture class -// set_up_tc: pointer to the function that sets up the test case -// tear_down_tc: pointer to the function that tears down the test case -// factory: pointer to the factory that creates a test object. -// The newly created TestInfo instance will assume -// ownership of the factory object. -TestInfo* MakeAndRegisterTestInfo( - const char* test_case_name, - const char* name, - const char* type_param, - const char* value_param, - TypeId fixture_class_id, - SetUpTestCaseFunc set_up_tc, - TearDownTestCaseFunc tear_down_tc, - TestFactoryBase* factory) { - TestInfo* const test_info = - new TestInfo(test_case_name, name, type_param, value_param, - fixture_class_id, factory); - GetUnitTestImpl()->AddTestInfo(set_up_tc, tear_down_tc, test_info); - return test_info; -} - -#if GTEST_HAS_PARAM_TEST -void ReportInvalidTestCaseType(const char* test_case_name, - const char* file, int line) { - Message errors; - errors - << "Attempted redefinition of test case " << test_case_name << ".\n" - << "All tests in the same test case must use the same test fixture\n" - << "class. However, in test case " << test_case_name << ", you tried\n" - << "to define a test using a fixture class different from the one\n" - << "used earlier. This can happen if the two fixture classes are\n" - << "from different namespaces and have the same name. You should\n" - << "probably rename one of the classes to put the tests into different\n" - << "test cases."; - - fprintf(stderr, "%s %s", FormatFileLocation(file, line).c_str(), - errors.GetString().c_str()); -} -#endif // GTEST_HAS_PARAM_TEST - -} // namespace internal - -namespace { - -// A predicate that checks the test name of a TestInfo against a known -// value. -// -// This is used for implementation of the TestCase class only. We put -// it in the anonymous namespace to prevent polluting the outer -// namespace. -// -// TestNameIs is copyable. -class TestNameIs { - public: - // Constructor. - // - // TestNameIs has NO default constructor. - explicit TestNameIs(const char* name) - : name_(name) {} - - // Returns true iff the test name of test_info matches name_. - bool operator()(const TestInfo * test_info) const { - return test_info && test_info->name() == name_; - } - - private: - std::string name_; -}; - -} // namespace - -namespace internal { - -// This method expands all parameterized tests registered with macros TEST_P -// and INSTANTIATE_TEST_CASE_P into regular tests and registers those. -// This will be done just once during the program runtime. -void UnitTestImpl::RegisterParameterizedTests() { -#if GTEST_HAS_PARAM_TEST - if (!parameterized_tests_registered_) { - parameterized_test_registry_.RegisterTests(); - parameterized_tests_registered_ = true; - } -#endif -} - -} // namespace internal - -// Creates the test object, runs it, records its result, and then -// deletes it. -void TestInfo::Run() { - if (!should_run_) return; - - // Tells UnitTest where to store test result. - internal::UnitTestImpl* const impl = internal::GetUnitTestImpl(); - impl->set_current_test_info(this); - - TestEventListener* repeater = UnitTest::GetInstance()->listeners().repeater(); - - // Notifies the unit test event listeners that a test is about to start. - repeater->OnTestStart(*this); - - const TimeInMillis start = internal::GetTimeInMillis(); - - impl->os_stack_trace_getter()->UponLeavingGTest(); - - // Creates the test object. - Test* const test = internal::HandleExceptionsInMethodIfSupported( - factory_, &internal::TestFactoryBase::CreateTest, - "the test fixture's constructor"); - - // Runs the test only if the test object was created and its - // constructor didn't generate a fatal failure. - if ((test != NULL) && !Test::HasFatalFailure()) { - // This doesn't throw as all user code that can throw are wrapped into - // exception handling code. - test->Run(); - } - - // Deletes the test object. - impl->os_stack_trace_getter()->UponLeavingGTest(); - internal::HandleExceptionsInMethodIfSupported( - test, &Test::DeleteSelf_, "the test fixture's destructor"); - - result_.set_elapsed_time(internal::GetTimeInMillis() - start); - - // Notifies the unit test event listener that a test has just finished. - repeater->OnTestEnd(*this); - - // Tells UnitTest to stop associating assertion results to this - // test. - impl->set_current_test_info(NULL); -} - -// class TestCase - -// Gets the number of successful tests in this test case. -int TestCase::successful_test_count() const { - return CountIf(test_info_list_, TestPassed); -} - -// Gets the number of failed tests in this test case. -int TestCase::failed_test_count() const { - return CountIf(test_info_list_, TestFailed); -} - -// Gets the number of disabled tests that will be reported in the XML report. -int TestCase::reportable_disabled_test_count() const { - return CountIf(test_info_list_, TestReportableDisabled); -} - -// Gets the number of disabled tests in this test case. -int TestCase::disabled_test_count() const { - return CountIf(test_info_list_, TestDisabled); -} - -// Gets the number of tests to be printed in the XML report. -int TestCase::reportable_test_count() const { - return CountIf(test_info_list_, TestReportable); -} - -// Get the number of tests in this test case that should run. -int TestCase::test_to_run_count() const { - return CountIf(test_info_list_, ShouldRunTest); -} - -// Gets the number of all tests. -int TestCase::total_test_count() const { - return static_cast(test_info_list_.size()); -} - -// Creates a TestCase with the given name. -// -// Arguments: -// -// name: name of the test case -// a_type_param: the name of the test case's type parameter, or NULL if -// this is not a typed or a type-parameterized test case. -// set_up_tc: pointer to the function that sets up the test case -// tear_down_tc: pointer to the function that tears down the test case -TestCase::TestCase(const char* a_name, const char* a_type_param, - Test::SetUpTestCaseFunc set_up_tc, - Test::TearDownTestCaseFunc tear_down_tc) - : name_(a_name), - type_param_(a_type_param ? new std::string(a_type_param) : NULL), - set_up_tc_(set_up_tc), - tear_down_tc_(tear_down_tc), - should_run_(false), - elapsed_time_(0) { -} - -// Destructor of TestCase. -TestCase::~TestCase() { - // Deletes every Test in the collection. - ForEach(test_info_list_, internal::Delete); -} - -// Returns the i-th test among all the tests. i can range from 0 to -// total_test_count() - 1. If i is not in that range, returns NULL. -const TestInfo* TestCase::GetTestInfo(int i) const { - const int index = GetElementOr(test_indices_, i, -1); - return index < 0 ? NULL : test_info_list_[index]; -} - -// Returns the i-th test among all the tests. i can range from 0 to -// total_test_count() - 1. If i is not in that range, returns NULL. -TestInfo* TestCase::GetMutableTestInfo(int i) { - const int index = GetElementOr(test_indices_, i, -1); - return index < 0 ? NULL : test_info_list_[index]; -} - -// Adds a test to this test case. Will delete the test upon -// destruction of the TestCase object. -void TestCase::AddTestInfo(TestInfo * test_info) { - test_info_list_.push_back(test_info); - test_indices_.push_back(static_cast(test_indices_.size())); -} - -// Runs every test in this TestCase. -void TestCase::Run() { - if (!should_run_) return; - - internal::UnitTestImpl* const impl = internal::GetUnitTestImpl(); - impl->set_current_test_case(this); - - TestEventListener* repeater = UnitTest::GetInstance()->listeners().repeater(); - - repeater->OnTestCaseStart(*this); - impl->os_stack_trace_getter()->UponLeavingGTest(); - internal::HandleExceptionsInMethodIfSupported( - this, &TestCase::RunSetUpTestCase, "SetUpTestCase()"); - - const internal::TimeInMillis start = internal::GetTimeInMillis(); - for (int i = 0; i < total_test_count(); i++) { - GetMutableTestInfo(i)->Run(); - } - elapsed_time_ = internal::GetTimeInMillis() - start; - - impl->os_stack_trace_getter()->UponLeavingGTest(); - internal::HandleExceptionsInMethodIfSupported( - this, &TestCase::RunTearDownTestCase, "TearDownTestCase()"); - - repeater->OnTestCaseEnd(*this); - impl->set_current_test_case(NULL); -} - -// Clears the results of all tests in this test case. -void TestCase::ClearResult() { - ad_hoc_test_result_.Clear(); - ForEach(test_info_list_, TestInfo::ClearTestResult); -} - -// Shuffles the tests in this test case. -void TestCase::ShuffleTests(internal::Random* random) { - Shuffle(random, &test_indices_); -} - -// Restores the test order to before the first shuffle. -void TestCase::UnshuffleTests() { - for (size_t i = 0; i < test_indices_.size(); i++) { - test_indices_[i] = static_cast(i); - } -} - -// Formats a countable noun. Depending on its quantity, either the -// singular form or the plural form is used. e.g. -// -// FormatCountableNoun(1, "formula", "formuli") returns "1 formula". -// FormatCountableNoun(5, "book", "books") returns "5 books". -static std::string FormatCountableNoun(int count, - const char * singular_form, - const char * plural_form) { - return internal::StreamableToString(count) + " " + - (count == 1 ? singular_form : plural_form); -} - -// Formats the count of tests. -static std::string FormatTestCount(int test_count) { - return FormatCountableNoun(test_count, "test", "tests"); -} - -// Formats the count of test cases. -static std::string FormatTestCaseCount(int test_case_count) { - return FormatCountableNoun(test_case_count, "test case", "test cases"); -} - -// Converts a TestPartResult::Type enum to human-friendly string -// representation. Both kNonFatalFailure and kFatalFailure are translated -// to "Failure", as the user usually doesn't care about the difference -// between the two when viewing the test result. -static const char * TestPartResultTypeToString(TestPartResult::Type type) { - switch (type) { - case TestPartResult::kSuccess: - return "Success"; - - case TestPartResult::kNonFatalFailure: - case TestPartResult::kFatalFailure: -#ifdef _MSC_VER - return "error: "; -#else - return "Failure\n"; -#endif - default: - return "Unknown result type"; - } -} - -namespace internal { - -// Prints a TestPartResult to an std::string. -static std::string PrintTestPartResultToString( - const TestPartResult& test_part_result) { - return (Message() - << internal::FormatFileLocation(test_part_result.file_name(), - test_part_result.line_number()) - << " " << TestPartResultTypeToString(test_part_result.type()) - << test_part_result.message()).GetString(); -} - -// Prints a TestPartResult. -static void PrintTestPartResult(const TestPartResult& test_part_result) { - const std::string& result = - PrintTestPartResultToString(test_part_result); - printf("%s\n", result.c_str()); - fflush(stdout); - // If the test program runs in Visual Studio or a debugger, the - // following statements add the test part result message to the Output - // window such that the user can double-click on it to jump to the - // corresponding source code location; otherwise they do nothing. -#if GTEST_OS_WINDOWS && !GTEST_OS_WINDOWS_MOBILE - // We don't call OutputDebugString*() on Windows Mobile, as printing - // to stdout is done by OutputDebugString() there already - we don't - // want the same message printed twice. - ::OutputDebugStringA(result.c_str()); - ::OutputDebugStringA("\n"); -#endif -} - -// class PrettyUnitTestResultPrinter - -enum GTestColor { - COLOR_DEFAULT, - COLOR_RED, - COLOR_GREEN, - COLOR_YELLOW -}; - -#if GTEST_OS_WINDOWS && !GTEST_OS_WINDOWS_MOBILE - -// Returns the character attribute for the given color. -WORD GetColorAttribute(GTestColor color) { - switch (color) { - case COLOR_RED: return FOREGROUND_RED; - case COLOR_GREEN: return FOREGROUND_GREEN; - case COLOR_YELLOW: return FOREGROUND_RED | FOREGROUND_GREEN; - default: return 0; - } -} - -#else - -// Returns the ANSI color code for the given color. COLOR_DEFAULT is -// an invalid input. -const char* GetAnsiColorCode(GTestColor color) { - switch (color) { - case COLOR_RED: return "1"; - case COLOR_GREEN: return "2"; - case COLOR_YELLOW: return "3"; - default: return NULL; - }; -} - -#endif // GTEST_OS_WINDOWS && !GTEST_OS_WINDOWS_MOBILE - -// Returns true iff Google Test should use colors in the output. -bool ShouldUseColor(bool stdout_is_tty) { - const char* const gtest_color = GTEST_FLAG(color).c_str(); - - if (String::CaseInsensitiveCStringEquals(gtest_color, "auto")) { -#if GTEST_OS_WINDOWS - // On Windows the TERM variable is usually not set, but the - // console there does support colors. - return stdout_is_tty; -#else - // On non-Windows platforms, we rely on the TERM variable. - const char* const term = posix::GetEnv("TERM"); - const bool term_supports_color = - String::CStringEquals(term, "xterm") || - String::CStringEquals(term, "xterm-color") || - String::CStringEquals(term, "xterm-256color") || - String::CStringEquals(term, "screen") || - String::CStringEquals(term, "screen-256color") || - String::CStringEquals(term, "linux") || - String::CStringEquals(term, "cygwin"); - return stdout_is_tty && term_supports_color; -#endif // GTEST_OS_WINDOWS - } - - return String::CaseInsensitiveCStringEquals(gtest_color, "yes") || - String::CaseInsensitiveCStringEquals(gtest_color, "true") || - String::CaseInsensitiveCStringEquals(gtest_color, "t") || - String::CStringEquals(gtest_color, "1"); - // We take "yes", "true", "t", and "1" as meaning "yes". If the - // value is neither one of these nor "auto", we treat it as "no" to - // be conservative. -} - -// Helpers for printing colored strings to stdout. Note that on Windows, we -// cannot simply emit special characters and have the terminal change colors. -// This routine must actually emit the characters rather than return a string -// that would be colored when printed, as can be done on Linux. -void ColoredPrintf(GTestColor color, const char* fmt, ...) { - va_list args; - va_start(args, fmt); - -#if GTEST_OS_WINDOWS_MOBILE || GTEST_OS_SYMBIAN || GTEST_OS_ZOS || GTEST_OS_IOS - const bool use_color = false; -#else - static const bool in_color_mode = - ShouldUseColor(posix::IsATTY(posix::FileNo(stdout)) != 0); - const bool use_color = in_color_mode && (color != COLOR_DEFAULT); -#endif // GTEST_OS_WINDOWS_MOBILE || GTEST_OS_SYMBIAN || GTEST_OS_ZOS - // The '!= 0' comparison is necessary to satisfy MSVC 7.1. - - if (!use_color) { - vprintf(fmt, args); - va_end(args); - return; - } - -#if GTEST_OS_WINDOWS && !GTEST_OS_WINDOWS_MOBILE - const HANDLE stdout_handle = GetStdHandle(STD_OUTPUT_HANDLE); - - // Gets the current text color. - CONSOLE_SCREEN_BUFFER_INFO buffer_info; - GetConsoleScreenBufferInfo(stdout_handle, &buffer_info); - const WORD old_color_attrs = buffer_info.wAttributes; - - // We need to flush the stream buffers into the console before each - // SetConsoleTextAttribute call lest it affect the text that is already - // printed but has not yet reached the console. - fflush(stdout); - SetConsoleTextAttribute(stdout_handle, - GetColorAttribute(color) | FOREGROUND_INTENSITY); - vprintf(fmt, args); - - fflush(stdout); - // Restores the text color. - SetConsoleTextAttribute(stdout_handle, old_color_attrs); -#else - printf("\033[0;3%sm", GetAnsiColorCode(color)); - vprintf(fmt, args); - printf("\033[m"); // Resets the terminal to default. -#endif // GTEST_OS_WINDOWS && !GTEST_OS_WINDOWS_MOBILE - va_end(args); -} - -// Text printed in Google Test's text output and --gunit_list_tests -// output to label the type parameter and value parameter for a test. -static const char kTypeParamLabel[] = "TypeParam"; -static const char kValueParamLabel[] = "GetParam()"; - -void PrintFullTestCommentIfPresent(const TestInfo& test_info) { - const char* const type_param = test_info.type_param(); - const char* const value_param = test_info.value_param(); - - if (type_param != NULL || value_param != NULL) { - printf(", where "); - if (type_param != NULL) { - printf("%s = %s", kTypeParamLabel, type_param); - if (value_param != NULL) - printf(" and "); - } - if (value_param != NULL) { - printf("%s = %s", kValueParamLabel, value_param); - } - } -} - -// This class implements the TestEventListener interface. -// -// Class PrettyUnitTestResultPrinter is copyable. -class PrettyUnitTestResultPrinter : public TestEventListener { - public: - PrettyUnitTestResultPrinter() {} - static void PrintTestName(const char * test_case, const char * test) { - printf("%s.%s", test_case, test); - } - - // The following methods override what's in the TestEventListener class. - virtual void OnTestProgramStart(const UnitTest& /*unit_test*/) {} - virtual void OnTestIterationStart(const UnitTest& unit_test, int iteration); - virtual void OnEnvironmentsSetUpStart(const UnitTest& unit_test); - virtual void OnEnvironmentsSetUpEnd(const UnitTest& /*unit_test*/) {} - virtual void OnTestCaseStart(const TestCase& test_case); - virtual void OnTestStart(const TestInfo& test_info); - virtual void OnTestPartResult(const TestPartResult& result); - virtual void OnTestEnd(const TestInfo& test_info); - virtual void OnTestCaseEnd(const TestCase& test_case); - virtual void OnEnvironmentsTearDownStart(const UnitTest& unit_test); - virtual void OnEnvironmentsTearDownEnd(const UnitTest& /*unit_test*/) {} - virtual void OnTestIterationEnd(const UnitTest& unit_test, int iteration); - virtual void OnTestProgramEnd(const UnitTest& /*unit_test*/) {} - - private: - static void PrintFailedTests(const UnitTest& unit_test); -}; - - // Fired before each iteration of tests starts. -void PrettyUnitTestResultPrinter::OnTestIterationStart( - const UnitTest& unit_test, int iteration) { - if (GTEST_FLAG(repeat) != 1) - printf("\nRepeating all tests (iteration %d) . . .\n\n", iteration + 1); - - const char* const filter = GTEST_FLAG(filter).c_str(); - - // Prints the filter if it's not *. This reminds the user that some - // tests may be skipped. - if (!String::CStringEquals(filter, kUniversalFilter)) { - ColoredPrintf(COLOR_YELLOW, - "Note: %s filter = %s\n", GTEST_NAME_, filter); - } - - if (internal::ShouldShard(kTestTotalShards, kTestShardIndex, false)) { - const Int32 shard_index = Int32FromEnvOrDie(kTestShardIndex, -1); - ColoredPrintf(COLOR_YELLOW, - "Note: This is test shard %d of %s.\n", - static_cast(shard_index) + 1, - internal::posix::GetEnv(kTestTotalShards)); - } - - if (GTEST_FLAG(shuffle)) { - ColoredPrintf(COLOR_YELLOW, - "Note: Randomizing tests' orders with a seed of %d .\n", - unit_test.random_seed()); - } - - ColoredPrintf(COLOR_GREEN, "[==========] "); - printf("Running %s from %s.\n", - FormatTestCount(unit_test.test_to_run_count()).c_str(), - FormatTestCaseCount(unit_test.test_case_to_run_count()).c_str()); - fflush(stdout); -} - -void PrettyUnitTestResultPrinter::OnEnvironmentsSetUpStart( - const UnitTest& /*unit_test*/) { - ColoredPrintf(COLOR_GREEN, "[----------] "); - printf("Global test environment set-up.\n"); - fflush(stdout); -} - -void PrettyUnitTestResultPrinter::OnTestCaseStart(const TestCase& test_case) { - const std::string counts = - FormatCountableNoun(test_case.test_to_run_count(), "test", "tests"); - ColoredPrintf(COLOR_GREEN, "[----------] "); - printf("%s from %s", counts.c_str(), test_case.name()); - if (test_case.type_param() == NULL) { - printf("\n"); - } else { - printf(", where %s = %s\n", kTypeParamLabel, test_case.type_param()); - } - fflush(stdout); -} - -void PrettyUnitTestResultPrinter::OnTestStart(const TestInfo& test_info) { - ColoredPrintf(COLOR_GREEN, "[ RUN ] "); - PrintTestName(test_info.test_case_name(), test_info.name()); - printf("\n"); - fflush(stdout); -} - -// Called after an assertion failure. -void PrettyUnitTestResultPrinter::OnTestPartResult( - const TestPartResult& result) { - // If the test part succeeded, we don't need to do anything. - if (result.type() == TestPartResult::kSuccess) - return; - - // Print failure message from the assertion (e.g. expected this and got that). - PrintTestPartResult(result); - fflush(stdout); -} - -void PrettyUnitTestResultPrinter::OnTestEnd(const TestInfo& test_info) { - if (test_info.result()->Passed()) { - ColoredPrintf(COLOR_GREEN, "[ OK ] "); - } else { - ColoredPrintf(COLOR_RED, "[ FAILED ] "); - } - PrintTestName(test_info.test_case_name(), test_info.name()); - if (test_info.result()->Failed()) - PrintFullTestCommentIfPresent(test_info); - - if (GTEST_FLAG(print_time)) { - printf(" (%s ms)\n", internal::StreamableToString( - test_info.result()->elapsed_time()).c_str()); - } else { - printf("\n"); - } - fflush(stdout); -} - -void PrettyUnitTestResultPrinter::OnTestCaseEnd(const TestCase& test_case) { - if (!GTEST_FLAG(print_time)) return; - - const std::string counts = - FormatCountableNoun(test_case.test_to_run_count(), "test", "tests"); - ColoredPrintf(COLOR_GREEN, "[----------] "); - printf("%s from %s (%s ms total)\n\n", - counts.c_str(), test_case.name(), - internal::StreamableToString(test_case.elapsed_time()).c_str()); - fflush(stdout); -} - -void PrettyUnitTestResultPrinter::OnEnvironmentsTearDownStart( - const UnitTest& /*unit_test*/) { - ColoredPrintf(COLOR_GREEN, "[----------] "); - printf("Global test environment tear-down\n"); - fflush(stdout); -} - -// Internal helper for printing the list of failed tests. -void PrettyUnitTestResultPrinter::PrintFailedTests(const UnitTest& unit_test) { - const int failed_test_count = unit_test.failed_test_count(); - if (failed_test_count == 0) { - return; - } - - for (int i = 0; i < unit_test.total_test_case_count(); ++i) { - const TestCase& test_case = *unit_test.GetTestCase(i); - if (!test_case.should_run() || (test_case.failed_test_count() == 0)) { - continue; - } - for (int j = 0; j < test_case.total_test_count(); ++j) { - const TestInfo& test_info = *test_case.GetTestInfo(j); - if (!test_info.should_run() || test_info.result()->Passed()) { - continue; - } - ColoredPrintf(COLOR_RED, "[ FAILED ] "); - printf("%s.%s", test_case.name(), test_info.name()); - PrintFullTestCommentIfPresent(test_info); - printf("\n"); - } - } -} - -void PrettyUnitTestResultPrinter::OnTestIterationEnd(const UnitTest& unit_test, - int /*iteration*/) { - ColoredPrintf(COLOR_GREEN, "[==========] "); - printf("%s from %s ran.", - FormatTestCount(unit_test.test_to_run_count()).c_str(), - FormatTestCaseCount(unit_test.test_case_to_run_count()).c_str()); - if (GTEST_FLAG(print_time)) { - printf(" (%s ms total)", - internal::StreamableToString(unit_test.elapsed_time()).c_str()); - } - printf("\n"); - ColoredPrintf(COLOR_GREEN, "[ PASSED ] "); - printf("%s.\n", FormatTestCount(unit_test.successful_test_count()).c_str()); - - int num_failures = unit_test.failed_test_count(); - if (!unit_test.Passed()) { - const int failed_test_count = unit_test.failed_test_count(); - ColoredPrintf(COLOR_RED, "[ FAILED ] "); - printf("%s, listed below:\n", FormatTestCount(failed_test_count).c_str()); - PrintFailedTests(unit_test); - printf("\n%2d FAILED %s\n", num_failures, - num_failures == 1 ? "TEST" : "TESTS"); - } - - int num_disabled = unit_test.reportable_disabled_test_count(); - if (num_disabled && !GTEST_FLAG(also_run_disabled_tests)) { - if (!num_failures) { - printf("\n"); // Add a spacer if no FAILURE banner is displayed. - } - ColoredPrintf(COLOR_YELLOW, - " YOU HAVE %d DISABLED %s\n\n", - num_disabled, - num_disabled == 1 ? "TEST" : "TESTS"); - } - // Ensure that Google Test output is printed before, e.g., heapchecker output. - fflush(stdout); -} - -// End PrettyUnitTestResultPrinter - -// class TestEventRepeater -// -// This class forwards events to other event listeners. -class TestEventRepeater : public TestEventListener { - public: - TestEventRepeater() : forwarding_enabled_(true) {} - virtual ~TestEventRepeater(); - void Append(TestEventListener *listener); - TestEventListener* Release(TestEventListener* listener); - - // Controls whether events will be forwarded to listeners_. Set to false - // in death test child processes. - bool forwarding_enabled() const { return forwarding_enabled_; } - void set_forwarding_enabled(bool enable) { forwarding_enabled_ = enable; } - - virtual void OnTestProgramStart(const UnitTest& unit_test); - virtual void OnTestIterationStart(const UnitTest& unit_test, int iteration); - virtual void OnEnvironmentsSetUpStart(const UnitTest& unit_test); - virtual void OnEnvironmentsSetUpEnd(const UnitTest& unit_test); - virtual void OnTestCaseStart(const TestCase& test_case); - virtual void OnTestStart(const TestInfo& test_info); - virtual void OnTestPartResult(const TestPartResult& result); - virtual void OnTestEnd(const TestInfo& test_info); - virtual void OnTestCaseEnd(const TestCase& test_case); - virtual void OnEnvironmentsTearDownStart(const UnitTest& unit_test); - virtual void OnEnvironmentsTearDownEnd(const UnitTest& unit_test); - virtual void OnTestIterationEnd(const UnitTest& unit_test, int iteration); - virtual void OnTestProgramEnd(const UnitTest& unit_test); - - private: - // Controls whether events will be forwarded to listeners_. Set to false - // in death test child processes. - bool forwarding_enabled_; - // The list of listeners that receive events. - std::vector listeners_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(TestEventRepeater); -}; - -TestEventRepeater::~TestEventRepeater() { - ForEach(listeners_, Delete); -} - -void TestEventRepeater::Append(TestEventListener *listener) { - listeners_.push_back(listener); -} - -// TODO(vladl@google.com): Factor the search functionality into Vector::Find. -TestEventListener* TestEventRepeater::Release(TestEventListener *listener) { - for (size_t i = 0; i < listeners_.size(); ++i) { - if (listeners_[i] == listener) { - listeners_.erase(listeners_.begin() + i); - return listener; - } - } - - return NULL; -} - -// Since most methods are very similar, use macros to reduce boilerplate. -// This defines a member that forwards the call to all listeners. -#define GTEST_REPEATER_METHOD_(Name, Type) \ -void TestEventRepeater::Name(const Type& parameter) { \ - if (forwarding_enabled_) { \ - for (size_t i = 0; i < listeners_.size(); i++) { \ - listeners_[i]->Name(parameter); \ - } \ - } \ -} -// This defines a member that forwards the call to all listeners in reverse -// order. -#define GTEST_REVERSE_REPEATER_METHOD_(Name, Type) \ -void TestEventRepeater::Name(const Type& parameter) { \ - if (forwarding_enabled_) { \ - for (int i = static_cast(listeners_.size()) - 1; i >= 0; i--) { \ - listeners_[i]->Name(parameter); \ - } \ - } \ -} - -GTEST_REPEATER_METHOD_(OnTestProgramStart, UnitTest) -GTEST_REPEATER_METHOD_(OnEnvironmentsSetUpStart, UnitTest) -GTEST_REPEATER_METHOD_(OnTestCaseStart, TestCase) -GTEST_REPEATER_METHOD_(OnTestStart, TestInfo) -GTEST_REPEATER_METHOD_(OnTestPartResult, TestPartResult) -GTEST_REPEATER_METHOD_(OnEnvironmentsTearDownStart, UnitTest) -GTEST_REVERSE_REPEATER_METHOD_(OnEnvironmentsSetUpEnd, UnitTest) -GTEST_REVERSE_REPEATER_METHOD_(OnEnvironmentsTearDownEnd, UnitTest) -GTEST_REVERSE_REPEATER_METHOD_(OnTestEnd, TestInfo) -GTEST_REVERSE_REPEATER_METHOD_(OnTestCaseEnd, TestCase) -GTEST_REVERSE_REPEATER_METHOD_(OnTestProgramEnd, UnitTest) - -#undef GTEST_REPEATER_METHOD_ -#undef GTEST_REVERSE_REPEATER_METHOD_ - -void TestEventRepeater::OnTestIterationStart(const UnitTest& unit_test, - int iteration) { - if (forwarding_enabled_) { - for (size_t i = 0; i < listeners_.size(); i++) { - listeners_[i]->OnTestIterationStart(unit_test, iteration); - } - } -} - -void TestEventRepeater::OnTestIterationEnd(const UnitTest& unit_test, - int iteration) { - if (forwarding_enabled_) { - for (int i = static_cast(listeners_.size()) - 1; i >= 0; i--) { - listeners_[i]->OnTestIterationEnd(unit_test, iteration); - } - } -} - -// End TestEventRepeater - -// This class generates an XML output file. -class XmlUnitTestResultPrinter : public EmptyTestEventListener { - public: - explicit XmlUnitTestResultPrinter(const char* output_file); - - virtual void OnTestIterationEnd(const UnitTest& unit_test, int iteration); - - private: - // Is c a whitespace character that is normalized to a space character - // when it appears in an XML attribute value? - static bool IsNormalizableWhitespace(char c) { - return c == 0x9 || c == 0xA || c == 0xD; - } - - // May c appear in a well-formed XML document? - static bool IsValidXmlCharacter(char c) { - return IsNormalizableWhitespace(c) || c >= 0x20; - } - - // Returns an XML-escaped copy of the input string str. If - // is_attribute is true, the text is meant to appear as an attribute - // value, and normalizable whitespace is preserved by replacing it - // with character references. - static std::string EscapeXml(const std::string& str, bool is_attribute); - - // Returns the given string with all characters invalid in XML removed. - static std::string RemoveInvalidXmlCharacters(const std::string& str); - - // Convenience wrapper around EscapeXml when str is an attribute value. - static std::string EscapeXmlAttribute(const std::string& str) { - return EscapeXml(str, true); - } - - // Convenience wrapper around EscapeXml when str is not an attribute value. - static std::string EscapeXmlText(const char* str) { - return EscapeXml(str, false); - } - - // Verifies that the given attribute belongs to the given element and - // streams the attribute as XML. - static void OutputXmlAttribute(std::ostream* stream, - const std::string& element_name, - const std::string& name, - const std::string& value); - - // Streams an XML CDATA section, escaping invalid CDATA sequences as needed. - static void OutputXmlCDataSection(::std::ostream* stream, const char* data); - - // Streams an XML representation of a TestInfo object. - static void OutputXmlTestInfo(::std::ostream* stream, - const char* test_case_name, - const TestInfo& test_info); - - // Prints an XML representation of a TestCase object - static void PrintXmlTestCase(::std::ostream* stream, - const TestCase& test_case); - - // Prints an XML summary of unit_test to output stream out. - static void PrintXmlUnitTest(::std::ostream* stream, - const UnitTest& unit_test); - - // Produces a string representing the test properties in a result as space - // delimited XML attributes based on the property key="value" pairs. - // When the std::string is not empty, it includes a space at the beginning, - // to delimit this attribute from prior attributes. - static std::string TestPropertiesAsXmlAttributes(const TestResult& result); - - // The output file. - const std::string output_file_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(XmlUnitTestResultPrinter); -}; - -// Creates a new XmlUnitTestResultPrinter. -XmlUnitTestResultPrinter::XmlUnitTestResultPrinter(const char* output_file) - : output_file_(output_file) { - if (output_file_.c_str() == NULL || output_file_.empty()) { - fprintf(stderr, "XML output file may not be null\n"); - fflush(stderr); - exit(EXIT_FAILURE); - } -} - -// Called after the unit test ends. -void XmlUnitTestResultPrinter::OnTestIterationEnd(const UnitTest& unit_test, - int /*iteration*/) { - FILE* xmlout = NULL; - FilePath output_file(output_file_); - FilePath output_dir(output_file.RemoveFileName()); - - if (output_dir.CreateDirectoriesRecursively()) { - xmlout = posix::FOpen(output_file_.c_str(), "w"); - } - if (xmlout == NULL) { - // TODO(wan): report the reason of the failure. - // - // We don't do it for now as: - // - // 1. There is no urgent need for it. - // 2. It's a bit involved to make the errno variable thread-safe on - // all three operating systems (Linux, Windows, and Mac OS). - // 3. To interpret the meaning of errno in a thread-safe way, - // we need the strerror_r() function, which is not available on - // Windows. - fprintf(stderr, - "Unable to open file \"%s\"\n", - output_file_.c_str()); - fflush(stderr); - exit(EXIT_FAILURE); - } - std::stringstream stream; - PrintXmlUnitTest(&stream, unit_test); - fprintf(xmlout, "%s", StringStreamToString(&stream).c_str()); - fclose(xmlout); -} - -// Returns an XML-escaped copy of the input string str. If is_attribute -// is true, the text is meant to appear as an attribute value, and -// normalizable whitespace is preserved by replacing it with character -// references. -// -// Invalid XML characters in str, if any, are stripped from the output. -// It is expected that most, if not all, of the text processed by this -// module will consist of ordinary English text. -// If this module is ever modified to produce version 1.1 XML output, -// most invalid characters can be retained using character references. -// TODO(wan): It might be nice to have a minimally invasive, human-readable -// escaping scheme for invalid characters, rather than dropping them. -std::string XmlUnitTestResultPrinter::EscapeXml( - const std::string& str, bool is_attribute) { - Message m; - - for (size_t i = 0; i < str.size(); ++i) { - const char ch = str[i]; - switch (ch) { - case '<': - m << "<"; - break; - case '>': - m << ">"; - break; - case '&': - m << "&"; - break; - case '\'': - if (is_attribute) - m << "'"; - else - m << '\''; - break; - case '"': - if (is_attribute) - m << """; - else - m << '"'; - break; - default: - if (IsValidXmlCharacter(ch)) { - if (is_attribute && IsNormalizableWhitespace(ch)) - m << "&#x" << String::FormatByte(static_cast(ch)) - << ";"; - else - m << ch; - } - break; - } - } - - return m.GetString(); -} - -// Returns the given string with all characters invalid in XML removed. -// Currently invalid characters are dropped from the string. An -// alternative is to replace them with certain characters such as . or ?. -std::string XmlUnitTestResultPrinter::RemoveInvalidXmlCharacters( - const std::string& str) { - std::string output; - output.reserve(str.size()); - for (std::string::const_iterator it = str.begin(); it != str.end(); ++it) - if (IsValidXmlCharacter(*it)) - output.push_back(*it); - - return output; -} - -// The following routines generate an XML representation of a UnitTest -// object. -// -// This is how Google Test concepts map to the DTD: -// -// <-- corresponds to a UnitTest object -// <-- corresponds to a TestCase object -// <-- corresponds to a TestInfo object -// ... -// ... -// ... -// <-- individual assertion failures -// -// -// - -// Formats the given time in milliseconds as seconds. -std::string FormatTimeInMillisAsSeconds(TimeInMillis ms) { - ::std::stringstream ss; - ss << ms/1000.0; - return ss.str(); -} - -// Converts the given epoch time in milliseconds to a date string in the ISO -// 8601 format, without the timezone information. -std::string FormatEpochTimeInMillisAsIso8601(TimeInMillis ms) { - // Using non-reentrant version as localtime_r is not portable. - time_t seconds = static_cast(ms / 1000); -#ifdef _MSC_VER -# pragma warning(push) // Saves the current warning state. -# pragma warning(disable:4996) // Temporarily disables warning 4996 - // (function or variable may be unsafe). - const struct tm* const time_struct = localtime(&seconds); // NOLINT -# pragma warning(pop) // Restores the warning state again. -#else - const struct tm* const time_struct = localtime(&seconds); // NOLINT -#endif - if (time_struct == NULL) - return ""; // Invalid ms value - - // YYYY-MM-DDThh:mm:ss - return StreamableToString(time_struct->tm_year + 1900) + "-" + - String::FormatIntWidth2(time_struct->tm_mon + 1) + "-" + - String::FormatIntWidth2(time_struct->tm_mday) + "T" + - String::FormatIntWidth2(time_struct->tm_hour) + ":" + - String::FormatIntWidth2(time_struct->tm_min) + ":" + - String::FormatIntWidth2(time_struct->tm_sec); -} - -// Streams an XML CDATA section, escaping invalid CDATA sequences as needed. -void XmlUnitTestResultPrinter::OutputXmlCDataSection(::std::ostream* stream, - const char* data) { - const char* segment = data; - *stream << ""); - if (next_segment != NULL) { - stream->write( - segment, static_cast(next_segment - segment)); - *stream << "]]>]]>"); - } else { - *stream << segment; - break; - } - } - *stream << "]]>"; -} - -void XmlUnitTestResultPrinter::OutputXmlAttribute( - std::ostream* stream, - const std::string& element_name, - const std::string& name, - const std::string& value) { - const std::vector& allowed_names = - GetReservedAttributesForElement(element_name); - - GTEST_CHECK_(std::find(allowed_names.begin(), allowed_names.end(), name) != - allowed_names.end()) - << "Attribute " << name << " is not allowed for element <" << element_name - << ">."; - - *stream << " " << name << "=\"" << EscapeXmlAttribute(value) << "\""; -} - -// Prints an XML representation of a TestInfo object. -// TODO(wan): There is also value in printing properties with the plain printer. -void XmlUnitTestResultPrinter::OutputXmlTestInfo(::std::ostream* stream, - const char* test_case_name, - const TestInfo& test_info) { - const TestResult& result = *test_info.result(); - const std::string kTestcase = "testcase"; - - *stream << " \n"; - } - const string location = internal::FormatCompilerIndependentFileLocation( - part.file_name(), part.line_number()); - const string summary = location + "\n" + part.summary(); - *stream << " "; - const string detail = location + "\n" + part.message(); - OutputXmlCDataSection(stream, RemoveInvalidXmlCharacters(detail).c_str()); - *stream << "\n"; - } - } - - if (failures == 0) - *stream << " />\n"; - else - *stream << " \n"; -} - -// Prints an XML representation of a TestCase object -void XmlUnitTestResultPrinter::PrintXmlTestCase(std::ostream* stream, - const TestCase& test_case) { - const std::string kTestsuite = "testsuite"; - *stream << " <" << kTestsuite; - OutputXmlAttribute(stream, kTestsuite, "name", test_case.name()); - OutputXmlAttribute(stream, kTestsuite, "tests", - StreamableToString(test_case.reportable_test_count())); - OutputXmlAttribute(stream, kTestsuite, "failures", - StreamableToString(test_case.failed_test_count())); - OutputXmlAttribute( - stream, kTestsuite, "disabled", - StreamableToString(test_case.reportable_disabled_test_count())); - OutputXmlAttribute(stream, kTestsuite, "errors", "0"); - OutputXmlAttribute(stream, kTestsuite, "time", - FormatTimeInMillisAsSeconds(test_case.elapsed_time())); - *stream << TestPropertiesAsXmlAttributes(test_case.ad_hoc_test_result()) - << ">\n"; - - for (int i = 0; i < test_case.total_test_count(); ++i) { - if (test_case.GetTestInfo(i)->is_reportable()) - OutputXmlTestInfo(stream, test_case.name(), *test_case.GetTestInfo(i)); - } - *stream << " \n"; -} - -// Prints an XML summary of unit_test to output stream out. -void XmlUnitTestResultPrinter::PrintXmlUnitTest(std::ostream* stream, - const UnitTest& unit_test) { - const std::string kTestsuites = "testsuites"; - - *stream << "\n"; - *stream << "<" << kTestsuites; - - OutputXmlAttribute(stream, kTestsuites, "tests", - StreamableToString(unit_test.reportable_test_count())); - OutputXmlAttribute(stream, kTestsuites, "failures", - StreamableToString(unit_test.failed_test_count())); - OutputXmlAttribute( - stream, kTestsuites, "disabled", - StreamableToString(unit_test.reportable_disabled_test_count())); - OutputXmlAttribute(stream, kTestsuites, "errors", "0"); - OutputXmlAttribute( - stream, kTestsuites, "timestamp", - FormatEpochTimeInMillisAsIso8601(unit_test.start_timestamp())); - OutputXmlAttribute(stream, kTestsuites, "time", - FormatTimeInMillisAsSeconds(unit_test.elapsed_time())); - - if (GTEST_FLAG(shuffle)) { - OutputXmlAttribute(stream, kTestsuites, "random_seed", - StreamableToString(unit_test.random_seed())); - } - - *stream << TestPropertiesAsXmlAttributes(unit_test.ad_hoc_test_result()); - - OutputXmlAttribute(stream, kTestsuites, "name", "AllTests"); - *stream << ">\n"; - - for (int i = 0; i < unit_test.total_test_case_count(); ++i) { - if (unit_test.GetTestCase(i)->reportable_test_count() > 0) - PrintXmlTestCase(stream, *unit_test.GetTestCase(i)); - } - *stream << "\n"; -} - -// Produces a string representing the test properties in a result as space -// delimited XML attributes based on the property key="value" pairs. -std::string XmlUnitTestResultPrinter::TestPropertiesAsXmlAttributes( - const TestResult& result) { - Message attributes; - for (int i = 0; i < result.test_property_count(); ++i) { - const TestProperty& property = result.GetTestProperty(i); - attributes << " " << property.key() << "=" - << "\"" << EscapeXmlAttribute(property.value()) << "\""; - } - return attributes.GetString(); -} - -// End XmlUnitTestResultPrinter - -#if GTEST_CAN_STREAM_RESULTS_ - -// Checks if str contains '=', '&', '%' or '\n' characters. If yes, -// replaces them by "%xx" where xx is their hexadecimal value. For -// example, replaces "=" with "%3D". This algorithm is O(strlen(str)) -// in both time and space -- important as the input str may contain an -// arbitrarily long test failure message and stack trace. -string StreamingListener::UrlEncode(const char* str) { - string result; - result.reserve(strlen(str) + 1); - for (char ch = *str; ch != '\0'; ch = *++str) { - switch (ch) { - case '%': - case '=': - case '&': - case '\n': - result.append("%" + String::FormatByte(static_cast(ch))); - break; - default: - result.push_back(ch); - break; - } - } - return result; -} - -void StreamingListener::SocketWriter::MakeConnection() { - GTEST_CHECK_(sockfd_ == -1) - << "MakeConnection() can't be called when there is already a connection."; - - addrinfo hints; - memset(&hints, 0, sizeof(hints)); - hints.ai_family = AF_UNSPEC; // To allow both IPv4 and IPv6 addresses. - hints.ai_socktype = SOCK_STREAM; - addrinfo* servinfo = NULL; - - // Use the getaddrinfo() to get a linked list of IP addresses for - // the given host name. - const int error_num = getaddrinfo( - host_name_.c_str(), port_num_.c_str(), &hints, &servinfo); - if (error_num != 0) { - GTEST_LOG_(WARNING) << "stream_result_to: getaddrinfo() failed: " - << gai_strerror(error_num); - } - - // Loop through all the results and connect to the first we can. - for (addrinfo* cur_addr = servinfo; sockfd_ == -1 && cur_addr != NULL; - cur_addr = cur_addr->ai_next) { - sockfd_ = socket( - cur_addr->ai_family, cur_addr->ai_socktype, cur_addr->ai_protocol); - if (sockfd_ != -1) { - // Connect the client socket to the server socket. - if (connect(sockfd_, cur_addr->ai_addr, cur_addr->ai_addrlen) == -1) { - close(sockfd_); - sockfd_ = -1; - } - } - } - - freeaddrinfo(servinfo); // all done with this structure - - if (sockfd_ == -1) { - GTEST_LOG_(WARNING) << "stream_result_to: failed to connect to " - << host_name_ << ":" << port_num_; - } -} - -// End of class Streaming Listener -#endif // GTEST_CAN_STREAM_RESULTS__ - -// Class ScopedTrace - -// Pushes the given source file location and message onto a per-thread -// trace stack maintained by Google Test. -ScopedTrace::ScopedTrace(const char* file, int line, const Message& message) - GTEST_LOCK_EXCLUDED_(&UnitTest::mutex_) { - TraceInfo trace; - trace.file = file; - trace.line = line; - trace.message = message.GetString(); - - UnitTest::GetInstance()->PushGTestTrace(trace); -} - -// Pops the info pushed by the c'tor. -ScopedTrace::~ScopedTrace() - GTEST_LOCK_EXCLUDED_(&UnitTest::mutex_) { - UnitTest::GetInstance()->PopGTestTrace(); -} - - -// class OsStackTraceGetter - -// Returns the current OS stack trace as an std::string. Parameters: -// -// max_depth - the maximum number of stack frames to be included -// in the trace. -// skip_count - the number of top frames to be skipped; doesn't count -// against max_depth. -// -string OsStackTraceGetter::CurrentStackTrace(int /* max_depth */, - int /* skip_count */) - GTEST_LOCK_EXCLUDED_(mutex_) { - return ""; -} - -void OsStackTraceGetter::UponLeavingGTest() - GTEST_LOCK_EXCLUDED_(mutex_) { -} - -const char* const -OsStackTraceGetter::kElidedFramesMarker = - "... " GTEST_NAME_ " internal frames ..."; - -// A helper class that creates the premature-exit file in its -// constructor and deletes the file in its destructor. -class ScopedPrematureExitFile { - public: - explicit ScopedPrematureExitFile(const char* premature_exit_filepath) - : premature_exit_filepath_(premature_exit_filepath) { - // If a path to the premature-exit file is specified... - if (premature_exit_filepath != NULL && *premature_exit_filepath != '\0') { - // create the file with a single "0" character in it. I/O - // errors are ignored as there's nothing better we can do and we - // don't want to fail the test because of this. - FILE* pfile = posix::FOpen(premature_exit_filepath, "w"); - fwrite("0", 1, 1, pfile); - fclose(pfile); - } - } - - ~ScopedPrematureExitFile() { - if (premature_exit_filepath_ != NULL && *premature_exit_filepath_ != '\0') { - remove(premature_exit_filepath_); - } - } - - private: - const char* const premature_exit_filepath_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(ScopedPrematureExitFile); -}; - -} // namespace internal - -// class TestEventListeners - -TestEventListeners::TestEventListeners() - : repeater_(new internal::TestEventRepeater()), - default_result_printer_(NULL), - default_xml_generator_(NULL) { -} - -TestEventListeners::~TestEventListeners() { delete repeater_; } - -// Returns the standard listener responsible for the default console -// output. Can be removed from the listeners list to shut down default -// console output. Note that removing this object from the listener list -// with Release transfers its ownership to the user. -void TestEventListeners::Append(TestEventListener* listener) { - repeater_->Append(listener); -} - -// Removes the given event listener from the list and returns it. It then -// becomes the caller's responsibility to delete the listener. Returns -// NULL if the listener is not found in the list. -TestEventListener* TestEventListeners::Release(TestEventListener* listener) { - if (listener == default_result_printer_) - default_result_printer_ = NULL; - else if (listener == default_xml_generator_) - default_xml_generator_ = NULL; - return repeater_->Release(listener); -} - -// Returns repeater that broadcasts the TestEventListener events to all -// subscribers. -TestEventListener* TestEventListeners::repeater() { return repeater_; } - -// Sets the default_result_printer attribute to the provided listener. -// The listener is also added to the listener list and previous -// default_result_printer is removed from it and deleted. The listener can -// also be NULL in which case it will not be added to the list. Does -// nothing if the previous and the current listener objects are the same. -void TestEventListeners::SetDefaultResultPrinter(TestEventListener* listener) { - if (default_result_printer_ != listener) { - // It is an error to pass this method a listener that is already in the - // list. - delete Release(default_result_printer_); - default_result_printer_ = listener; - if (listener != NULL) - Append(listener); - } -} - -// Sets the default_xml_generator attribute to the provided listener. The -// listener is also added to the listener list and previous -// default_xml_generator is removed from it and deleted. The listener can -// also be NULL in which case it will not be added to the list. Does -// nothing if the previous and the current listener objects are the same. -void TestEventListeners::SetDefaultXmlGenerator(TestEventListener* listener) { - if (default_xml_generator_ != listener) { - // It is an error to pass this method a listener that is already in the - // list. - delete Release(default_xml_generator_); - default_xml_generator_ = listener; - if (listener != NULL) - Append(listener); - } -} - -// Controls whether events will be forwarded by the repeater to the -// listeners in the list. -bool TestEventListeners::EventForwardingEnabled() const { - return repeater_->forwarding_enabled(); -} - -void TestEventListeners::SuppressEventForwarding() { - repeater_->set_forwarding_enabled(false); -} - -// class UnitTest - -// Gets the singleton UnitTest object. The first time this method is -// called, a UnitTest object is constructed and returned. Consecutive -// calls will return the same object. -// -// We don't protect this under mutex_ as a user is not supposed to -// call this before main() starts, from which point on the return -// value will never change. -UnitTest* UnitTest::GetInstance() { - // When compiled with MSVC 7.1 in optimized mode, destroying the - // UnitTest object upon exiting the program messes up the exit code, - // causing successful tests to appear failed. We have to use a - // different implementation in this case to bypass the compiler bug. - // This implementation makes the compiler happy, at the cost of - // leaking the UnitTest object. - - // CodeGear C++Builder insists on a public destructor for the - // default implementation. Use this implementation to keep good OO - // design with private destructor. - -#if (_MSC_VER == 1310 && !defined(_DEBUG)) || defined(__BORLANDC__) - static UnitTest* const instance = new UnitTest; - return instance; -#else - static UnitTest instance; - return &instance; -#endif // (_MSC_VER == 1310 && !defined(_DEBUG)) || defined(__BORLANDC__) -} - -// Gets the number of successful test cases. -int UnitTest::successful_test_case_count() const { - return impl()->successful_test_case_count(); -} - -// Gets the number of failed test cases. -int UnitTest::failed_test_case_count() const { - return impl()->failed_test_case_count(); -} - -// Gets the number of all test cases. -int UnitTest::total_test_case_count() const { - return impl()->total_test_case_count(); -} - -// Gets the number of all test cases that contain at least one test -// that should run. -int UnitTest::test_case_to_run_count() const { - return impl()->test_case_to_run_count(); -} - -// Gets the number of successful tests. -int UnitTest::successful_test_count() const { - return impl()->successful_test_count(); -} - -// Gets the number of failed tests. -int UnitTest::failed_test_count() const { return impl()->failed_test_count(); } - -// Gets the number of disabled tests that will be reported in the XML report. -int UnitTest::reportable_disabled_test_count() const { - return impl()->reportable_disabled_test_count(); -} - -// Gets the number of disabled tests. -int UnitTest::disabled_test_count() const { - return impl()->disabled_test_count(); -} - -// Gets the number of tests to be printed in the XML report. -int UnitTest::reportable_test_count() const { - return impl()->reportable_test_count(); -} - -// Gets the number of all tests. -int UnitTest::total_test_count() const { return impl()->total_test_count(); } - -// Gets the number of tests that should run. -int UnitTest::test_to_run_count() const { return impl()->test_to_run_count(); } - -// Gets the time of the test program start, in ms from the start of the -// UNIX epoch. -internal::TimeInMillis UnitTest::start_timestamp() const { - return impl()->start_timestamp(); -} - -// Gets the elapsed time, in milliseconds. -internal::TimeInMillis UnitTest::elapsed_time() const { - return impl()->elapsed_time(); -} - -// Returns true iff the unit test passed (i.e. all test cases passed). -bool UnitTest::Passed() const { return impl()->Passed(); } - -// Returns true iff the unit test failed (i.e. some test case failed -// or something outside of all tests failed). -bool UnitTest::Failed() const { return impl()->Failed(); } - -// Gets the i-th test case among all the test cases. i can range from 0 to -// total_test_case_count() - 1. If i is not in that range, returns NULL. -const TestCase* UnitTest::GetTestCase(int i) const { - return impl()->GetTestCase(i); -} - -// Returns the TestResult containing information on test failures and -// properties logged outside of individual test cases. -const TestResult& UnitTest::ad_hoc_test_result() const { - return *impl()->ad_hoc_test_result(); -} - -// Gets the i-th test case among all the test cases. i can range from 0 to -// total_test_case_count() - 1. If i is not in that range, returns NULL. -TestCase* UnitTest::GetMutableTestCase(int i) { - return impl()->GetMutableTestCase(i); -} - -// Returns the list of event listeners that can be used to track events -// inside Google Test. -TestEventListeners& UnitTest::listeners() { - return *impl()->listeners(); -} - -// Registers and returns a global test environment. When a test -// program is run, all global test environments will be set-up in the -// order they were registered. After all tests in the program have -// finished, all global test environments will be torn-down in the -// *reverse* order they were registered. -// -// The UnitTest object takes ownership of the given environment. -// -// We don't protect this under mutex_, as we only support calling it -// from the main thread. -Environment* UnitTest::AddEnvironment(Environment* env) { - if (env == NULL) { - return NULL; - } - - impl_->environments().push_back(env); - return env; -} - -// Adds a TestPartResult to the current TestResult object. All Google Test -// assertion macros (e.g. ASSERT_TRUE, EXPECT_EQ, etc) eventually call -// this to report their results. The user code should use the -// assertion macros instead of calling this directly. -void UnitTest::AddTestPartResult( - TestPartResult::Type result_type, - const char* file_name, - int line_number, - const std::string& message, - const std::string& os_stack_trace) GTEST_LOCK_EXCLUDED_(mutex_) { - Message msg; - msg << message; - - internal::MutexLock lock(&mutex_); - if (impl_->gtest_trace_stack().size() > 0) { - msg << "\n" << GTEST_NAME_ << " trace:"; - - for (int i = static_cast(impl_->gtest_trace_stack().size()); - i > 0; --i) { - const internal::TraceInfo& trace = impl_->gtest_trace_stack()[i - 1]; - msg << "\n" << internal::FormatFileLocation(trace.file, trace.line) - << " " << trace.message; - } - } - - if (os_stack_trace.c_str() != NULL && !os_stack_trace.empty()) { - msg << internal::kStackTraceMarker << os_stack_trace; - } - - const TestPartResult result = - TestPartResult(result_type, file_name, line_number, - msg.GetString().c_str()); - impl_->GetTestPartResultReporterForCurrentThread()-> - ReportTestPartResult(result); - - if (result_type != TestPartResult::kSuccess) { - // gtest_break_on_failure takes precedence over - // gtest_throw_on_failure. This allows a user to set the latter - // in the code (perhaps in order to use Google Test assertions - // with another testing framework) and specify the former on the - // command line for debugging. - if (GTEST_FLAG(break_on_failure)) { -#if GTEST_OS_WINDOWS - // Using DebugBreak on Windows allows gtest to still break into a debugger - // when a failure happens and both the --gtest_break_on_failure and - // the --gtest_catch_exceptions flags are specified. - DebugBreak(); -#else - // Dereference NULL through a volatile pointer to prevent the compiler - // from removing. We use this rather than abort() or __builtin_trap() for - // portability: Symbian doesn't implement abort() well, and some debuggers - // don't correctly trap abort(). - *static_cast(NULL) = 1; -#endif // GTEST_OS_WINDOWS - } else if (GTEST_FLAG(throw_on_failure)) { -#if GTEST_HAS_EXCEPTIONS - throw internal::GoogleTestFailureException(result); -#else - // We cannot call abort() as it generates a pop-up in debug mode - // that cannot be suppressed in VC 7.1 or below. - exit(1); -#endif - } - } -} - -// Adds a TestProperty to the current TestResult object when invoked from -// inside a test, to current TestCase's ad_hoc_test_result_ when invoked -// from SetUpTestCase or TearDownTestCase, or to the global property set -// when invoked elsewhere. If the result already contains a property with -// the same key, the value will be updated. -void UnitTest::RecordProperty(const std::string& key, - const std::string& value) { - impl_->RecordProperty(TestProperty(key, value)); -} - -// Runs all tests in this UnitTest object and prints the result. -// Returns 0 if successful, or 1 otherwise. -// -// We don't protect this under mutex_, as we only support calling it -// from the main thread. -int UnitTest::Run() { - const bool in_death_test_child_process = - internal::GTEST_FLAG(internal_run_death_test).length() > 0; - - // Google Test implements this protocol for catching that a test - // program exits before returning control to Google Test: - // - // 1. Upon start, Google Test creates a file whose absolute path - // is specified by the environment variable - // TEST_PREMATURE_EXIT_FILE. - // 2. When Google Test has finished its work, it deletes the file. - // - // This allows a test runner to set TEST_PREMATURE_EXIT_FILE before - // running a Google-Test-based test program and check the existence - // of the file at the end of the test execution to see if it has - // exited prematurely. - - // If we are in the child process of a death test, don't - // create/delete the premature exit file, as doing so is unnecessary - // and will confuse the parent process. Otherwise, create/delete - // the file upon entering/leaving this function. If the program - // somehow exits before this function has a chance to return, the - // premature-exit file will be left undeleted, causing a test runner - // that understands the premature-exit-file protocol to report the - // test as having failed. - const internal::ScopedPrematureExitFile premature_exit_file( - in_death_test_child_process ? - NULL : internal::posix::GetEnv("TEST_PREMATURE_EXIT_FILE")); - - // Captures the value of GTEST_FLAG(catch_exceptions). This value will be - // used for the duration of the program. - impl()->set_catch_exceptions(GTEST_FLAG(catch_exceptions)); - -#if GTEST_HAS_SEH - // Either the user wants Google Test to catch exceptions thrown by the - // tests or this is executing in the context of death test child - // process. In either case the user does not want to see pop-up dialogs - // about crashes - they are expected. - if (impl()->catch_exceptions() || in_death_test_child_process) { -# if !GTEST_OS_WINDOWS_MOBILE - // SetErrorMode doesn't exist on CE. - SetErrorMode(SEM_FAILCRITICALERRORS | SEM_NOALIGNMENTFAULTEXCEPT | - SEM_NOGPFAULTERRORBOX | SEM_NOOPENFILEERRORBOX); -# endif // !GTEST_OS_WINDOWS_MOBILE - -# if (defined(_MSC_VER) || GTEST_OS_WINDOWS_MINGW) && !GTEST_OS_WINDOWS_MOBILE - // Death test children can be terminated with _abort(). On Windows, - // _abort() can show a dialog with a warning message. This forces the - // abort message to go to stderr instead. - _set_error_mode(_OUT_TO_STDERR); -# endif - -# if _MSC_VER >= 1400 && !GTEST_OS_WINDOWS_MOBILE - // In the debug version, Visual Studio pops up a separate dialog - // offering a choice to debug the aborted program. We need to suppress - // this dialog or it will pop up for every EXPECT/ASSERT_DEATH statement - // executed. Google Test will notify the user of any unexpected - // failure via stderr. - // - // VC++ doesn't define _set_abort_behavior() prior to the version 8.0. - // Users of prior VC versions shall suffer the agony and pain of - // clicking through the countless debug dialogs. - // TODO(vladl@google.com): find a way to suppress the abort dialog() in the - // debug mode when compiled with VC 7.1 or lower. - if (!GTEST_FLAG(break_on_failure)) - _set_abort_behavior( - 0x0, // Clear the following flags: - _WRITE_ABORT_MSG | _CALL_REPORTFAULT); // pop-up window, core dump. -# endif - } -#endif // GTEST_HAS_SEH - - return internal::HandleExceptionsInMethodIfSupported( - impl(), - &internal::UnitTestImpl::RunAllTests, - "auxiliary test code (environments or event listeners)") ? 0 : 1; -} - -// Returns the working directory when the first TEST() or TEST_F() was -// executed. -const char* UnitTest::original_working_dir() const { - return impl_->original_working_dir_.c_str(); -} - -// Returns the TestCase object for the test that's currently running, -// or NULL if no test is running. -const TestCase* UnitTest::current_test_case() const - GTEST_LOCK_EXCLUDED_(mutex_) { - internal::MutexLock lock(&mutex_); - return impl_->current_test_case(); -} - -// Returns the TestInfo object for the test that's currently running, -// or NULL if no test is running. -const TestInfo* UnitTest::current_test_info() const - GTEST_LOCK_EXCLUDED_(mutex_) { - internal::MutexLock lock(&mutex_); - return impl_->current_test_info(); -} - -// Returns the random seed used at the start of the current test run. -int UnitTest::random_seed() const { return impl_->random_seed(); } - -#if GTEST_HAS_PARAM_TEST -// Returns ParameterizedTestCaseRegistry object used to keep track of -// value-parameterized tests and instantiate and register them. -internal::ParameterizedTestCaseRegistry& - UnitTest::parameterized_test_registry() - GTEST_LOCK_EXCLUDED_(mutex_) { - return impl_->parameterized_test_registry(); -} -#endif // GTEST_HAS_PARAM_TEST - -// Creates an empty UnitTest. -UnitTest::UnitTest() { - impl_ = new internal::UnitTestImpl(this); -} - -// Destructor of UnitTest. -UnitTest::~UnitTest() { - delete impl_; -} - -// Pushes a trace defined by SCOPED_TRACE() on to the per-thread -// Google Test trace stack. -void UnitTest::PushGTestTrace(const internal::TraceInfo& trace) - GTEST_LOCK_EXCLUDED_(mutex_) { - internal::MutexLock lock(&mutex_); - impl_->gtest_trace_stack().push_back(trace); -} - -// Pops a trace from the per-thread Google Test trace stack. -void UnitTest::PopGTestTrace() - GTEST_LOCK_EXCLUDED_(mutex_) { - internal::MutexLock lock(&mutex_); - impl_->gtest_trace_stack().pop_back(); -} - -namespace internal { - -UnitTestImpl::UnitTestImpl(UnitTest* parent) - : parent_(parent), -#ifdef _MSC_VER -# pragma warning(push) // Saves the current warning state. -# pragma warning(disable:4355) // Temporarily disables warning 4355 - // (using this in initializer). - default_global_test_part_result_reporter_(this), - default_per_thread_test_part_result_reporter_(this), -# pragma warning(pop) // Restores the warning state again. -#else - default_global_test_part_result_reporter_(this), - default_per_thread_test_part_result_reporter_(this), -#endif // _MSC_VER - global_test_part_result_repoter_( - &default_global_test_part_result_reporter_), - per_thread_test_part_result_reporter_( - &default_per_thread_test_part_result_reporter_), -#if GTEST_HAS_PARAM_TEST - parameterized_test_registry_(), - parameterized_tests_registered_(false), -#endif // GTEST_HAS_PARAM_TEST - last_death_test_case_(-1), - current_test_case_(NULL), - current_test_info_(NULL), - ad_hoc_test_result_(), - os_stack_trace_getter_(NULL), - post_flag_parse_init_performed_(false), - random_seed_(0), // Will be overridden by the flag before first use. - random_(0), // Will be reseeded before first use. - start_timestamp_(0), - elapsed_time_(0), -#if GTEST_HAS_DEATH_TEST - death_test_factory_(new DefaultDeathTestFactory), -#endif - // Will be overridden by the flag before first use. - catch_exceptions_(false) { - listeners()->SetDefaultResultPrinter(new PrettyUnitTestResultPrinter); -} - -UnitTestImpl::~UnitTestImpl() { - // Deletes every TestCase. - ForEach(test_cases_, internal::Delete); - - // Deletes every Environment. - ForEach(environments_, internal::Delete); - - delete os_stack_trace_getter_; -} - -// Adds a TestProperty to the current TestResult object when invoked in a -// context of a test, to current test case's ad_hoc_test_result when invoke -// from SetUpTestCase/TearDownTestCase, or to the global property set -// otherwise. If the result already contains a property with the same key, -// the value will be updated. -void UnitTestImpl::RecordProperty(const TestProperty& test_property) { - std::string xml_element; - TestResult* test_result; // TestResult appropriate for property recording. - - if (current_test_info_ != NULL) { - xml_element = "testcase"; - test_result = &(current_test_info_->result_); - } else if (current_test_case_ != NULL) { - xml_element = "testsuite"; - test_result = &(current_test_case_->ad_hoc_test_result_); - } else { - xml_element = "testsuites"; - test_result = &ad_hoc_test_result_; - } - test_result->RecordProperty(xml_element, test_property); -} - -#if GTEST_HAS_DEATH_TEST -// Disables event forwarding if the control is currently in a death test -// subprocess. Must not be called before InitGoogleTest. -void UnitTestImpl::SuppressTestEventsIfInSubprocess() { - if (internal_run_death_test_flag_.get() != NULL) - listeners()->SuppressEventForwarding(); -} -#endif // GTEST_HAS_DEATH_TEST - -// Initializes event listeners performing XML output as specified by -// UnitTestOptions. Must not be called before InitGoogleTest. -void UnitTestImpl::ConfigureXmlOutput() { - const std::string& output_format = UnitTestOptions::GetOutputFormat(); - if (output_format == "xml") { - listeners()->SetDefaultXmlGenerator(new XmlUnitTestResultPrinter( - UnitTestOptions::GetAbsolutePathToOutputFile().c_str())); - } else if (output_format != "") { - printf("WARNING: unrecognized output format \"%s\" ignored.\n", - output_format.c_str()); - fflush(stdout); - } -} - -#if GTEST_CAN_STREAM_RESULTS_ -// Initializes event listeners for streaming test results in string form. -// Must not be called before InitGoogleTest. -void UnitTestImpl::ConfigureStreamingOutput() { - const std::string& target = GTEST_FLAG(stream_result_to); - if (!target.empty()) { - const size_t pos = target.find(':'); - if (pos != std::string::npos) { - listeners()->Append(new StreamingListener(target.substr(0, pos), - target.substr(pos+1))); - } else { - printf("WARNING: unrecognized streaming target \"%s\" ignored.\n", - target.c_str()); - fflush(stdout); - } - } -} -#endif // GTEST_CAN_STREAM_RESULTS_ - -// Performs initialization dependent upon flag values obtained in -// ParseGoogleTestFlagsOnly. Is called from InitGoogleTest after the call to -// ParseGoogleTestFlagsOnly. In case a user neglects to call InitGoogleTest -// this function is also called from RunAllTests. Since this function can be -// called more than once, it has to be idempotent. -void UnitTestImpl::PostFlagParsingInit() { - // Ensures that this function does not execute more than once. - if (!post_flag_parse_init_performed_) { - post_flag_parse_init_performed_ = true; - -#if GTEST_HAS_DEATH_TEST - InitDeathTestSubprocessControlInfo(); - SuppressTestEventsIfInSubprocess(); -#endif // GTEST_HAS_DEATH_TEST - - // Registers parameterized tests. This makes parameterized tests - // available to the UnitTest reflection API without running - // RUN_ALL_TESTS. - RegisterParameterizedTests(); - - // Configures listeners for XML output. This makes it possible for users - // to shut down the default XML output before invoking RUN_ALL_TESTS. - ConfigureXmlOutput(); - -#if GTEST_CAN_STREAM_RESULTS_ - // Configures listeners for streaming test results to the specified server. - ConfigureStreamingOutput(); -#endif // GTEST_CAN_STREAM_RESULTS_ - } -} - -// A predicate that checks the name of a TestCase against a known -// value. -// -// This is used for implementation of the UnitTest class only. We put -// it in the anonymous namespace to prevent polluting the outer -// namespace. -// -// TestCaseNameIs is copyable. -class TestCaseNameIs { - public: - // Constructor. - explicit TestCaseNameIs(const std::string& name) - : name_(name) {} - - // Returns true iff the name of test_case matches name_. - bool operator()(const TestCase* test_case) const { - return test_case != NULL && strcmp(test_case->name(), name_.c_str()) == 0; - } - - private: - std::string name_; -}; - -// Finds and returns a TestCase with the given name. If one doesn't -// exist, creates one and returns it. It's the CALLER'S -// RESPONSIBILITY to ensure that this function is only called WHEN THE -// TESTS ARE NOT SHUFFLED. -// -// Arguments: -// -// test_case_name: name of the test case -// type_param: the name of the test case's type parameter, or NULL if -// this is not a typed or a type-parameterized test case. -// set_up_tc: pointer to the function that sets up the test case -// tear_down_tc: pointer to the function that tears down the test case -TestCase* UnitTestImpl::GetTestCase(const char* test_case_name, - const char* type_param, - Test::SetUpTestCaseFunc set_up_tc, - Test::TearDownTestCaseFunc tear_down_tc) { - // Can we find a TestCase with the given name? - const std::vector::const_iterator test_case = - std::find_if(test_cases_.begin(), test_cases_.end(), - TestCaseNameIs(test_case_name)); - - if (test_case != test_cases_.end()) - return *test_case; - - // No. Let's create one. - TestCase* const new_test_case = - new TestCase(test_case_name, type_param, set_up_tc, tear_down_tc); - - // Is this a death test case? - if (internal::UnitTestOptions::MatchesFilter(test_case_name, - kDeathTestCaseFilter)) { - // Yes. Inserts the test case after the last death test case - // defined so far. This only works when the test cases haven't - // been shuffled. Otherwise we may end up running a death test - // after a non-death test. - ++last_death_test_case_; - test_cases_.insert(test_cases_.begin() + last_death_test_case_, - new_test_case); - } else { - // No. Appends to the end of the list. - test_cases_.push_back(new_test_case); - } - - test_case_indices_.push_back(static_cast(test_case_indices_.size())); - return new_test_case; -} - -// Helpers for setting up / tearing down the given environment. They -// are for use in the ForEach() function. -static void SetUpEnvironment(Environment* env) { env->SetUp(); } -static void TearDownEnvironment(Environment* env) { env->TearDown(); } - -// Runs all tests in this UnitTest object, prints the result, and -// returns true if all tests are successful. If any exception is -// thrown during a test, the test is considered to be failed, but the -// rest of the tests will still be run. -// -// When parameterized tests are enabled, it expands and registers -// parameterized tests first in RegisterParameterizedTests(). -// All other functions called from RunAllTests() may safely assume that -// parameterized tests are ready to be counted and run. -bool UnitTestImpl::RunAllTests() { - // Makes sure InitGoogleTest() was called. - if (!GTestIsInitialized()) { - printf("%s", - "\nThis test program did NOT call ::testing::InitGoogleTest " - "before calling RUN_ALL_TESTS(). Please fix it.\n"); - return false; - } - - // Do not run any test if the --help flag was specified. - if (g_help_flag) - return true; - - // Repeats the call to the post-flag parsing initialization in case the - // user didn't call InitGoogleTest. - PostFlagParsingInit(); - - // Even if sharding is not on, test runners may want to use the - // GTEST_SHARD_STATUS_FILE to query whether the test supports the sharding - // protocol. - internal::WriteToShardStatusFileIfNeeded(); - - // True iff we are in a subprocess for running a thread-safe-style - // death test. - bool in_subprocess_for_death_test = false; - -#if GTEST_HAS_DEATH_TEST - in_subprocess_for_death_test = (internal_run_death_test_flag_.get() != NULL); -#endif // GTEST_HAS_DEATH_TEST - - const bool should_shard = ShouldShard(kTestTotalShards, kTestShardIndex, - in_subprocess_for_death_test); - - // Compares the full test names with the filter to decide which - // tests to run. - const bool has_tests_to_run = FilterTests(should_shard - ? HONOR_SHARDING_PROTOCOL - : IGNORE_SHARDING_PROTOCOL) > 0; - - // Lists the tests and exits if the --gtest_list_tests flag was specified. - if (GTEST_FLAG(list_tests)) { - // This must be called *after* FilterTests() has been called. - ListTestsMatchingFilter(); - return true; - } - - random_seed_ = GTEST_FLAG(shuffle) ? - GetRandomSeedFromFlag(GTEST_FLAG(random_seed)) : 0; - - // True iff at least one test has failed. - bool failed = false; - - TestEventListener* repeater = listeners()->repeater(); - - start_timestamp_ = GetTimeInMillis(); - repeater->OnTestProgramStart(*parent_); - - // How many times to repeat the tests? We don't want to repeat them - // when we are inside the subprocess of a death test. - const int repeat = in_subprocess_for_death_test ? 1 : GTEST_FLAG(repeat); - // Repeats forever if the repeat count is negative. - const bool forever = repeat < 0; - for (int i = 0; forever || i != repeat; i++) { - // We want to preserve failures generated by ad-hoc test - // assertions executed before RUN_ALL_TESTS(). - ClearNonAdHocTestResult(); - - const TimeInMillis start = GetTimeInMillis(); - - // Shuffles test cases and tests if requested. - if (has_tests_to_run && GTEST_FLAG(shuffle)) { - random()->Reseed(random_seed_); - // This should be done before calling OnTestIterationStart(), - // such that a test event listener can see the actual test order - // in the event. - ShuffleTests(); - } - - // Tells the unit test event listeners that the tests are about to start. - repeater->OnTestIterationStart(*parent_, i); - - // Runs each test case if there is at least one test to run. - if (has_tests_to_run) { - // Sets up all environments beforehand. - repeater->OnEnvironmentsSetUpStart(*parent_); - ForEach(environments_, SetUpEnvironment); - repeater->OnEnvironmentsSetUpEnd(*parent_); - - // Runs the tests only if there was no fatal failure during global - // set-up. - if (!Test::HasFatalFailure()) { - for (int test_index = 0; test_index < total_test_case_count(); - test_index++) { - GetMutableTestCase(test_index)->Run(); - } - } - - // Tears down all environments in reverse order afterwards. - repeater->OnEnvironmentsTearDownStart(*parent_); - std::for_each(environments_.rbegin(), environments_.rend(), - TearDownEnvironment); - repeater->OnEnvironmentsTearDownEnd(*parent_); - } - - elapsed_time_ = GetTimeInMillis() - start; - - // Tells the unit test event listener that the tests have just finished. - repeater->OnTestIterationEnd(*parent_, i); - - // Gets the result and clears it. - if (!Passed()) { - failed = true; - } - - // Restores the original test order after the iteration. This - // allows the user to quickly repro a failure that happens in the - // N-th iteration without repeating the first (N - 1) iterations. - // This is not enclosed in "if (GTEST_FLAG(shuffle)) { ... }", in - // case the user somehow changes the value of the flag somewhere - // (it's always safe to unshuffle the tests). - UnshuffleTests(); - - if (GTEST_FLAG(shuffle)) { - // Picks a new random seed for each iteration. - random_seed_ = GetNextRandomSeed(random_seed_); - } - } - - repeater->OnTestProgramEnd(*parent_); - - return !failed; -} - -// Reads the GTEST_SHARD_STATUS_FILE environment variable, and creates the file -// if the variable is present. If a file already exists at this location, this -// function will write over it. If the variable is present, but the file cannot -// be created, prints an error and exits. -void WriteToShardStatusFileIfNeeded() { - const char* const test_shard_file = posix::GetEnv(kTestShardStatusFile); - if (test_shard_file != NULL) { - FILE* const file = posix::FOpen(test_shard_file, "w"); - if (file == NULL) { - ColoredPrintf(COLOR_RED, - "Could not write to the test shard status file \"%s\" " - "specified by the %s environment variable.\n", - test_shard_file, kTestShardStatusFile); - fflush(stdout); - exit(EXIT_FAILURE); - } - fclose(file); - } -} - -// Checks whether sharding is enabled by examining the relevant -// environment variable values. If the variables are present, -// but inconsistent (i.e., shard_index >= total_shards), prints -// an error and exits. If in_subprocess_for_death_test, sharding is -// disabled because it must only be applied to the original test -// process. Otherwise, we could filter out death tests we intended to execute. -bool ShouldShard(const char* total_shards_env, - const char* shard_index_env, - bool in_subprocess_for_death_test) { - if (in_subprocess_for_death_test) { - return false; - } - - const Int32 total_shards = Int32FromEnvOrDie(total_shards_env, -1); - const Int32 shard_index = Int32FromEnvOrDie(shard_index_env, -1); - - if (total_shards == -1 && shard_index == -1) { - return false; - } else if (total_shards == -1 && shard_index != -1) { - const Message msg = Message() - << "Invalid environment variables: you have " - << kTestShardIndex << " = " << shard_index - << ", but have left " << kTestTotalShards << " unset.\n"; - ColoredPrintf(COLOR_RED, msg.GetString().c_str()); - fflush(stdout); - exit(EXIT_FAILURE); - } else if (total_shards != -1 && shard_index == -1) { - const Message msg = Message() - << "Invalid environment variables: you have " - << kTestTotalShards << " = " << total_shards - << ", but have left " << kTestShardIndex << " unset.\n"; - ColoredPrintf(COLOR_RED, msg.GetString().c_str()); - fflush(stdout); - exit(EXIT_FAILURE); - } else if (shard_index < 0 || shard_index >= total_shards) { - const Message msg = Message() - << "Invalid environment variables: we require 0 <= " - << kTestShardIndex << " < " << kTestTotalShards - << ", but you have " << kTestShardIndex << "=" << shard_index - << ", " << kTestTotalShards << "=" << total_shards << ".\n"; - ColoredPrintf(COLOR_RED, msg.GetString().c_str()); - fflush(stdout); - exit(EXIT_FAILURE); - } - - return total_shards > 1; -} - -// Parses the environment variable var as an Int32. If it is unset, -// returns default_val. If it is not an Int32, prints an error -// and aborts. -Int32 Int32FromEnvOrDie(const char* var, Int32 default_val) { - const char* str_val = posix::GetEnv(var); - if (str_val == NULL) { - return default_val; - } - - Int32 result; - if (!ParseInt32(Message() << "The value of environment variable " << var, - str_val, &result)) { - exit(EXIT_FAILURE); - } - return result; -} - -// Given the total number of shards, the shard index, and the test id, -// returns true iff the test should be run on this shard. The test id is -// some arbitrary but unique non-negative integer assigned to each test -// method. Assumes that 0 <= shard_index < total_shards. -bool ShouldRunTestOnShard(int total_shards, int shard_index, int test_id) { - return (test_id % total_shards) == shard_index; -} - -// Compares the name of each test with the user-specified filter to -// decide whether the test should be run, then records the result in -// each TestCase and TestInfo object. -// If shard_tests == true, further filters tests based on sharding -// variables in the environment - see -// http://code.google.com/p/googletest/wiki/GoogleTestAdvancedGuide. -// Returns the number of tests that should run. -int UnitTestImpl::FilterTests(ReactionToSharding shard_tests) { - const Int32 total_shards = shard_tests == HONOR_SHARDING_PROTOCOL ? - Int32FromEnvOrDie(kTestTotalShards, -1) : -1; - const Int32 shard_index = shard_tests == HONOR_SHARDING_PROTOCOL ? - Int32FromEnvOrDie(kTestShardIndex, -1) : -1; - - // num_runnable_tests are the number of tests that will - // run across all shards (i.e., match filter and are not disabled). - // num_selected_tests are the number of tests to be run on - // this shard. - int num_runnable_tests = 0; - int num_selected_tests = 0; - for (size_t i = 0; i < test_cases_.size(); i++) { - TestCase* const test_case = test_cases_[i]; - const std::string &test_case_name = test_case->name(); - test_case->set_should_run(false); - - for (size_t j = 0; j < test_case->test_info_list().size(); j++) { - TestInfo* const test_info = test_case->test_info_list()[j]; - const std::string test_name(test_info->name()); - // A test is disabled if test case name or test name matches - // kDisableTestFilter. - const bool is_disabled = - internal::UnitTestOptions::MatchesFilter(test_case_name, - kDisableTestFilter) || - internal::UnitTestOptions::MatchesFilter(test_name, - kDisableTestFilter); - test_info->is_disabled_ = is_disabled; - - const bool matches_filter = - internal::UnitTestOptions::FilterMatchesTest(test_case_name, - test_name); - test_info->matches_filter_ = matches_filter; - - const bool is_runnable = - (GTEST_FLAG(also_run_disabled_tests) || !is_disabled) && - matches_filter; - - const bool is_selected = is_runnable && - (shard_tests == IGNORE_SHARDING_PROTOCOL || - ShouldRunTestOnShard(total_shards, shard_index, - num_runnable_tests)); - - num_runnable_tests += is_runnable; - num_selected_tests += is_selected; - - test_info->should_run_ = is_selected; - test_case->set_should_run(test_case->should_run() || is_selected); - } - } - return num_selected_tests; -} - -// Prints the given C-string on a single line by replacing all '\n' -// characters with string "\\n". If the output takes more than -// max_length characters, only prints the first max_length characters -// and "...". -static void PrintOnOneLine(const char* str, int max_length) { - if (str != NULL) { - for (int i = 0; *str != '\0'; ++str) { - if (i >= max_length) { - printf("..."); - break; - } - if (*str == '\n') { - printf("\\n"); - i += 2; - } else { - printf("%c", *str); - ++i; - } - } - } -} - -// Prints the names of the tests matching the user-specified filter flag. -void UnitTestImpl::ListTestsMatchingFilter() { - // Print at most this many characters for each type/value parameter. - const int kMaxParamLength = 250; - - for (size_t i = 0; i < test_cases_.size(); i++) { - const TestCase* const test_case = test_cases_[i]; - bool printed_test_case_name = false; - - for (size_t j = 0; j < test_case->test_info_list().size(); j++) { - const TestInfo* const test_info = - test_case->test_info_list()[j]; - if (test_info->matches_filter_) { - if (!printed_test_case_name) { - printed_test_case_name = true; - printf("%s.", test_case->name()); - if (test_case->type_param() != NULL) { - printf(" # %s = ", kTypeParamLabel); - // We print the type parameter on a single line to make - // the output easy to parse by a program. - PrintOnOneLine(test_case->type_param(), kMaxParamLength); - } - printf("\n"); - } - printf(" %s", test_info->name()); - if (test_info->value_param() != NULL) { - printf(" # %s = ", kValueParamLabel); - // We print the value parameter on a single line to make the - // output easy to parse by a program. - PrintOnOneLine(test_info->value_param(), kMaxParamLength); - } - printf("\n"); - } - } - } - fflush(stdout); -} - -// Sets the OS stack trace getter. -// -// Does nothing if the input and the current OS stack trace getter are -// the same; otherwise, deletes the old getter and makes the input the -// current getter. -void UnitTestImpl::set_os_stack_trace_getter( - OsStackTraceGetterInterface* getter) { - if (os_stack_trace_getter_ != getter) { - delete os_stack_trace_getter_; - os_stack_trace_getter_ = getter; - } -} - -// Returns the current OS stack trace getter if it is not NULL; -// otherwise, creates an OsStackTraceGetter, makes it the current -// getter, and returns it. -OsStackTraceGetterInterface* UnitTestImpl::os_stack_trace_getter() { - if (os_stack_trace_getter_ == NULL) { - os_stack_trace_getter_ = new OsStackTraceGetter; - } - - return os_stack_trace_getter_; -} - -// Returns the TestResult for the test that's currently running, or -// the TestResult for the ad hoc test if no test is running. -TestResult* UnitTestImpl::current_test_result() { - return current_test_info_ ? - &(current_test_info_->result_) : &ad_hoc_test_result_; -} - -// Shuffles all test cases, and the tests within each test case, -// making sure that death tests are still run first. -void UnitTestImpl::ShuffleTests() { - // Shuffles the death test cases. - ShuffleRange(random(), 0, last_death_test_case_ + 1, &test_case_indices_); - - // Shuffles the non-death test cases. - ShuffleRange(random(), last_death_test_case_ + 1, - static_cast(test_cases_.size()), &test_case_indices_); - - // Shuffles the tests inside each test case. - for (size_t i = 0; i < test_cases_.size(); i++) { - test_cases_[i]->ShuffleTests(random()); - } -} - -// Restores the test cases and tests to their order before the first shuffle. -void UnitTestImpl::UnshuffleTests() { - for (size_t i = 0; i < test_cases_.size(); i++) { - // Unshuffles the tests in each test case. - test_cases_[i]->UnshuffleTests(); - // Resets the index of each test case. - test_case_indices_[i] = static_cast(i); - } -} - -// Returns the current OS stack trace as an std::string. -// -// The maximum number of stack frames to be included is specified by -// the gtest_stack_trace_depth flag. The skip_count parameter -// specifies the number of top frames to be skipped, which doesn't -// count against the number of frames to be included. -// -// For example, if Foo() calls Bar(), which in turn calls -// GetCurrentOsStackTraceExceptTop(..., 1), Foo() will be included in -// the trace but Bar() and GetCurrentOsStackTraceExceptTop() won't. -std::string GetCurrentOsStackTraceExceptTop(UnitTest* /*unit_test*/, - int skip_count) { - // We pass skip_count + 1 to skip this wrapper function in addition - // to what the user really wants to skip. - return GetUnitTestImpl()->CurrentOsStackTraceExceptTop(skip_count + 1); -} - -// Used by the GTEST_SUPPRESS_UNREACHABLE_CODE_WARNING_BELOW_ macro to -// suppress unreachable code warnings. -namespace { -class ClassUniqueToAlwaysTrue {}; -} - -bool IsTrue(bool condition) { return condition; } - -bool AlwaysTrue() { -#if GTEST_HAS_EXCEPTIONS - // This condition is always false so AlwaysTrue() never actually throws, - // but it makes the compiler think that it may throw. - if (IsTrue(false)) - throw ClassUniqueToAlwaysTrue(); -#endif // GTEST_HAS_EXCEPTIONS - return true; -} - -// If *pstr starts with the given prefix, modifies *pstr to be right -// past the prefix and returns true; otherwise leaves *pstr unchanged -// and returns false. None of pstr, *pstr, and prefix can be NULL. -bool SkipPrefix(const char* prefix, const char** pstr) { - const size_t prefix_len = strlen(prefix); - if (strncmp(*pstr, prefix, prefix_len) == 0) { - *pstr += prefix_len; - return true; - } - return false; -} - -// Parses a string as a command line flag. The string should have -// the format "--flag=value". When def_optional is true, the "=value" -// part can be omitted. -// -// Returns the value of the flag, or NULL if the parsing failed. -const char* ParseFlagValue(const char* str, - const char* flag, - bool def_optional) { - // str and flag must not be NULL. - if (str == NULL || flag == NULL) return NULL; - - // The flag must start with "--" followed by GTEST_FLAG_PREFIX_. - const std::string flag_str = std::string("--") + GTEST_FLAG_PREFIX_ + flag; - const size_t flag_len = flag_str.length(); - if (strncmp(str, flag_str.c_str(), flag_len) != 0) return NULL; - - // Skips the flag name. - const char* flag_end = str + flag_len; - - // When def_optional is true, it's OK to not have a "=value" part. - if (def_optional && (flag_end[0] == '\0')) { - return flag_end; - } - - // If def_optional is true and there are more characters after the - // flag name, or if def_optional is false, there must be a '=' after - // the flag name. - if (flag_end[0] != '=') return NULL; - - // Returns the string after "=". - return flag_end + 1; -} - -// Parses a string for a bool flag, in the form of either -// "--flag=value" or "--flag". -// -// In the former case, the value is taken as true as long as it does -// not start with '0', 'f', or 'F'. -// -// In the latter case, the value is taken as true. -// -// On success, stores the value of the flag in *value, and returns -// true. On failure, returns false without changing *value. -bool ParseBoolFlag(const char* str, const char* flag, bool* value) { - // Gets the value of the flag as a string. - const char* const value_str = ParseFlagValue(str, flag, true); - - // Aborts if the parsing failed. - if (value_str == NULL) return false; - - // Converts the string value to a bool. - *value = !(*value_str == '0' || *value_str == 'f' || *value_str == 'F'); - return true; -} - -// Parses a string for an Int32 flag, in the form of -// "--flag=value". -// -// On success, stores the value of the flag in *value, and returns -// true. On failure, returns false without changing *value. -bool ParseInt32Flag(const char* str, const char* flag, Int32* value) { - // Gets the value of the flag as a string. - const char* const value_str = ParseFlagValue(str, flag, false); - - // Aborts if the parsing failed. - if (value_str == NULL) return false; - - // Sets *value to the value of the flag. - return ParseInt32(Message() << "The value of flag --" << flag, - value_str, value); -} - -// Parses a string for a string flag, in the form of -// "--flag=value". -// -// On success, stores the value of the flag in *value, and returns -// true. On failure, returns false without changing *value. -bool ParseStringFlag(const char* str, const char* flag, std::string* value) { - // Gets the value of the flag as a string. - const char* const value_str = ParseFlagValue(str, flag, false); - - // Aborts if the parsing failed. - if (value_str == NULL) return false; - - // Sets *value to the value of the flag. - *value = value_str; - return true; -} - -// Determines whether a string has a prefix that Google Test uses for its -// flags, i.e., starts with GTEST_FLAG_PREFIX_ or GTEST_FLAG_PREFIX_DASH_. -// If Google Test detects that a command line flag has its prefix but is not -// recognized, it will print its help message. Flags starting with -// GTEST_INTERNAL_PREFIX_ followed by "internal_" are considered Google Test -// internal flags and do not trigger the help message. -static bool HasGoogleTestFlagPrefix(const char* str) { - return (SkipPrefix("--", &str) || - SkipPrefix("-", &str) || - SkipPrefix("/", &str)) && - !SkipPrefix(GTEST_FLAG_PREFIX_ "internal_", &str) && - (SkipPrefix(GTEST_FLAG_PREFIX_, &str) || - SkipPrefix(GTEST_FLAG_PREFIX_DASH_, &str)); -} - -// Prints a string containing code-encoded text. The following escape -// sequences can be used in the string to control the text color: -// -// @@ prints a single '@' character. -// @R changes the color to red. -// @G changes the color to green. -// @Y changes the color to yellow. -// @D changes to the default terminal text color. -// -// TODO(wan@google.com): Write tests for this once we add stdout -// capturing to Google Test. -static void PrintColorEncoded(const char* str) { - GTestColor color = COLOR_DEFAULT; // The current color. - - // Conceptually, we split the string into segments divided by escape - // sequences. Then we print one segment at a time. At the end of - // each iteration, the str pointer advances to the beginning of the - // next segment. - for (;;) { - const char* p = strchr(str, '@'); - if (p == NULL) { - ColoredPrintf(color, "%s", str); - return; - } - - ColoredPrintf(color, "%s", std::string(str, p).c_str()); - - const char ch = p[1]; - str = p + 2; - if (ch == '@') { - ColoredPrintf(color, "@"); - } else if (ch == 'D') { - color = COLOR_DEFAULT; - } else if (ch == 'R') { - color = COLOR_RED; - } else if (ch == 'G') { - color = COLOR_GREEN; - } else if (ch == 'Y') { - color = COLOR_YELLOW; - } else { - --str; - } - } -} - -static const char kColorEncodedHelpMessage[] = -"This program contains tests written using " GTEST_NAME_ ". You can use the\n" -"following command line flags to control its behavior:\n" -"\n" -"Test Selection:\n" -" @G--" GTEST_FLAG_PREFIX_ "list_tests@D\n" -" List the names of all tests instead of running them. The name of\n" -" TEST(Foo, Bar) is \"Foo.Bar\".\n" -" @G--" GTEST_FLAG_PREFIX_ "filter=@YPOSTIVE_PATTERNS" - "[@G-@YNEGATIVE_PATTERNS]@D\n" -" Run only the tests whose name matches one of the positive patterns but\n" -" none of the negative patterns. '?' matches any single character; '*'\n" -" matches any substring; ':' separates two patterns.\n" -" @G--" GTEST_FLAG_PREFIX_ "also_run_disabled_tests@D\n" -" Run all disabled tests too.\n" -"\n" -"Test Execution:\n" -" @G--" GTEST_FLAG_PREFIX_ "repeat=@Y[COUNT]@D\n" -" Run the tests repeatedly; use a negative count to repeat forever.\n" -" @G--" GTEST_FLAG_PREFIX_ "shuffle@D\n" -" Randomize tests' orders on every iteration.\n" -" @G--" GTEST_FLAG_PREFIX_ "random_seed=@Y[NUMBER]@D\n" -" Random number seed to use for shuffling test orders (between 1 and\n" -" 99999, or 0 to use a seed based on the current time).\n" -"\n" -"Test Output:\n" -" @G--" GTEST_FLAG_PREFIX_ "color=@Y(@Gyes@Y|@Gno@Y|@Gauto@Y)@D\n" -" Enable/disable colored output. The default is @Gauto@D.\n" -" -@G-" GTEST_FLAG_PREFIX_ "print_time=0@D\n" -" Don't print the elapsed time of each test.\n" -" @G--" GTEST_FLAG_PREFIX_ "output=xml@Y[@G:@YDIRECTORY_PATH@G" - GTEST_PATH_SEP_ "@Y|@G:@YFILE_PATH]@D\n" -" Generate an XML report in the given directory or with the given file\n" -" name. @YFILE_PATH@D defaults to @Gtest_details.xml@D.\n" -#if GTEST_CAN_STREAM_RESULTS_ -" @G--" GTEST_FLAG_PREFIX_ "stream_result_to=@YHOST@G:@YPORT@D\n" -" Stream test results to the given server.\n" -#endif // GTEST_CAN_STREAM_RESULTS_ -"\n" -"Assertion Behavior:\n" -#if GTEST_HAS_DEATH_TEST && !GTEST_OS_WINDOWS -" @G--" GTEST_FLAG_PREFIX_ "death_test_style=@Y(@Gfast@Y|@Gthreadsafe@Y)@D\n" -" Set the default death test style.\n" -#endif // GTEST_HAS_DEATH_TEST && !GTEST_OS_WINDOWS -" @G--" GTEST_FLAG_PREFIX_ "break_on_failure@D\n" -" Turn assertion failures into debugger break-points.\n" -" @G--" GTEST_FLAG_PREFIX_ "throw_on_failure@D\n" -" Turn assertion failures into C++ exceptions.\n" -" @G--" GTEST_FLAG_PREFIX_ "catch_exceptions=0@D\n" -" Do not report exceptions as test failures. Instead, allow them\n" -" to crash the program or throw a pop-up (on Windows).\n" -"\n" -"Except for @G--" GTEST_FLAG_PREFIX_ "list_tests@D, you can alternatively set " - "the corresponding\n" -"environment variable of a flag (all letters in upper-case). For example, to\n" -"disable colored text output, you can either specify @G--" GTEST_FLAG_PREFIX_ - "color=no@D or set\n" -"the @G" GTEST_FLAG_PREFIX_UPPER_ "COLOR@D environment variable to @Gno@D.\n" -"\n" -"For more information, please read the " GTEST_NAME_ " documentation at\n" -"@G" GTEST_PROJECT_URL_ "@D. If you find a bug in " GTEST_NAME_ "\n" -"(not one in your own code or tests), please report it to\n" -"@G<" GTEST_DEV_EMAIL_ ">@D.\n"; - -// Parses the command line for Google Test flags, without initializing -// other parts of Google Test. The type parameter CharType can be -// instantiated to either char or wchar_t. -template -void ParseGoogleTestFlagsOnlyImpl(int* argc, CharType** argv) { - for (int i = 1; i < *argc; i++) { - const std::string arg_string = StreamableToString(argv[i]); - const char* const arg = arg_string.c_str(); - - using internal::ParseBoolFlag; - using internal::ParseInt32Flag; - using internal::ParseStringFlag; - - // Do we see a Google Test flag? - if (ParseBoolFlag(arg, kAlsoRunDisabledTestsFlag, - >EST_FLAG(also_run_disabled_tests)) || - ParseBoolFlag(arg, kBreakOnFailureFlag, - >EST_FLAG(break_on_failure)) || - ParseBoolFlag(arg, kCatchExceptionsFlag, - >EST_FLAG(catch_exceptions)) || - ParseStringFlag(arg, kColorFlag, >EST_FLAG(color)) || - ParseStringFlag(arg, kDeathTestStyleFlag, - >EST_FLAG(death_test_style)) || - ParseBoolFlag(arg, kDeathTestUseFork, - >EST_FLAG(death_test_use_fork)) || - ParseStringFlag(arg, kFilterFlag, >EST_FLAG(filter)) || - ParseStringFlag(arg, kInternalRunDeathTestFlag, - >EST_FLAG(internal_run_death_test)) || - ParseBoolFlag(arg, kListTestsFlag, >EST_FLAG(list_tests)) || - ParseStringFlag(arg, kOutputFlag, >EST_FLAG(output)) || - ParseBoolFlag(arg, kPrintTimeFlag, >EST_FLAG(print_time)) || - ParseInt32Flag(arg, kRandomSeedFlag, >EST_FLAG(random_seed)) || - ParseInt32Flag(arg, kRepeatFlag, >EST_FLAG(repeat)) || - ParseBoolFlag(arg, kShuffleFlag, >EST_FLAG(shuffle)) || - ParseInt32Flag(arg, kStackTraceDepthFlag, - >EST_FLAG(stack_trace_depth)) || - ParseStringFlag(arg, kStreamResultToFlag, - >EST_FLAG(stream_result_to)) || - ParseBoolFlag(arg, kThrowOnFailureFlag, - >EST_FLAG(throw_on_failure)) - ) { - // Yes. Shift the remainder of the argv list left by one. Note - // that argv has (*argc + 1) elements, the last one always being - // NULL. The following loop moves the trailing NULL element as - // well. - for (int j = i; j != *argc; j++) { - argv[j] = argv[j + 1]; - } - - // Decrements the argument count. - (*argc)--; - - // We also need to decrement the iterator as we just removed - // an element. - i--; - } else if (arg_string == "--help" || arg_string == "-h" || - arg_string == "-?" || arg_string == "/?" || - HasGoogleTestFlagPrefix(arg)) { - // Both help flag and unrecognized Google Test flags (excluding - // internal ones) trigger help display. - g_help_flag = true; - } - } - - if (g_help_flag) { - // We print the help here instead of in RUN_ALL_TESTS(), as the - // latter may not be called at all if the user is using Google - // Test with another testing framework. - PrintColorEncoded(kColorEncodedHelpMessage); - } -} - -// Parses the command line for Google Test flags, without initializing -// other parts of Google Test. -void ParseGoogleTestFlagsOnly(int* argc, char** argv) { - ParseGoogleTestFlagsOnlyImpl(argc, argv); -} -void ParseGoogleTestFlagsOnly(int* argc, wchar_t** argv) { - ParseGoogleTestFlagsOnlyImpl(argc, argv); -} - -// The internal implementation of InitGoogleTest(). -// -// The type parameter CharType can be instantiated to either char or -// wchar_t. -template -void InitGoogleTestImpl(int* argc, CharType** argv) { - g_init_gtest_count++; - - // We don't want to run the initialization code twice. - if (g_init_gtest_count != 1) return; - - if (*argc <= 0) return; - - internal::g_executable_path = internal::StreamableToString(argv[0]); - -#if GTEST_HAS_DEATH_TEST - - g_argvs.clear(); - for (int i = 0; i != *argc; i++) { - g_argvs.push_back(StreamableToString(argv[i])); - } - -#endif // GTEST_HAS_DEATH_TEST - - ParseGoogleTestFlagsOnly(argc, argv); - GetUnitTestImpl()->PostFlagParsingInit(); -} - -} // namespace internal - -// Initializes Google Test. This must be called before calling -// RUN_ALL_TESTS(). In particular, it parses a command line for the -// flags that Google Test recognizes. Whenever a Google Test flag is -// seen, it is removed from argv, and *argc is decremented. -// -// No value is returned. Instead, the Google Test flag variables are -// updated. -// -// Calling the function for the second time has no user-visible effect. -void InitGoogleTest(int* argc, char** argv) { - internal::InitGoogleTestImpl(argc, argv); -} - -// This overloaded version can be used in Windows programs compiled in -// UNICODE mode. -void InitGoogleTest(int* argc, wchar_t** argv) { - internal::InitGoogleTestImpl(argc, argv); -} - -} // namespace testing -// Copyright 2005, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: wan@google.com (Zhanyong Wan), vladl@google.com (Vlad Losev) -// -// This file implements death tests. - - -#if GTEST_HAS_DEATH_TEST - -# if GTEST_OS_MAC -# include -# endif // GTEST_OS_MAC - -# include -# include -# include - -# if GTEST_OS_LINUX -# include -# endif // GTEST_OS_LINUX - -# include - -# if GTEST_OS_WINDOWS -# include -# else -# include -# include -# endif // GTEST_OS_WINDOWS - -# if GTEST_OS_QNX -# include -# endif // GTEST_OS_QNX - -#endif // GTEST_HAS_DEATH_TEST - - -// Indicates that this translation unit is part of Google Test's -// implementation. It must come before gtest-internal-inl.h is -// included, or there will be a compiler error. This trick is to -// prevent a user from accidentally including gtest-internal-inl.h in -// his code. -#define GTEST_IMPLEMENTATION_ 1 -#undef GTEST_IMPLEMENTATION_ - -namespace testing { - -// Constants. - -// The default death test style. -static const char kDefaultDeathTestStyle[] = "fast"; - -GTEST_DEFINE_string_( - death_test_style, - internal::StringFromGTestEnv("death_test_style", kDefaultDeathTestStyle), - "Indicates how to run a death test in a forked child process: " - "\"threadsafe\" (child process re-executes the test binary " - "from the beginning, running only the specific death test) or " - "\"fast\" (child process runs the death test immediately " - "after forking)."); - -GTEST_DEFINE_bool_( - death_test_use_fork, - internal::BoolFromGTestEnv("death_test_use_fork", false), - "Instructs to use fork()/_exit() instead of clone() in death tests. " - "Ignored and always uses fork() on POSIX systems where clone() is not " - "implemented. Useful when running under valgrind or similar tools if " - "those do not support clone(). Valgrind 3.3.1 will just fail if " - "it sees an unsupported combination of clone() flags. " - "It is not recommended to use this flag w/o valgrind though it will " - "work in 99% of the cases. Once valgrind is fixed, this flag will " - "most likely be removed."); - -namespace internal { -GTEST_DEFINE_string_( - internal_run_death_test, "", - "Indicates the file, line number, temporal index of " - "the single death test to run, and a file descriptor to " - "which a success code may be sent, all separated by " - "the '|' characters. This flag is specified if and only if the current " - "process is a sub-process launched for running a thread-safe " - "death test. FOR INTERNAL USE ONLY."); -} // namespace internal - -#if GTEST_HAS_DEATH_TEST - -namespace internal { - -// Valid only for fast death tests. Indicates the code is running in the -// child process of a fast style death test. -static bool g_in_fast_death_test_child = false; - -// Returns a Boolean value indicating whether the caller is currently -// executing in the context of the death test child process. Tools such as -// Valgrind heap checkers may need this to modify their behavior in death -// tests. IMPORTANT: This is an internal utility. Using it may break the -// implementation of death tests. User code MUST NOT use it. -bool InDeathTestChild() { -# if GTEST_OS_WINDOWS - - // On Windows, death tests are thread-safe regardless of the value of the - // death_test_style flag. - return !GTEST_FLAG(internal_run_death_test).empty(); - -# else - - if (GTEST_FLAG(death_test_style) == "threadsafe") - return !GTEST_FLAG(internal_run_death_test).empty(); - else - return g_in_fast_death_test_child; -#endif -} - -} // namespace internal - -// ExitedWithCode constructor. -ExitedWithCode::ExitedWithCode(int exit_code) : exit_code_(exit_code) { -} - -// ExitedWithCode function-call operator. -bool ExitedWithCode::operator()(int exit_status) const { -# if GTEST_OS_WINDOWS - - return exit_status == exit_code_; - -# else - - return WIFEXITED(exit_status) && WEXITSTATUS(exit_status) == exit_code_; - -# endif // GTEST_OS_WINDOWS -} - -# if !GTEST_OS_WINDOWS -// KilledBySignal constructor. -KilledBySignal::KilledBySignal(int signum) : signum_(signum) { -} - -// KilledBySignal function-call operator. -bool KilledBySignal::operator()(int exit_status) const { - return WIFSIGNALED(exit_status) && WTERMSIG(exit_status) == signum_; -} -# endif // !GTEST_OS_WINDOWS - -namespace internal { - -// Utilities needed for death tests. - -// Generates a textual description of a given exit code, in the format -// specified by wait(2). -static std::string ExitSummary(int exit_code) { - Message m; - -# if GTEST_OS_WINDOWS - - m << "Exited with exit status " << exit_code; - -# else - - if (WIFEXITED(exit_code)) { - m << "Exited with exit status " << WEXITSTATUS(exit_code); - } else if (WIFSIGNALED(exit_code)) { - m << "Terminated by signal " << WTERMSIG(exit_code); - } -# ifdef WCOREDUMP - if (WCOREDUMP(exit_code)) { - m << " (core dumped)"; - } -# endif -# endif // GTEST_OS_WINDOWS - - return m.GetString(); -} - -// Returns true if exit_status describes a process that was terminated -// by a signal, or exited normally with a nonzero exit code. -bool ExitedUnsuccessfully(int exit_status) { - return !ExitedWithCode(0)(exit_status); -} - -# if !GTEST_OS_WINDOWS -// Generates a textual failure message when a death test finds more than -// one thread running, or cannot determine the number of threads, prior -// to executing the given statement. It is the responsibility of the -// caller not to pass a thread_count of 1. -static std::string DeathTestThreadWarning(size_t thread_count) { - Message msg; - msg << "Death tests use fork(), which is unsafe particularly" - << " in a threaded context. For this test, " << GTEST_NAME_ << " "; - if (thread_count == 0) - msg << "couldn't detect the number of threads."; - else - msg << "detected " << thread_count << " threads."; - return msg.GetString(); -} -# endif // !GTEST_OS_WINDOWS - -// Flag characters for reporting a death test that did not die. -static const char kDeathTestLived = 'L'; -static const char kDeathTestReturned = 'R'; -static const char kDeathTestThrew = 'T'; -static const char kDeathTestInternalError = 'I'; - -// An enumeration describing all of the possible ways that a death test can -// conclude. DIED means that the process died while executing the test -// code; LIVED means that process lived beyond the end of the test code; -// RETURNED means that the test statement attempted to execute a return -// statement, which is not allowed; THREW means that the test statement -// returned control by throwing an exception. IN_PROGRESS means the test -// has not yet concluded. -// TODO(vladl@google.com): Unify names and possibly values for -// AbortReason, DeathTestOutcome, and flag characters above. -enum DeathTestOutcome { IN_PROGRESS, DIED, LIVED, RETURNED, THREW }; - -// Routine for aborting the program which is safe to call from an -// exec-style death test child process, in which case the error -// message is propagated back to the parent process. Otherwise, the -// message is simply printed to stderr. In either case, the program -// then exits with status 1. -void DeathTestAbort(const std::string& message) { - // On a POSIX system, this function may be called from a threadsafe-style - // death test child process, which operates on a very small stack. Use - // the heap for any additional non-minuscule memory requirements. - const InternalRunDeathTestFlag* const flag = - GetUnitTestImpl()->internal_run_death_test_flag(); - if (flag != NULL) { - FILE* parent = posix::FDOpen(flag->write_fd(), "w"); - fputc(kDeathTestInternalError, parent); - fprintf(parent, "%s", message.c_str()); - fflush(parent); - _exit(1); - } else { - fprintf(stderr, "%s", message.c_str()); - fflush(stderr); - posix::Abort(); - } -} - -// A replacement for CHECK that calls DeathTestAbort if the assertion -// fails. -# define GTEST_DEATH_TEST_CHECK_(expression) \ - do { \ - if (!::testing::internal::IsTrue(expression)) { \ - DeathTestAbort( \ - ::std::string("CHECK failed: File ") + __FILE__ + ", line " \ - + ::testing::internal::StreamableToString(__LINE__) + ": " \ - + #expression); \ - } \ - } while (::testing::internal::AlwaysFalse()) - -// This macro is similar to GTEST_DEATH_TEST_CHECK_, but it is meant for -// evaluating any system call that fulfills two conditions: it must return -// -1 on failure, and set errno to EINTR when it is interrupted and -// should be tried again. The macro expands to a loop that repeatedly -// evaluates the expression as long as it evaluates to -1 and sets -// errno to EINTR. If the expression evaluates to -1 but errno is -// something other than EINTR, DeathTestAbort is called. -# define GTEST_DEATH_TEST_CHECK_SYSCALL_(expression) \ - do { \ - int gtest_retval; \ - do { \ - gtest_retval = (expression); \ - } while (gtest_retval == -1 && errno == EINTR); \ - if (gtest_retval == -1) { \ - DeathTestAbort( \ - ::std::string("CHECK failed: File ") + __FILE__ + ", line " \ - + ::testing::internal::StreamableToString(__LINE__) + ": " \ - + #expression + " != -1"); \ - } \ - } while (::testing::internal::AlwaysFalse()) - -// Returns the message describing the last system error in errno. -std::string GetLastErrnoDescription() { - return errno == 0 ? "" : posix::StrError(errno); -} - -// This is called from a death test parent process to read a failure -// message from the death test child process and log it with the FATAL -// severity. On Windows, the message is read from a pipe handle. On other -// platforms, it is read from a file descriptor. -static void FailFromInternalError(int fd) { - Message error; - char buffer[256]; - int num_read; - - do { - while ((num_read = posix::Read(fd, buffer, 255)) > 0) { - buffer[num_read] = '\0'; - error << buffer; - } - } while (num_read == -1 && errno == EINTR); - - if (num_read == 0) { - GTEST_LOG_(FATAL) << error.GetString(); - } else { - const int last_error = errno; - GTEST_LOG_(FATAL) << "Error while reading death test internal: " - << GetLastErrnoDescription() << " [" << last_error << "]"; - } -} - -// Death test constructor. Increments the running death test count -// for the current test. -DeathTest::DeathTest() { - TestInfo* const info = GetUnitTestImpl()->current_test_info(); - if (info == NULL) { - DeathTestAbort("Cannot run a death test outside of a TEST or " - "TEST_F construct"); - } -} - -// Creates and returns a death test by dispatching to the current -// death test factory. -bool DeathTest::Create(const char* statement, const RE* regex, - const char* file, int line, DeathTest** test) { - return GetUnitTestImpl()->death_test_factory()->Create( - statement, regex, file, line, test); -} - -const char* DeathTest::LastMessage() { - return last_death_test_message_.c_str(); -} - -void DeathTest::set_last_death_test_message(const std::string& message) { - last_death_test_message_ = message; -} - -std::string DeathTest::last_death_test_message_; - -// Provides cross platform implementation for some death functionality. -class DeathTestImpl : public DeathTest { - protected: - DeathTestImpl(const char* a_statement, const RE* a_regex) - : statement_(a_statement), - regex_(a_regex), - spawned_(false), - status_(-1), - outcome_(IN_PROGRESS), - read_fd_(-1), - write_fd_(-1) {} - - // read_fd_ is expected to be closed and cleared by a derived class. - ~DeathTestImpl() { GTEST_DEATH_TEST_CHECK_(read_fd_ == -1); } - - void Abort(AbortReason reason); - virtual bool Passed(bool status_ok); - - const char* statement() const { return statement_; } - const RE* regex() const { return regex_; } - bool spawned() const { return spawned_; } - void set_spawned(bool is_spawned) { spawned_ = is_spawned; } - int status() const { return status_; } - void set_status(int a_status) { status_ = a_status; } - DeathTestOutcome outcome() const { return outcome_; } - void set_outcome(DeathTestOutcome an_outcome) { outcome_ = an_outcome; } - int read_fd() const { return read_fd_; } - void set_read_fd(int fd) { read_fd_ = fd; } - int write_fd() const { return write_fd_; } - void set_write_fd(int fd) { write_fd_ = fd; } - - // Called in the parent process only. Reads the result code of the death - // test child process via a pipe, interprets it to set the outcome_ - // member, and closes read_fd_. Outputs diagnostics and terminates in - // case of unexpected codes. - void ReadAndInterpretStatusByte(); - - private: - // The textual content of the code this object is testing. This class - // doesn't own this string and should not attempt to delete it. - const char* const statement_; - // The regular expression which test output must match. DeathTestImpl - // doesn't own this object and should not attempt to delete it. - const RE* const regex_; - // True if the death test child process has been successfully spawned. - bool spawned_; - // The exit status of the child process. - int status_; - // How the death test concluded. - DeathTestOutcome outcome_; - // Descriptor to the read end of the pipe to the child process. It is - // always -1 in the child process. The child keeps its write end of the - // pipe in write_fd_. - int read_fd_; - // Descriptor to the child's write end of the pipe to the parent process. - // It is always -1 in the parent process. The parent keeps its end of the - // pipe in read_fd_. - int write_fd_; -}; - -// Called in the parent process only. Reads the result code of the death -// test child process via a pipe, interprets it to set the outcome_ -// member, and closes read_fd_. Outputs diagnostics and terminates in -// case of unexpected codes. -void DeathTestImpl::ReadAndInterpretStatusByte() { - char flag; - int bytes_read; - - // The read() here blocks until data is available (signifying the - // failure of the death test) or until the pipe is closed (signifying - // its success), so it's okay to call this in the parent before - // the child process has exited. - do { - bytes_read = posix::Read(read_fd(), &flag, 1); - } while (bytes_read == -1 && errno == EINTR); - - if (bytes_read == 0) { - set_outcome(DIED); - } else if (bytes_read == 1) { - switch (flag) { - case kDeathTestReturned: - set_outcome(RETURNED); - break; - case kDeathTestThrew: - set_outcome(THREW); - break; - case kDeathTestLived: - set_outcome(LIVED); - break; - case kDeathTestInternalError: - FailFromInternalError(read_fd()); // Does not return. - break; - default: - GTEST_LOG_(FATAL) << "Death test child process reported " - << "unexpected status byte (" - << static_cast(flag) << ")"; - } - } else { - GTEST_LOG_(FATAL) << "Read from death test child process failed: " - << GetLastErrnoDescription(); - } - GTEST_DEATH_TEST_CHECK_SYSCALL_(posix::Close(read_fd())); - set_read_fd(-1); -} - -// Signals that the death test code which should have exited, didn't. -// Should be called only in a death test child process. -// Writes a status byte to the child's status file descriptor, then -// calls _exit(1). -void DeathTestImpl::Abort(AbortReason reason) { - // The parent process considers the death test to be a failure if - // it finds any data in our pipe. So, here we write a single flag byte - // to the pipe, then exit. - const char status_ch = - reason == TEST_DID_NOT_DIE ? kDeathTestLived : - reason == TEST_THREW_EXCEPTION ? kDeathTestThrew : kDeathTestReturned; - - GTEST_DEATH_TEST_CHECK_SYSCALL_(posix::Write(write_fd(), &status_ch, 1)); - // We are leaking the descriptor here because on some platforms (i.e., - // when built as Windows DLL), destructors of global objects will still - // run after calling _exit(). On such systems, write_fd_ will be - // indirectly closed from the destructor of UnitTestImpl, causing double - // close if it is also closed here. On debug configurations, double close - // may assert. As there are no in-process buffers to flush here, we are - // relying on the OS to close the descriptor after the process terminates - // when the destructors are not run. - _exit(1); // Exits w/o any normal exit hooks (we were supposed to crash) -} - -// Returns an indented copy of stderr output for a death test. -// This makes distinguishing death test output lines from regular log lines -// much easier. -static ::std::string FormatDeathTestOutput(const ::std::string& output) { - ::std::string ret; - for (size_t at = 0; ; ) { - const size_t line_end = output.find('\n', at); - ret += "[ DEATH ] "; - if (line_end == ::std::string::npos) { - ret += output.substr(at); - break; - } - ret += output.substr(at, line_end + 1 - at); - at = line_end + 1; - } - return ret; -} - -// Assesses the success or failure of a death test, using both private -// members which have previously been set, and one argument: -// -// Private data members: -// outcome: An enumeration describing how the death test -// concluded: DIED, LIVED, THREW, or RETURNED. The death test -// fails in the latter three cases. -// status: The exit status of the child process. On *nix, it is in the -// in the format specified by wait(2). On Windows, this is the -// value supplied to the ExitProcess() API or a numeric code -// of the exception that terminated the program. -// regex: A regular expression object to be applied to -// the test's captured standard error output; the death test -// fails if it does not match. -// -// Argument: -// status_ok: true if exit_status is acceptable in the context of -// this particular death test, which fails if it is false -// -// Returns true iff all of the above conditions are met. Otherwise, the -// first failing condition, in the order given above, is the one that is -// reported. Also sets the last death test message string. -bool DeathTestImpl::Passed(bool status_ok) { - if (!spawned()) - return false; - - const std::string error_message = GetCapturedStderr(); - - bool success = false; - Message buffer; - - buffer << "Death test: " << statement() << "\n"; - switch (outcome()) { - case LIVED: - buffer << " Result: failed to die.\n" - << " Error msg:\n" << FormatDeathTestOutput(error_message); - break; - case THREW: - buffer << " Result: threw an exception.\n" - << " Error msg:\n" << FormatDeathTestOutput(error_message); - break; - case RETURNED: - buffer << " Result: illegal return in test statement.\n" - << " Error msg:\n" << FormatDeathTestOutput(error_message); - break; - case DIED: - if (status_ok) { - const bool matched = RE::PartialMatch(error_message.c_str(), *regex()); - if (matched) { - success = true; - } else { - buffer << " Result: died but not with expected error.\n" - << " Expected: " << regex()->pattern() << "\n" - << "Actual msg:\n" << FormatDeathTestOutput(error_message); - } - } else { - buffer << " Result: died but not with expected exit code:\n" - << " " << ExitSummary(status()) << "\n" - << "Actual msg:\n" << FormatDeathTestOutput(error_message); - } - break; - case IN_PROGRESS: - default: - GTEST_LOG_(FATAL) - << "DeathTest::Passed somehow called before conclusion of test"; - } - - DeathTest::set_last_death_test_message(buffer.GetString()); - return success; -} - -# if GTEST_OS_WINDOWS -// WindowsDeathTest implements death tests on Windows. Due to the -// specifics of starting new processes on Windows, death tests there are -// always threadsafe, and Google Test considers the -// --gtest_death_test_style=fast setting to be equivalent to -// --gtest_death_test_style=threadsafe there. -// -// A few implementation notes: Like the Linux version, the Windows -// implementation uses pipes for child-to-parent communication. But due to -// the specifics of pipes on Windows, some extra steps are required: -// -// 1. The parent creates a communication pipe and stores handles to both -// ends of it. -// 2. The parent starts the child and provides it with the information -// necessary to acquire the handle to the write end of the pipe. -// 3. The child acquires the write end of the pipe and signals the parent -// using a Windows event. -// 4. Now the parent can release the write end of the pipe on its side. If -// this is done before step 3, the object's reference count goes down to -// 0 and it is destroyed, preventing the child from acquiring it. The -// parent now has to release it, or read operations on the read end of -// the pipe will not return when the child terminates. -// 5. The parent reads child's output through the pipe (outcome code and -// any possible error messages) from the pipe, and its stderr and then -// determines whether to fail the test. -// -// Note: to distinguish Win32 API calls from the local method and function -// calls, the former are explicitly resolved in the global namespace. -// -class WindowsDeathTest : public DeathTestImpl { - public: - WindowsDeathTest(const char* a_statement, - const RE* a_regex, - const char* file, - int line) - : DeathTestImpl(a_statement, a_regex), file_(file), line_(line) {} - - // All of these virtual functions are inherited from DeathTest. - virtual int Wait(); - virtual TestRole AssumeRole(); - - private: - // The name of the file in which the death test is located. - const char* const file_; - // The line number on which the death test is located. - const int line_; - // Handle to the write end of the pipe to the child process. - AutoHandle write_handle_; - // Child process handle. - AutoHandle child_handle_; - // Event the child process uses to signal the parent that it has - // acquired the handle to the write end of the pipe. After seeing this - // event the parent can release its own handles to make sure its - // ReadFile() calls return when the child terminates. - AutoHandle event_handle_; -}; - -// Waits for the child in a death test to exit, returning its exit -// status, or 0 if no child process exists. As a side effect, sets the -// outcome data member. -int WindowsDeathTest::Wait() { - if (!spawned()) - return 0; - - // Wait until the child either signals that it has acquired the write end - // of the pipe or it dies. - const HANDLE wait_handles[2] = { child_handle_.Get(), event_handle_.Get() }; - switch (::WaitForMultipleObjects(2, - wait_handles, - FALSE, // Waits for any of the handles. - INFINITE)) { - case WAIT_OBJECT_0: - case WAIT_OBJECT_0 + 1: - break; - default: - GTEST_DEATH_TEST_CHECK_(false); // Should not get here. - } - - // The child has acquired the write end of the pipe or exited. - // We release the handle on our side and continue. - write_handle_.Reset(); - event_handle_.Reset(); - - ReadAndInterpretStatusByte(); - - // Waits for the child process to exit if it haven't already. This - // returns immediately if the child has already exited, regardless of - // whether previous calls to WaitForMultipleObjects synchronized on this - // handle or not. - GTEST_DEATH_TEST_CHECK_( - WAIT_OBJECT_0 == ::WaitForSingleObject(child_handle_.Get(), - INFINITE)); - DWORD status_code; - GTEST_DEATH_TEST_CHECK_( - ::GetExitCodeProcess(child_handle_.Get(), &status_code) != FALSE); - child_handle_.Reset(); - set_status(static_cast(status_code)); - return status(); -} - -// The AssumeRole process for a Windows death test. It creates a child -// process with the same executable as the current process to run the -// death test. The child process is given the --gtest_filter and -// --gtest_internal_run_death_test flags such that it knows to run the -// current death test only. -DeathTest::TestRole WindowsDeathTest::AssumeRole() { - const UnitTestImpl* const impl = GetUnitTestImpl(); - const InternalRunDeathTestFlag* const flag = - impl->internal_run_death_test_flag(); - const TestInfo* const info = impl->current_test_info(); - const int death_test_index = info->result()->death_test_count(); - - if (flag != NULL) { - // ParseInternalRunDeathTestFlag() has performed all the necessary - // processing. - set_write_fd(flag->write_fd()); - return EXECUTE_TEST; - } - - // WindowsDeathTest uses an anonymous pipe to communicate results of - // a death test. - SECURITY_ATTRIBUTES handles_are_inheritable = { - sizeof(SECURITY_ATTRIBUTES), NULL, TRUE }; - HANDLE read_handle, write_handle; - GTEST_DEATH_TEST_CHECK_( - ::CreatePipe(&read_handle, &write_handle, &handles_are_inheritable, - 0) // Default buffer size. - != FALSE); - set_read_fd(::_open_osfhandle(reinterpret_cast(read_handle), - O_RDONLY)); - write_handle_.Reset(write_handle); - event_handle_.Reset(::CreateEvent( - &handles_are_inheritable, - TRUE, // The event will automatically reset to non-signaled state. - FALSE, // The initial state is non-signalled. - NULL)); // The even is unnamed. - GTEST_DEATH_TEST_CHECK_(event_handle_.Get() != NULL); - const std::string filter_flag = - std::string("--") + GTEST_FLAG_PREFIX_ + kFilterFlag + "=" + - info->test_case_name() + "." + info->name(); - const std::string internal_flag = - std::string("--") + GTEST_FLAG_PREFIX_ + kInternalRunDeathTestFlag + - "=" + file_ + "|" + StreamableToString(line_) + "|" + - StreamableToString(death_test_index) + "|" + - StreamableToString(static_cast(::GetCurrentProcessId())) + - // size_t has the same width as pointers on both 32-bit and 64-bit - // Windows platforms. - // See http://msdn.microsoft.com/en-us/library/tcxf1dw6.aspx. - "|" + StreamableToString(reinterpret_cast(write_handle)) + - "|" + StreamableToString(reinterpret_cast(event_handle_.Get())); - - char executable_path[_MAX_PATH + 1]; // NOLINT - GTEST_DEATH_TEST_CHECK_( - _MAX_PATH + 1 != ::GetModuleFileNameA(NULL, - executable_path, - _MAX_PATH)); - - std::string command_line = - std::string(::GetCommandLineA()) + " " + filter_flag + " \"" + - internal_flag + "\""; - - DeathTest::set_last_death_test_message(""); - - CaptureStderr(); - // Flush the log buffers since the log streams are shared with the child. - FlushInfoLog(); - - // The child process will share the standard handles with the parent. - STARTUPINFOA startup_info; - memset(&startup_info, 0, sizeof(STARTUPINFO)); - startup_info.dwFlags = STARTF_USESTDHANDLES; - startup_info.hStdInput = ::GetStdHandle(STD_INPUT_HANDLE); - startup_info.hStdOutput = ::GetStdHandle(STD_OUTPUT_HANDLE); - startup_info.hStdError = ::GetStdHandle(STD_ERROR_HANDLE); - - PROCESS_INFORMATION process_info; - GTEST_DEATH_TEST_CHECK_(::CreateProcessA( - executable_path, - const_cast(command_line.c_str()), - NULL, // Retuned process handle is not inheritable. - NULL, // Retuned thread handle is not inheritable. - TRUE, // Child inherits all inheritable handles (for write_handle_). - 0x0, // Default creation flags. - NULL, // Inherit the parent's environment. - UnitTest::GetInstance()->original_working_dir(), - &startup_info, - &process_info) != FALSE); - child_handle_.Reset(process_info.hProcess); - ::CloseHandle(process_info.hThread); - set_spawned(true); - return OVERSEE_TEST; -} -# else // We are not on Windows. - -// ForkingDeathTest provides implementations for most of the abstract -// methods of the DeathTest interface. Only the AssumeRole method is -// left undefined. -class ForkingDeathTest : public DeathTestImpl { - public: - ForkingDeathTest(const char* statement, const RE* regex); - - // All of these virtual functions are inherited from DeathTest. - virtual int Wait(); - - protected: - void set_child_pid(pid_t child_pid) { child_pid_ = child_pid; } - - private: - // PID of child process during death test; 0 in the child process itself. - pid_t child_pid_; -}; - -// Constructs a ForkingDeathTest. -ForkingDeathTest::ForkingDeathTest(const char* a_statement, const RE* a_regex) - : DeathTestImpl(a_statement, a_regex), - child_pid_(-1) {} - -// Waits for the child in a death test to exit, returning its exit -// status, or 0 if no child process exists. As a side effect, sets the -// outcome data member. -int ForkingDeathTest::Wait() { - if (!spawned()) - return 0; - - ReadAndInterpretStatusByte(); - - int status_value; - GTEST_DEATH_TEST_CHECK_SYSCALL_(waitpid(child_pid_, &status_value, 0)); - set_status(status_value); - return status_value; -} - -// A concrete death test class that forks, then immediately runs the test -// in the child process. -class NoExecDeathTest : public ForkingDeathTest { - public: - NoExecDeathTest(const char* a_statement, const RE* a_regex) : - ForkingDeathTest(a_statement, a_regex) { } - virtual TestRole AssumeRole(); -}; - -// The AssumeRole process for a fork-and-run death test. It implements a -// straightforward fork, with a simple pipe to transmit the status byte. -DeathTest::TestRole NoExecDeathTest::AssumeRole() { - const size_t thread_count = GetThreadCount(); - if (thread_count != 1) { - GTEST_LOG_(WARNING) << DeathTestThreadWarning(thread_count); - } - - int pipe_fd[2]; - GTEST_DEATH_TEST_CHECK_(pipe(pipe_fd) != -1); - - DeathTest::set_last_death_test_message(""); - CaptureStderr(); - // When we fork the process below, the log file buffers are copied, but the - // file descriptors are shared. We flush all log files here so that closing - // the file descriptors in the child process doesn't throw off the - // synchronization between descriptors and buffers in the parent process. - // This is as close to the fork as possible to avoid a race condition in case - // there are multiple threads running before the death test, and another - // thread writes to the log file. - FlushInfoLog(); - - const pid_t child_pid = fork(); - GTEST_DEATH_TEST_CHECK_(child_pid != -1); - set_child_pid(child_pid); - if (child_pid == 0) { - GTEST_DEATH_TEST_CHECK_SYSCALL_(close(pipe_fd[0])); - set_write_fd(pipe_fd[1]); - // Redirects all logging to stderr in the child process to prevent - // concurrent writes to the log files. We capture stderr in the parent - // process and append the child process' output to a log. - LogToStderr(); - // Event forwarding to the listeners of event listener API mush be shut - // down in death test subprocesses. - GetUnitTestImpl()->listeners()->SuppressEventForwarding(); - g_in_fast_death_test_child = true; - return EXECUTE_TEST; - } else { - GTEST_DEATH_TEST_CHECK_SYSCALL_(close(pipe_fd[1])); - set_read_fd(pipe_fd[0]); - set_spawned(true); - return OVERSEE_TEST; - } -} - -// A concrete death test class that forks and re-executes the main -// program from the beginning, with command-line flags set that cause -// only this specific death test to be run. -class ExecDeathTest : public ForkingDeathTest { - public: - ExecDeathTest(const char* a_statement, const RE* a_regex, - const char* file, int line) : - ForkingDeathTest(a_statement, a_regex), file_(file), line_(line) { } - virtual TestRole AssumeRole(); - private: - static ::std::vector - GetArgvsForDeathTestChildProcess() { - ::std::vector args = GetInjectableArgvs(); - return args; - } - // The name of the file in which the death test is located. - const char* const file_; - // The line number on which the death test is located. - const int line_; -}; - -// Utility class for accumulating command-line arguments. -class Arguments { - public: - Arguments() { - args_.push_back(NULL); - } - - ~Arguments() { - for (std::vector::iterator i = args_.begin(); i != args_.end(); - ++i) { - free(*i); - } - } - void AddArgument(const char* argument) { - args_.insert(args_.end() - 1, posix::StrDup(argument)); - } - - template - void AddArguments(const ::std::vector& arguments) { - for (typename ::std::vector::const_iterator i = arguments.begin(); - i != arguments.end(); - ++i) { - args_.insert(args_.end() - 1, posix::StrDup(i->c_str())); - } - } - char* const* Argv() { - return &args_[0]; - } - - private: - std::vector args_; -}; - -// A struct that encompasses the arguments to the child process of a -// threadsafe-style death test process. -struct ExecDeathTestArgs { - char* const* argv; // Command-line arguments for the child's call to exec - int close_fd; // File descriptor to close; the read end of a pipe -}; - -# if GTEST_OS_MAC -inline char** GetEnviron() { - // When Google Test is built as a framework on MacOS X, the environ variable - // is unavailable. Apple's documentation (man environ) recommends using - // _NSGetEnviron() instead. - return *_NSGetEnviron(); -} -# else -// Some POSIX platforms expect you to declare environ. extern "C" makes -// it reside in the global namespace. -extern "C" char** environ; -inline char** GetEnviron() { return environ; } -# endif // GTEST_OS_MAC - -# if !GTEST_OS_QNX -// The main function for a threadsafe-style death test child process. -// This function is called in a clone()-ed process and thus must avoid -// any potentially unsafe operations like malloc or libc functions. -static int ExecDeathTestChildMain(void* child_arg) { - ExecDeathTestArgs* const args = static_cast(child_arg); - GTEST_DEATH_TEST_CHECK_SYSCALL_(close(args->close_fd)); - - // We need to execute the test program in the same environment where - // it was originally invoked. Therefore we change to the original - // working directory first. - const char* const original_dir = - UnitTest::GetInstance()->original_working_dir(); - // We can safely call chdir() as it's a direct system call. - if (chdir(original_dir) != 0) { - DeathTestAbort(std::string("chdir(\"") + original_dir + "\") failed: " + - GetLastErrnoDescription()); - return EXIT_FAILURE; - } - - // We can safely call execve() as it's a direct system call. We - // cannot use execvp() as it's a libc function and thus potentially - // unsafe. Since execve() doesn't search the PATH, the user must - // invoke the test program via a valid path that contains at least - // one path separator. - execve(args->argv[0], args->argv, GetEnviron()); - DeathTestAbort(std::string("execve(") + args->argv[0] + ", ...) in " + - original_dir + " failed: " + - GetLastErrnoDescription()); - return EXIT_FAILURE; -} -# endif // !GTEST_OS_QNX - -// Two utility routines that together determine the direction the stack -// grows. -// This could be accomplished more elegantly by a single recursive -// function, but we want to guard against the unlikely possibility of -// a smart compiler optimizing the recursion away. -// -// GTEST_NO_INLINE_ is required to prevent GCC 4.6 from inlining -// StackLowerThanAddress into StackGrowsDown, which then doesn't give -// correct answer. -void StackLowerThanAddress(const void* ptr, bool* result) GTEST_NO_INLINE_; -void StackLowerThanAddress(const void* ptr, bool* result) { - int dummy; - *result = (&dummy < ptr); -} - -bool StackGrowsDown() { - int dummy; - bool result; - StackLowerThanAddress(&dummy, &result); - return result; -} - -// Spawns a child process with the same executable as the current process in -// a thread-safe manner and instructs it to run the death test. The -// implementation uses fork(2) + exec. On systems where clone(2) is -// available, it is used instead, being slightly more thread-safe. On QNX, -// fork supports only single-threaded environments, so this function uses -// spawn(2) there instead. The function dies with an error message if -// anything goes wrong. -static pid_t ExecDeathTestSpawnChild(char* const* argv, int close_fd) { - ExecDeathTestArgs args = { argv, close_fd }; - pid_t child_pid = -1; - -# if GTEST_OS_QNX - // Obtains the current directory and sets it to be closed in the child - // process. - const int cwd_fd = open(".", O_RDONLY); - GTEST_DEATH_TEST_CHECK_(cwd_fd != -1); - GTEST_DEATH_TEST_CHECK_SYSCALL_(fcntl(cwd_fd, F_SETFD, FD_CLOEXEC)); - // We need to execute the test program in the same environment where - // it was originally invoked. Therefore we change to the original - // working directory first. - const char* const original_dir = - UnitTest::GetInstance()->original_working_dir(); - // We can safely call chdir() as it's a direct system call. - if (chdir(original_dir) != 0) { - DeathTestAbort(std::string("chdir(\"") + original_dir + "\") failed: " + - GetLastErrnoDescription()); - return EXIT_FAILURE; - } - - int fd_flags; - // Set close_fd to be closed after spawn. - GTEST_DEATH_TEST_CHECK_SYSCALL_(fd_flags = fcntl(close_fd, F_GETFD)); - GTEST_DEATH_TEST_CHECK_SYSCALL_(fcntl(close_fd, F_SETFD, - fd_flags | FD_CLOEXEC)); - struct inheritance inherit = {0}; - // spawn is a system call. - child_pid = spawn(args.argv[0], 0, NULL, &inherit, args.argv, GetEnviron()); - // Restores the current working directory. - GTEST_DEATH_TEST_CHECK_(fchdir(cwd_fd) != -1); - GTEST_DEATH_TEST_CHECK_SYSCALL_(close(cwd_fd)); - -# else // GTEST_OS_QNX -# if GTEST_OS_LINUX - // When a SIGPROF signal is received while fork() or clone() are executing, - // the process may hang. To avoid this, we ignore SIGPROF here and re-enable - // it after the call to fork()/clone() is complete. - struct sigaction saved_sigprof_action; - struct sigaction ignore_sigprof_action; - memset(&ignore_sigprof_action, 0, sizeof(ignore_sigprof_action)); - sigemptyset(&ignore_sigprof_action.sa_mask); - ignore_sigprof_action.sa_handler = SIG_IGN; - GTEST_DEATH_TEST_CHECK_SYSCALL_(sigaction( - SIGPROF, &ignore_sigprof_action, &saved_sigprof_action)); -# endif // GTEST_OS_LINUX - -# if GTEST_HAS_CLONE - const bool use_fork = GTEST_FLAG(death_test_use_fork); - - if (!use_fork) { - static const bool stack_grows_down = StackGrowsDown(); - const size_t stack_size = getpagesize(); - // MMAP_ANONYMOUS is not defined on Mac, so we use MAP_ANON instead. - void* const stack = mmap(NULL, stack_size, PROT_READ | PROT_WRITE, - MAP_ANON | MAP_PRIVATE, -1, 0); - GTEST_DEATH_TEST_CHECK_(stack != MAP_FAILED); - - // Maximum stack alignment in bytes: For a downward-growing stack, this - // amount is subtracted from size of the stack space to get an address - // that is within the stack space and is aligned on all systems we care - // about. As far as I know there is no ABI with stack alignment greater - // than 64. We assume stack and stack_size already have alignment of - // kMaxStackAlignment. - const size_t kMaxStackAlignment = 64; - void* const stack_top = - static_cast(stack) + - (stack_grows_down ? stack_size - kMaxStackAlignment : 0); - GTEST_DEATH_TEST_CHECK_(stack_size > kMaxStackAlignment && - reinterpret_cast(stack_top) % kMaxStackAlignment == 0); - - child_pid = clone(&ExecDeathTestChildMain, stack_top, SIGCHLD, &args); - - GTEST_DEATH_TEST_CHECK_(munmap(stack, stack_size) != -1); - } -# else - const bool use_fork = true; -# endif // GTEST_HAS_CLONE - - if (use_fork && (child_pid = fork()) == 0) { - ExecDeathTestChildMain(&args); - _exit(0); - } -# endif // GTEST_OS_QNX -# if GTEST_OS_LINUX - GTEST_DEATH_TEST_CHECK_SYSCALL_( - sigaction(SIGPROF, &saved_sigprof_action, NULL)); -# endif // GTEST_OS_LINUX - - GTEST_DEATH_TEST_CHECK_(child_pid != -1); - return child_pid; -} - -// The AssumeRole process for a fork-and-exec death test. It re-executes the -// main program from the beginning, setting the --gtest_filter -// and --gtest_internal_run_death_test flags to cause only the current -// death test to be re-run. -DeathTest::TestRole ExecDeathTest::AssumeRole() { - const UnitTestImpl* const impl = GetUnitTestImpl(); - const InternalRunDeathTestFlag* const flag = - impl->internal_run_death_test_flag(); - const TestInfo* const info = impl->current_test_info(); - const int death_test_index = info->result()->death_test_count(); - - if (flag != NULL) { - set_write_fd(flag->write_fd()); - return EXECUTE_TEST; - } - - int pipe_fd[2]; - GTEST_DEATH_TEST_CHECK_(pipe(pipe_fd) != -1); - // Clear the close-on-exec flag on the write end of the pipe, lest - // it be closed when the child process does an exec: - GTEST_DEATH_TEST_CHECK_(fcntl(pipe_fd[1], F_SETFD, 0) != -1); - - const std::string filter_flag = - std::string("--") + GTEST_FLAG_PREFIX_ + kFilterFlag + "=" - + info->test_case_name() + "." + info->name(); - const std::string internal_flag = - std::string("--") + GTEST_FLAG_PREFIX_ + kInternalRunDeathTestFlag + "=" - + file_ + "|" + StreamableToString(line_) + "|" - + StreamableToString(death_test_index) + "|" - + StreamableToString(pipe_fd[1]); - Arguments args; - args.AddArguments(GetArgvsForDeathTestChildProcess()); - args.AddArgument(filter_flag.c_str()); - args.AddArgument(internal_flag.c_str()); - - DeathTest::set_last_death_test_message(""); - - CaptureStderr(); - // See the comment in NoExecDeathTest::AssumeRole for why the next line - // is necessary. - FlushInfoLog(); - - const pid_t child_pid = ExecDeathTestSpawnChild(args.Argv(), pipe_fd[0]); - GTEST_DEATH_TEST_CHECK_SYSCALL_(close(pipe_fd[1])); - set_child_pid(child_pid); - set_read_fd(pipe_fd[0]); - set_spawned(true); - return OVERSEE_TEST; -} - -# endif // !GTEST_OS_WINDOWS - -// Creates a concrete DeathTest-derived class that depends on the -// --gtest_death_test_style flag, and sets the pointer pointed to -// by the "test" argument to its address. If the test should be -// skipped, sets that pointer to NULL. Returns true, unless the -// flag is set to an invalid value. -bool DefaultDeathTestFactory::Create(const char* statement, const RE* regex, - const char* file, int line, - DeathTest** test) { - UnitTestImpl* const impl = GetUnitTestImpl(); - const InternalRunDeathTestFlag* const flag = - impl->internal_run_death_test_flag(); - const int death_test_index = impl->current_test_info() - ->increment_death_test_count(); - - if (flag != NULL) { - if (death_test_index > flag->index()) { - DeathTest::set_last_death_test_message( - "Death test count (" + StreamableToString(death_test_index) - + ") somehow exceeded expected maximum (" - + StreamableToString(flag->index()) + ")"); - return false; - } - - if (!(flag->file() == file && flag->line() == line && - flag->index() == death_test_index)) { - *test = NULL; - return true; - } - } - -# if GTEST_OS_WINDOWS - - if (GTEST_FLAG(death_test_style) == "threadsafe" || - GTEST_FLAG(death_test_style) == "fast") { - *test = new WindowsDeathTest(statement, regex, file, line); - } - -# else - - if (GTEST_FLAG(death_test_style) == "threadsafe") { - *test = new ExecDeathTest(statement, regex, file, line); - } else if (GTEST_FLAG(death_test_style) == "fast") { - *test = new NoExecDeathTest(statement, regex); - } - -# endif // GTEST_OS_WINDOWS - - else { // NOLINT - this is more readable than unbalanced brackets inside #if. - DeathTest::set_last_death_test_message( - "Unknown death test style \"" + GTEST_FLAG(death_test_style) - + "\" encountered"); - return false; - } - - return true; -} - -// Splits a given string on a given delimiter, populating a given -// vector with the fields. GTEST_HAS_DEATH_TEST implies that we have -// ::std::string, so we can use it here. -static void SplitString(const ::std::string& str, char delimiter, - ::std::vector< ::std::string>* dest) { - ::std::vector< ::std::string> parsed; - ::std::string::size_type pos = 0; - while (::testing::internal::AlwaysTrue()) { - const ::std::string::size_type colon = str.find(delimiter, pos); - if (colon == ::std::string::npos) { - parsed.push_back(str.substr(pos)); - break; - } else { - parsed.push_back(str.substr(pos, colon - pos)); - pos = colon + 1; - } - } - dest->swap(parsed); -} - -# if GTEST_OS_WINDOWS -// Recreates the pipe and event handles from the provided parameters, -// signals the event, and returns a file descriptor wrapped around the pipe -// handle. This function is called in the child process only. -int GetStatusFileDescriptor(unsigned int parent_process_id, - size_t write_handle_as_size_t, - size_t event_handle_as_size_t) { - AutoHandle parent_process_handle(::OpenProcess(PROCESS_DUP_HANDLE, - FALSE, // Non-inheritable. - parent_process_id)); - if (parent_process_handle.Get() == INVALID_HANDLE_VALUE) { - DeathTestAbort("Unable to open parent process " + - StreamableToString(parent_process_id)); - } - - // TODO(vladl@google.com): Replace the following check with a - // compile-time assertion when available. - GTEST_CHECK_(sizeof(HANDLE) <= sizeof(size_t)); - - const HANDLE write_handle = - reinterpret_cast(write_handle_as_size_t); - HANDLE dup_write_handle; - - // The newly initialized handle is accessible only in in the parent - // process. To obtain one accessible within the child, we need to use - // DuplicateHandle. - if (!::DuplicateHandle(parent_process_handle.Get(), write_handle, - ::GetCurrentProcess(), &dup_write_handle, - 0x0, // Requested privileges ignored since - // DUPLICATE_SAME_ACCESS is used. - FALSE, // Request non-inheritable handler. - DUPLICATE_SAME_ACCESS)) { - DeathTestAbort("Unable to duplicate the pipe handle " + - StreamableToString(write_handle_as_size_t) + - " from the parent process " + - StreamableToString(parent_process_id)); - } - - const HANDLE event_handle = reinterpret_cast(event_handle_as_size_t); - HANDLE dup_event_handle; - - if (!::DuplicateHandle(parent_process_handle.Get(), event_handle, - ::GetCurrentProcess(), &dup_event_handle, - 0x0, - FALSE, - DUPLICATE_SAME_ACCESS)) { - DeathTestAbort("Unable to duplicate the event handle " + - StreamableToString(event_handle_as_size_t) + - " from the parent process " + - StreamableToString(parent_process_id)); - } - - const int write_fd = - ::_open_osfhandle(reinterpret_cast(dup_write_handle), O_APPEND); - if (write_fd == -1) { - DeathTestAbort("Unable to convert pipe handle " + - StreamableToString(write_handle_as_size_t) + - " to a file descriptor"); - } - - // Signals the parent that the write end of the pipe has been acquired - // so the parent can release its own write end. - ::SetEvent(dup_event_handle); - - return write_fd; -} -# endif // GTEST_OS_WINDOWS - -// Returns a newly created InternalRunDeathTestFlag object with fields -// initialized from the GTEST_FLAG(internal_run_death_test) flag if -// the flag is specified; otherwise returns NULL. -InternalRunDeathTestFlag* ParseInternalRunDeathTestFlag() { - if (GTEST_FLAG(internal_run_death_test) == "") return NULL; - - // GTEST_HAS_DEATH_TEST implies that we have ::std::string, so we - // can use it here. - int line = -1; - int index = -1; - ::std::vector< ::std::string> fields; - SplitString(GTEST_FLAG(internal_run_death_test).c_str(), '|', &fields); - int write_fd = -1; - -# if GTEST_OS_WINDOWS - - unsigned int parent_process_id = 0; - size_t write_handle_as_size_t = 0; - size_t event_handle_as_size_t = 0; - - if (fields.size() != 6 - || !ParseNaturalNumber(fields[1], &line) - || !ParseNaturalNumber(fields[2], &index) - || !ParseNaturalNumber(fields[3], &parent_process_id) - || !ParseNaturalNumber(fields[4], &write_handle_as_size_t) - || !ParseNaturalNumber(fields[5], &event_handle_as_size_t)) { - DeathTestAbort("Bad --gtest_internal_run_death_test flag: " + - GTEST_FLAG(internal_run_death_test)); - } - write_fd = GetStatusFileDescriptor(parent_process_id, - write_handle_as_size_t, - event_handle_as_size_t); -# else - - if (fields.size() != 4 - || !ParseNaturalNumber(fields[1], &line) - || !ParseNaturalNumber(fields[2], &index) - || !ParseNaturalNumber(fields[3], &write_fd)) { - DeathTestAbort("Bad --gtest_internal_run_death_test flag: " - + GTEST_FLAG(internal_run_death_test)); - } - -# endif // GTEST_OS_WINDOWS - - return new InternalRunDeathTestFlag(fields[0], line, index, write_fd); -} - -} // namespace internal - -#endif // GTEST_HAS_DEATH_TEST - -} // namespace testing -// Copyright 2008, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Authors: keith.ray@gmail.com (Keith Ray) - - -#include - -#if GTEST_OS_WINDOWS_MOBILE -# include -#elif GTEST_OS_WINDOWS -# include -# include -#elif GTEST_OS_SYMBIAN -// Symbian OpenC has PATH_MAX in sys/syslimits.h -# include -#else -# include -# include // Some Linux distributions define PATH_MAX here. -#endif // GTEST_OS_WINDOWS_MOBILE - -#if GTEST_OS_WINDOWS -# define GTEST_PATH_MAX_ _MAX_PATH -#elif defined(PATH_MAX) -# define GTEST_PATH_MAX_ PATH_MAX -#elif defined(_XOPEN_PATH_MAX) -# define GTEST_PATH_MAX_ _XOPEN_PATH_MAX -#else -# define GTEST_PATH_MAX_ _POSIX_PATH_MAX -#endif // GTEST_OS_WINDOWS - - -namespace testing { -namespace internal { - -#if GTEST_OS_WINDOWS -// On Windows, '\\' is the standard path separator, but many tools and the -// Windows API also accept '/' as an alternate path separator. Unless otherwise -// noted, a file path can contain either kind of path separators, or a mixture -// of them. -const char kPathSeparator = '\\'; -const char kAlternatePathSeparator = '/'; -const char kPathSeparatorString[] = "\\"; -const char kAlternatePathSeparatorString[] = "/"; -# if GTEST_OS_WINDOWS_MOBILE -// Windows CE doesn't have a current directory. You should not use -// the current directory in tests on Windows CE, but this at least -// provides a reasonable fallback. -const char kCurrentDirectoryString[] = "\\"; -// Windows CE doesn't define INVALID_FILE_ATTRIBUTES -const DWORD kInvalidFileAttributes = 0xffffffff; -# else -const char kCurrentDirectoryString[] = ".\\"; -# endif // GTEST_OS_WINDOWS_MOBILE -#else -const char kPathSeparator = '/'; -const char kPathSeparatorString[] = "/"; -const char kCurrentDirectoryString[] = "./"; -#endif // GTEST_OS_WINDOWS - -// Returns whether the given character is a valid path separator. -static bool IsPathSeparator(char c) { -#if GTEST_HAS_ALT_PATH_SEP_ - return (c == kPathSeparator) || (c == kAlternatePathSeparator); -#else - return c == kPathSeparator; -#endif -} - -// Returns the current working directory, or "" if unsuccessful. -FilePath FilePath::GetCurrentDir() { -#if GTEST_OS_WINDOWS_MOBILE - // Windows CE doesn't have a current directory, so we just return - // something reasonable. - return FilePath(kCurrentDirectoryString); -#elif GTEST_OS_WINDOWS - char cwd[GTEST_PATH_MAX_ + 1] = { '\0' }; - return FilePath(_getcwd(cwd, sizeof(cwd)) == NULL ? "" : cwd); -#else - char cwd[GTEST_PATH_MAX_ + 1] = { '\0' }; - return FilePath(getcwd(cwd, sizeof(cwd)) == NULL ? "" : cwd); -#endif // GTEST_OS_WINDOWS_MOBILE -} - -// Returns a copy of the FilePath with the case-insensitive extension removed. -// Example: FilePath("dir/file.exe").RemoveExtension("EXE") returns -// FilePath("dir/file"). If a case-insensitive extension is not -// found, returns a copy of the original FilePath. -FilePath FilePath::RemoveExtension(const char* extension) const { - const std::string dot_extension = std::string(".") + extension; - if (String::EndsWithCaseInsensitive(pathname_, dot_extension)) { - return FilePath(pathname_.substr( - 0, pathname_.length() - dot_extension.length())); - } - return *this; -} - -// Returns a pointer to the last occurence of a valid path separator in -// the FilePath. On Windows, for example, both '/' and '\' are valid path -// separators. Returns NULL if no path separator was found. -const char* FilePath::FindLastPathSeparator() const { - const char* const last_sep = strrchr(c_str(), kPathSeparator); -#if GTEST_HAS_ALT_PATH_SEP_ - const char* const last_alt_sep = strrchr(c_str(), kAlternatePathSeparator); - // Comparing two pointers of which only one is NULL is undefined. - if (last_alt_sep != NULL && - (last_sep == NULL || last_alt_sep > last_sep)) { - return last_alt_sep; - } -#endif - return last_sep; -} - -// Returns a copy of the FilePath with the directory part removed. -// Example: FilePath("path/to/file").RemoveDirectoryName() returns -// FilePath("file"). If there is no directory part ("just_a_file"), it returns -// the FilePath unmodified. If there is no file part ("just_a_dir/") it -// returns an empty FilePath (""). -// On Windows platform, '\' is the path separator, otherwise it is '/'. -FilePath FilePath::RemoveDirectoryName() const { - const char* const last_sep = FindLastPathSeparator(); - return last_sep ? FilePath(last_sep + 1) : *this; -} - -// RemoveFileName returns the directory path with the filename removed. -// Example: FilePath("path/to/file").RemoveFileName() returns "path/to/". -// If the FilePath is "a_file" or "/a_file", RemoveFileName returns -// FilePath("./") or, on Windows, FilePath(".\\"). If the filepath does -// not have a file, like "just/a/dir/", it returns the FilePath unmodified. -// On Windows platform, '\' is the path separator, otherwise it is '/'. -FilePath FilePath::RemoveFileName() const { - const char* const last_sep = FindLastPathSeparator(); - std::string dir; - if (last_sep) { - dir = std::string(c_str(), last_sep + 1 - c_str()); - } else { - dir = kCurrentDirectoryString; - } - return FilePath(dir); -} - -// Helper functions for naming files in a directory for xml output. - -// Given directory = "dir", base_name = "test", number = 0, -// extension = "xml", returns "dir/test.xml". If number is greater -// than zero (e.g., 12), returns "dir/test_12.xml". -// On Windows platform, uses \ as the separator rather than /. -FilePath FilePath::MakeFileName(const FilePath& directory, - const FilePath& base_name, - int number, - const char* extension) { - std::string file; - if (number == 0) { - file = base_name.string() + "." + extension; - } else { - file = base_name.string() + "_" + StreamableToString(number) - + "." + extension; - } - return ConcatPaths(directory, FilePath(file)); -} - -// Given directory = "dir", relative_path = "test.xml", returns "dir/test.xml". -// On Windows, uses \ as the separator rather than /. -FilePath FilePath::ConcatPaths(const FilePath& directory, - const FilePath& relative_path) { - if (directory.IsEmpty()) - return relative_path; - const FilePath dir(directory.RemoveTrailingPathSeparator()); - return FilePath(dir.string() + kPathSeparator + relative_path.string()); -} - -// Returns true if pathname describes something findable in the file-system, -// either a file, directory, or whatever. -bool FilePath::FileOrDirectoryExists() const { -#if GTEST_OS_WINDOWS_MOBILE - LPCWSTR unicode = String::AnsiToUtf16(pathname_.c_str()); - const DWORD attributes = GetFileAttributes(unicode); - delete [] unicode; - return attributes != kInvalidFileAttributes; -#else - posix::StatStruct file_stat; - return posix::Stat(pathname_.c_str(), &file_stat) == 0; -#endif // GTEST_OS_WINDOWS_MOBILE -} - -// Returns true if pathname describes a directory in the file-system -// that exists. -bool FilePath::DirectoryExists() const { - bool result = false; -#if GTEST_OS_WINDOWS - // Don't strip off trailing separator if path is a root directory on - // Windows (like "C:\\"). - const FilePath& path(IsRootDirectory() ? *this : - RemoveTrailingPathSeparator()); -#else - const FilePath& path(*this); -#endif - -#if GTEST_OS_WINDOWS_MOBILE - LPCWSTR unicode = String::AnsiToUtf16(path.c_str()); - const DWORD attributes = GetFileAttributes(unicode); - delete [] unicode; - if ((attributes != kInvalidFileAttributes) && - (attributes & FILE_ATTRIBUTE_DIRECTORY)) { - result = true; - } -#else - posix::StatStruct file_stat; - result = posix::Stat(path.c_str(), &file_stat) == 0 && - posix::IsDir(file_stat); -#endif // GTEST_OS_WINDOWS_MOBILE - - return result; -} - -// Returns true if pathname describes a root directory. (Windows has one -// root directory per disk drive.) -bool FilePath::IsRootDirectory() const { -#if GTEST_OS_WINDOWS - // TODO(wan@google.com): on Windows a network share like - // \\server\share can be a root directory, although it cannot be the - // current directory. Handle this properly. - return pathname_.length() == 3 && IsAbsolutePath(); -#else - return pathname_.length() == 1 && IsPathSeparator(pathname_.c_str()[0]); -#endif -} - -// Returns true if pathname describes an absolute path. -bool FilePath::IsAbsolutePath() const { - const char* const name = pathname_.c_str(); -#if GTEST_OS_WINDOWS - return pathname_.length() >= 3 && - ((name[0] >= 'a' && name[0] <= 'z') || - (name[0] >= 'A' && name[0] <= 'Z')) && - name[1] == ':' && - IsPathSeparator(name[2]); -#else - return IsPathSeparator(name[0]); -#endif -} - -// Returns a pathname for a file that does not currently exist. The pathname -// will be directory/base_name.extension or -// directory/base_name_.extension if directory/base_name.extension -// already exists. The number will be incremented until a pathname is found -// that does not already exist. -// Examples: 'dir/foo_test.xml' or 'dir/foo_test_1.xml'. -// There could be a race condition if two or more processes are calling this -// function at the same time -- they could both pick the same filename. -FilePath FilePath::GenerateUniqueFileName(const FilePath& directory, - const FilePath& base_name, - const char* extension) { - FilePath full_pathname; - int number = 0; - do { - full_pathname.Set(MakeFileName(directory, base_name, number++, extension)); - } while (full_pathname.FileOrDirectoryExists()); - return full_pathname; -} - -// Returns true if FilePath ends with a path separator, which indicates that -// it is intended to represent a directory. Returns false otherwise. -// This does NOT check that a directory (or file) actually exists. -bool FilePath::IsDirectory() const { - return !pathname_.empty() && - IsPathSeparator(pathname_.c_str()[pathname_.length() - 1]); -} - -// Create directories so that path exists. Returns true if successful or if -// the directories already exist; returns false if unable to create directories -// for any reason. -bool FilePath::CreateDirectoriesRecursively() const { - if (!this->IsDirectory()) { - return false; - } - - if (pathname_.length() == 0 || this->DirectoryExists()) { - return true; - } - - const FilePath parent(this->RemoveTrailingPathSeparator().RemoveFileName()); - return parent.CreateDirectoriesRecursively() && this->CreateFolder(); -} - -// Create the directory so that path exists. Returns true if successful or -// if the directory already exists; returns false if unable to create the -// directory for any reason, including if the parent directory does not -// exist. Not named "CreateDirectory" because that's a macro on Windows. -bool FilePath::CreateFolder() const { -#if GTEST_OS_WINDOWS_MOBILE - FilePath removed_sep(this->RemoveTrailingPathSeparator()); - LPCWSTR unicode = String::AnsiToUtf16(removed_sep.c_str()); - int result = CreateDirectory(unicode, NULL) ? 0 : -1; - delete [] unicode; -#elif GTEST_OS_WINDOWS - int result = _mkdir(pathname_.c_str()); -#else - int result = mkdir(pathname_.c_str(), 0777); -#endif // GTEST_OS_WINDOWS_MOBILE - - if (result == -1) { - return this->DirectoryExists(); // An error is OK if the directory exists. - } - return true; // No error. -} - -// If input name has a trailing separator character, remove it and return the -// name, otherwise return the name string unmodified. -// On Windows platform, uses \ as the separator, other platforms use /. -FilePath FilePath::RemoveTrailingPathSeparator() const { - return IsDirectory() - ? FilePath(pathname_.substr(0, pathname_.length() - 1)) - : *this; -} - -// Removes any redundant separators that might be in the pathname. -// For example, "bar///foo" becomes "bar/foo". Does not eliminate other -// redundancies that might be in a pathname involving "." or "..". -// TODO(wan@google.com): handle Windows network shares (e.g. \\server\share). -void FilePath::Normalize() { - if (pathname_.c_str() == NULL) { - pathname_ = ""; - return; - } - const char* src = pathname_.c_str(); - char* const dest = new char[pathname_.length() + 1]; - char* dest_ptr = dest; - memset(dest_ptr, 0, pathname_.length() + 1); - - while (*src != '\0') { - *dest_ptr = *src; - if (!IsPathSeparator(*src)) { - src++; - } else { -#if GTEST_HAS_ALT_PATH_SEP_ - if (*dest_ptr == kAlternatePathSeparator) { - *dest_ptr = kPathSeparator; - } -#endif - while (IsPathSeparator(*src)) - src++; - } - dest_ptr++; - } - *dest_ptr = '\0'; - pathname_ = dest; - delete[] dest; -} - -} // namespace internal -} // namespace testing -// Copyright 2008, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: wan@google.com (Zhanyong Wan) - - -#include -#include -#include -#include - -#if GTEST_OS_WINDOWS_MOBILE -# include // For TerminateProcess() -#elif GTEST_OS_WINDOWS -# include -# include -#else -# include -#endif // GTEST_OS_WINDOWS_MOBILE - -#if GTEST_OS_MAC -# include -# include -# include -#endif // GTEST_OS_MAC - -#if GTEST_OS_QNX -# include -# include -#endif // GTEST_OS_QNX - - -// Indicates that this translation unit is part of Google Test's -// implementation. It must come before gtest-internal-inl.h is -// included, or there will be a compiler error. This trick is to -// prevent a user from accidentally including gtest-internal-inl.h in -// his code. -#define GTEST_IMPLEMENTATION_ 1 -#undef GTEST_IMPLEMENTATION_ - -namespace testing { -namespace internal { - -#if defined(_MSC_VER) || defined(__BORLANDC__) -// MSVC and C++Builder do not provide a definition of STDERR_FILENO. -const int kStdOutFileno = 1; -const int kStdErrFileno = 2; -#else -const int kStdOutFileno = STDOUT_FILENO; -const int kStdErrFileno = STDERR_FILENO; -#endif // _MSC_VER - -#if GTEST_OS_MAC - -// Returns the number of threads running in the process, or 0 to indicate that -// we cannot detect it. -size_t GetThreadCount() { - const task_t task = mach_task_self(); - mach_msg_type_number_t thread_count; - thread_act_array_t thread_list; - const kern_return_t status = task_threads(task, &thread_list, &thread_count); - if (status == KERN_SUCCESS) { - // task_threads allocates resources in thread_list and we need to free them - // to avoid leaks. - vm_deallocate(task, - reinterpret_cast(thread_list), - sizeof(thread_t) * thread_count); - return static_cast(thread_count); - } else { - return 0; - } -} - -#elif GTEST_OS_QNX - -// Returns the number of threads running in the process, or 0 to indicate that -// we cannot detect it. -size_t GetThreadCount() { - const int fd = open("/proc/self/as", O_RDONLY); - if (fd < 0) { - return 0; - } - procfs_info process_info; - const int status = - devctl(fd, DCMD_PROC_INFO, &process_info, sizeof(process_info), NULL); - close(fd); - if (status == EOK) { - return static_cast(process_info.num_threads); - } else { - return 0; - } -} - -#else - -size_t GetThreadCount() { - // There's no portable way to detect the number of threads, so we just - // return 0 to indicate that we cannot detect it. - return 0; -} - -#endif // GTEST_OS_MAC - -#if GTEST_USES_POSIX_RE - -// Implements RE. Currently only needed for death tests. - -RE::~RE() { - if (is_valid_) { - // regfree'ing an invalid regex might crash because the content - // of the regex is undefined. Since the regex's are essentially - // the same, one cannot be valid (or invalid) without the other - // being so too. - regfree(&partial_regex_); - regfree(&full_regex_); - } - free(const_cast(pattern_)); -} - -// Returns true iff regular expression re matches the entire str. -bool RE::FullMatch(const char* str, const RE& re) { - if (!re.is_valid_) return false; - - regmatch_t match; - return regexec(&re.full_regex_, str, 1, &match, 0) == 0; -} - -// Returns true iff regular expression re matches a substring of str -// (including str itself). -bool RE::PartialMatch(const char* str, const RE& re) { - if (!re.is_valid_) return false; - - regmatch_t match; - return regexec(&re.partial_regex_, str, 1, &match, 0) == 0; -} - -// Initializes an RE from its string representation. -void RE::Init(const char* regex) { - pattern_ = posix::StrDup(regex); - - // Reserves enough bytes to hold the regular expression used for a - // full match. - const size_t full_regex_len = strlen(regex) + 10; - char* const full_pattern = new char[full_regex_len]; - - snprintf(full_pattern, full_regex_len, "^(%s)$", regex); - is_valid_ = regcomp(&full_regex_, full_pattern, REG_EXTENDED) == 0; - // We want to call regcomp(&partial_regex_, ...) even if the - // previous expression returns false. Otherwise partial_regex_ may - // not be properly initialized can may cause trouble when it's - // freed. - // - // Some implementation of POSIX regex (e.g. on at least some - // versions of Cygwin) doesn't accept the empty string as a valid - // regex. We change it to an equivalent form "()" to be safe. - if (is_valid_) { - const char* const partial_regex = (*regex == '\0') ? "()" : regex; - is_valid_ = regcomp(&partial_regex_, partial_regex, REG_EXTENDED) == 0; - } - EXPECT_TRUE(is_valid_) - << "Regular expression \"" << regex - << "\" is not a valid POSIX Extended regular expression."; - - delete[] full_pattern; -} - -#elif GTEST_USES_SIMPLE_RE - -// Returns true iff ch appears anywhere in str (excluding the -// terminating '\0' character). -bool IsInSet(char ch, const char* str) { - return ch != '\0' && strchr(str, ch) != NULL; -} - -// Returns true iff ch belongs to the given classification. Unlike -// similar functions in , these aren't affected by the -// current locale. -bool IsAsciiDigit(char ch) { return '0' <= ch && ch <= '9'; } -bool IsAsciiPunct(char ch) { - return IsInSet(ch, "^-!\"#$%&'()*+,./:;<=>?@[\\]_`{|}~"); -} -bool IsRepeat(char ch) { return IsInSet(ch, "?*+"); } -bool IsAsciiWhiteSpace(char ch) { return IsInSet(ch, " \f\n\r\t\v"); } -bool IsAsciiWordChar(char ch) { - return ('a' <= ch && ch <= 'z') || ('A' <= ch && ch <= 'Z') || - ('0' <= ch && ch <= '9') || ch == '_'; -} - -// Returns true iff "\\c" is a supported escape sequence. -bool IsValidEscape(char c) { - return (IsAsciiPunct(c) || IsInSet(c, "dDfnrsStvwW")); -} - -// Returns true iff the given atom (specified by escaped and pattern) -// matches ch. The result is undefined if the atom is invalid. -bool AtomMatchesChar(bool escaped, char pattern_char, char ch) { - if (escaped) { // "\\p" where p is pattern_char. - switch (pattern_char) { - case 'd': return IsAsciiDigit(ch); - case 'D': return !IsAsciiDigit(ch); - case 'f': return ch == '\f'; - case 'n': return ch == '\n'; - case 'r': return ch == '\r'; - case 's': return IsAsciiWhiteSpace(ch); - case 'S': return !IsAsciiWhiteSpace(ch); - case 't': return ch == '\t'; - case 'v': return ch == '\v'; - case 'w': return IsAsciiWordChar(ch); - case 'W': return !IsAsciiWordChar(ch); - } - return IsAsciiPunct(pattern_char) && pattern_char == ch; - } - - return (pattern_char == '.' && ch != '\n') || pattern_char == ch; -} - -// Helper function used by ValidateRegex() to format error messages. -std::string FormatRegexSyntaxError(const char* regex, int index) { - return (Message() << "Syntax error at index " << index - << " in simple regular expression \"" << regex << "\": ").GetString(); -} - -// Generates non-fatal failures and returns false if regex is invalid; -// otherwise returns true. -bool ValidateRegex(const char* regex) { - if (regex == NULL) { - // TODO(wan@google.com): fix the source file location in the - // assertion failures to match where the regex is used in user - // code. - ADD_FAILURE() << "NULL is not a valid simple regular expression."; - return false; - } - - bool is_valid = true; - - // True iff ?, *, or + can follow the previous atom. - bool prev_repeatable = false; - for (int i = 0; regex[i]; i++) { - if (regex[i] == '\\') { // An escape sequence - i++; - if (regex[i] == '\0') { - ADD_FAILURE() << FormatRegexSyntaxError(regex, i - 1) - << "'\\' cannot appear at the end."; - return false; - } - - if (!IsValidEscape(regex[i])) { - ADD_FAILURE() << FormatRegexSyntaxError(regex, i - 1) - << "invalid escape sequence \"\\" << regex[i] << "\"."; - is_valid = false; - } - prev_repeatable = true; - } else { // Not an escape sequence. - const char ch = regex[i]; - - if (ch == '^' && i > 0) { - ADD_FAILURE() << FormatRegexSyntaxError(regex, i) - << "'^' can only appear at the beginning."; - is_valid = false; - } else if (ch == '$' && regex[i + 1] != '\0') { - ADD_FAILURE() << FormatRegexSyntaxError(regex, i) - << "'$' can only appear at the end."; - is_valid = false; - } else if (IsInSet(ch, "()[]{}|")) { - ADD_FAILURE() << FormatRegexSyntaxError(regex, i) - << "'" << ch << "' is unsupported."; - is_valid = false; - } else if (IsRepeat(ch) && !prev_repeatable) { - ADD_FAILURE() << FormatRegexSyntaxError(regex, i) - << "'" << ch << "' can only follow a repeatable token."; - is_valid = false; - } - - prev_repeatable = !IsInSet(ch, "^$?*+"); - } - } - - return is_valid; -} - -// Matches a repeated regex atom followed by a valid simple regular -// expression. The regex atom is defined as c if escaped is false, -// or \c otherwise. repeat is the repetition meta character (?, *, -// or +). The behavior is undefined if str contains too many -// characters to be indexable by size_t, in which case the test will -// probably time out anyway. We are fine with this limitation as -// std::string has it too. -bool MatchRepetitionAndRegexAtHead( - bool escaped, char c, char repeat, const char* regex, - const char* str) { - const size_t min_count = (repeat == '+') ? 1 : 0; - const size_t max_count = (repeat == '?') ? 1 : - static_cast(-1) - 1; - // We cannot call numeric_limits::max() as it conflicts with the - // max() macro on Windows. - - for (size_t i = 0; i <= max_count; ++i) { - // We know that the atom matches each of the first i characters in str. - if (i >= min_count && MatchRegexAtHead(regex, str + i)) { - // We have enough matches at the head, and the tail matches too. - // Since we only care about *whether* the pattern matches str - // (as opposed to *how* it matches), there is no need to find a - // greedy match. - return true; - } - if (str[i] == '\0' || !AtomMatchesChar(escaped, c, str[i])) - return false; - } - return false; -} - -// Returns true iff regex matches a prefix of str. regex must be a -// valid simple regular expression and not start with "^", or the -// result is undefined. -bool MatchRegexAtHead(const char* regex, const char* str) { - if (*regex == '\0') // An empty regex matches a prefix of anything. - return true; - - // "$" only matches the end of a string. Note that regex being - // valid guarantees that there's nothing after "$" in it. - if (*regex == '$') - return *str == '\0'; - - // Is the first thing in regex an escape sequence? - const bool escaped = *regex == '\\'; - if (escaped) - ++regex; - if (IsRepeat(regex[1])) { - // MatchRepetitionAndRegexAtHead() calls MatchRegexAtHead(), so - // here's an indirect recursion. It terminates as the regex gets - // shorter in each recursion. - return MatchRepetitionAndRegexAtHead( - escaped, regex[0], regex[1], regex + 2, str); - } else { - // regex isn't empty, isn't "$", and doesn't start with a - // repetition. We match the first atom of regex with the first - // character of str and recurse. - return (*str != '\0') && AtomMatchesChar(escaped, *regex, *str) && - MatchRegexAtHead(regex + 1, str + 1); - } -} - -// Returns true iff regex matches any substring of str. regex must be -// a valid simple regular expression, or the result is undefined. -// -// The algorithm is recursive, but the recursion depth doesn't exceed -// the regex length, so we won't need to worry about running out of -// stack space normally. In rare cases the time complexity can be -// exponential with respect to the regex length + the string length, -// but usually it's must faster (often close to linear). -bool MatchRegexAnywhere(const char* regex, const char* str) { - if (regex == NULL || str == NULL) - return false; - - if (*regex == '^') - return MatchRegexAtHead(regex + 1, str); - - // A successful match can be anywhere in str. - do { - if (MatchRegexAtHead(regex, str)) - return true; - } while (*str++ != '\0'); - return false; -} - -// Implements the RE class. - -RE::~RE() { - free(const_cast(pattern_)); - free(const_cast(full_pattern_)); -} - -// Returns true iff regular expression re matches the entire str. -bool RE::FullMatch(const char* str, const RE& re) { - return re.is_valid_ && MatchRegexAnywhere(re.full_pattern_, str); -} - -// Returns true iff regular expression re matches a substring of str -// (including str itself). -bool RE::PartialMatch(const char* str, const RE& re) { - return re.is_valid_ && MatchRegexAnywhere(re.pattern_, str); -} - -// Initializes an RE from its string representation. -void RE::Init(const char* regex) { - pattern_ = full_pattern_ = NULL; - if (regex != NULL) { - pattern_ = posix::StrDup(regex); - } - - is_valid_ = ValidateRegex(regex); - if (!is_valid_) { - // No need to calculate the full pattern when the regex is invalid. - return; - } - - const size_t len = strlen(regex); - // Reserves enough bytes to hold the regular expression used for a - // full match: we need space to prepend a '^', append a '$', and - // terminate the string with '\0'. - char* buffer = static_cast(malloc(len + 3)); - full_pattern_ = buffer; - - if (*regex != '^') - *buffer++ = '^'; // Makes sure full_pattern_ starts with '^'. - - // We don't use snprintf or strncpy, as they trigger a warning when - // compiled with VC++ 8.0. - memcpy(buffer, regex, len); - buffer += len; - - if (len == 0 || regex[len - 1] != '$') - *buffer++ = '$'; // Makes sure full_pattern_ ends with '$'. - - *buffer = '\0'; -} - -#endif // GTEST_USES_POSIX_RE - -const char kUnknownFile[] = "unknown file"; - -// Formats a source file path and a line number as they would appear -// in an error message from the compiler used to compile this code. -GTEST_API_ ::std::string FormatFileLocation(const char* file, int line) { - const std::string file_name(file == NULL ? kUnknownFile : file); - - if (line < 0) { - return file_name + ":"; - } -#ifdef _MSC_VER - return file_name + "(" + StreamableToString(line) + "):"; -#else - return file_name + ":" + StreamableToString(line) + ":"; -#endif // _MSC_VER -} - -// Formats a file location for compiler-independent XML output. -// Although this function is not platform dependent, we put it next to -// FormatFileLocation in order to contrast the two functions. -// Note that FormatCompilerIndependentFileLocation() does NOT append colon -// to the file location it produces, unlike FormatFileLocation(). -GTEST_API_ ::std::string FormatCompilerIndependentFileLocation( - const char* file, int line) { - const std::string file_name(file == NULL ? kUnknownFile : file); - - if (line < 0) - return file_name; - else - return file_name + ":" + StreamableToString(line); -} - - -GTestLog::GTestLog(GTestLogSeverity severity, const char* file, int line) - : severity_(severity) { - const char* const marker = - severity == GTEST_INFO ? "[ INFO ]" : - severity == GTEST_WARNING ? "[WARNING]" : - severity == GTEST_ERROR ? "[ ERROR ]" : "[ FATAL ]"; - GetStream() << ::std::endl << marker << " " - << FormatFileLocation(file, line).c_str() << ": "; -} - -// Flushes the buffers and, if severity is GTEST_FATAL, aborts the program. -GTestLog::~GTestLog() { - GetStream() << ::std::endl; - if (severity_ == GTEST_FATAL) { - fflush(stderr); - posix::Abort(); - } -} -// Disable Microsoft deprecation warnings for POSIX functions called from -// this class (creat, dup, dup2, and close) -#ifdef _MSC_VER -# pragma warning(push) -# pragma warning(disable: 4996) -#endif // _MSC_VER - -#if GTEST_HAS_STREAM_REDIRECTION - -// Object that captures an output stream (stdout/stderr). -class CapturedStream { - public: - // The ctor redirects the stream to a temporary file. - explicit CapturedStream(int fd) : fd_(fd), uncaptured_fd_(dup(fd)) { -# if GTEST_OS_WINDOWS - char temp_dir_path[MAX_PATH + 1] = { '\0' }; // NOLINT - char temp_file_path[MAX_PATH + 1] = { '\0' }; // NOLINT - - ::GetTempPathA(sizeof(temp_dir_path), temp_dir_path); - const UINT success = ::GetTempFileNameA(temp_dir_path, - "gtest_redir", - 0, // Generate unique file name. - temp_file_path); - GTEST_CHECK_(success != 0) - << "Unable to create a temporary file in " << temp_dir_path; - const int captured_fd = creat(temp_file_path, _S_IREAD | _S_IWRITE); - GTEST_CHECK_(captured_fd != -1) << "Unable to open temporary file " - << temp_file_path; - filename_ = temp_file_path; -# else - // There's no guarantee that a test has write access to the current - // directory, so we create the temporary file in the /tmp directory - // instead. We use /tmp on most systems, and /sdcard on Android. - // That's because Android doesn't have /tmp. -# if GTEST_OS_LINUX_ANDROID - // Note: Android applications are expected to call the framework's - // Context.getExternalStorageDirectory() method through JNI to get - // the location of the world-writable SD Card directory. However, - // this requires a Context handle, which cannot be retrieved - // globally from native code. Doing so also precludes running the - // code as part of a regular standalone executable, which doesn't - // run in a Dalvik process (e.g. when running it through 'adb shell'). - // - // The location /sdcard is directly accessible from native code - // and is the only location (unofficially) supported by the Android - // team. It's generally a symlink to the real SD Card mount point - // which can be /mnt/sdcard, /mnt/sdcard0, /system/media/sdcard, or - // other OEM-customized locations. Never rely on these, and always - // use /sdcard. - char name_template[] = "/sdcard/gtest_captured_stream.XXXXXX"; -# else - char name_template[] = "/tmp/captured_stream.XXXXXX"; -# endif // GTEST_OS_LINUX_ANDROID - const int captured_fd = mkstemp(name_template); - filename_ = name_template; -# endif // GTEST_OS_WINDOWS - fflush(NULL); - dup2(captured_fd, fd_); - close(captured_fd); - } - - ~CapturedStream() { - remove(filename_.c_str()); - } - - std::string GetCapturedString() { - if (uncaptured_fd_ != -1) { - // Restores the original stream. - fflush(NULL); - dup2(uncaptured_fd_, fd_); - close(uncaptured_fd_); - uncaptured_fd_ = -1; - } - - FILE* const file = posix::FOpen(filename_.c_str(), "r"); - const std::string content = ReadEntireFile(file); - posix::FClose(file); - return content; - } - - private: - // Reads the entire content of a file as an std::string. - static std::string ReadEntireFile(FILE* file); - - // Returns the size (in bytes) of a file. - static size_t GetFileSize(FILE* file); - - const int fd_; // A stream to capture. - int uncaptured_fd_; - // Name of the temporary file holding the stderr output. - ::std::string filename_; - - GTEST_DISALLOW_COPY_AND_ASSIGN_(CapturedStream); -}; - -// Returns the size (in bytes) of a file. -size_t CapturedStream::GetFileSize(FILE* file) { - fseek(file, 0, SEEK_END); - return static_cast(ftell(file)); -} - -// Reads the entire content of a file as a string. -std::string CapturedStream::ReadEntireFile(FILE* file) { - const size_t file_size = GetFileSize(file); - char* const buffer = new char[file_size]; - - size_t bytes_last_read = 0; // # of bytes read in the last fread() - size_t bytes_read = 0; // # of bytes read so far - - fseek(file, 0, SEEK_SET); - - // Keeps reading the file until we cannot read further or the - // pre-determined file size is reached. - do { - bytes_last_read = fread(buffer+bytes_read, 1, file_size-bytes_read, file); - bytes_read += bytes_last_read; - } while (bytes_last_read > 0 && bytes_read < file_size); - - const std::string content(buffer, bytes_read); - delete[] buffer; - - return content; -} - -# ifdef _MSC_VER -# pragma warning(pop) -# endif // _MSC_VER - -static CapturedStream* g_captured_stderr = NULL; -static CapturedStream* g_captured_stdout = NULL; - -// Starts capturing an output stream (stdout/stderr). -void CaptureStream(int fd, const char* stream_name, CapturedStream** stream) { - if (*stream != NULL) { - GTEST_LOG_(FATAL) << "Only one " << stream_name - << " capturer can exist at a time."; - } - *stream = new CapturedStream(fd); -} - -// Stops capturing the output stream and returns the captured string. -std::string GetCapturedStream(CapturedStream** captured_stream) { - const std::string content = (*captured_stream)->GetCapturedString(); - - delete *captured_stream; - *captured_stream = NULL; - - return content; -} - -// Starts capturing stdout. -void CaptureStdout() { - CaptureStream(kStdOutFileno, "stdout", &g_captured_stdout); -} - -// Starts capturing stderr. -void CaptureStderr() { - CaptureStream(kStdErrFileno, "stderr", &g_captured_stderr); -} - -// Stops capturing stdout and returns the captured string. -std::string GetCapturedStdout() { - return GetCapturedStream(&g_captured_stdout); -} - -// Stops capturing stderr and returns the captured string. -std::string GetCapturedStderr() { - return GetCapturedStream(&g_captured_stderr); -} - -#endif // GTEST_HAS_STREAM_REDIRECTION - -#if GTEST_HAS_DEATH_TEST - -// A copy of all command line arguments. Set by InitGoogleTest(). -::std::vector g_argvs; - -static const ::std::vector* g_injected_test_argvs = - NULL; // Owned. - -void SetInjectableArgvs(const ::std::vector* argvs) { - if (g_injected_test_argvs != argvs) - delete g_injected_test_argvs; - g_injected_test_argvs = argvs; -} - -const ::std::vector& GetInjectableArgvs() { - if (g_injected_test_argvs != NULL) { - return *g_injected_test_argvs; - } - return g_argvs; -} -#endif // GTEST_HAS_DEATH_TEST - -#if GTEST_OS_WINDOWS_MOBILE -namespace posix { -void Abort() { - DebugBreak(); - TerminateProcess(GetCurrentProcess(), 1); -} -} // namespace posix -#endif // GTEST_OS_WINDOWS_MOBILE - -// Returns the name of the environment variable corresponding to the -// given flag. For example, FlagToEnvVar("foo") will return -// "GTEST_FOO" in the open-source version. -static std::string FlagToEnvVar(const char* flag) { - const std::string full_flag = - (Message() << GTEST_FLAG_PREFIX_ << flag).GetString(); - - Message env_var; - for (size_t i = 0; i != full_flag.length(); i++) { - env_var << ToUpper(full_flag.c_str()[i]); - } - - return env_var.GetString(); -} - -// Parses 'str' for a 32-bit signed integer. If successful, writes -// the result to *value and returns true; otherwise leaves *value -// unchanged and returns false. -bool ParseInt32(const Message& src_text, const char* str, Int32* value) { - // Parses the environment variable as a decimal integer. - char* end = NULL; - const long long_value = strtol(str, &end, 10); // NOLINT - - // Has strtol() consumed all characters in the string? - if (*end != '\0') { - // No - an invalid character was encountered. - Message msg; - msg << "WARNING: " << src_text - << " is expected to be a 32-bit integer, but actually" - << " has value \"" << str << "\".\n"; - printf("%s", msg.GetString().c_str()); - fflush(stdout); - return false; - } - - // Is the parsed value in the range of an Int32? - const Int32 result = static_cast(long_value); - if (long_value == LONG_MAX || long_value == LONG_MIN || - // The parsed value overflows as a long. (strtol() returns - // LONG_MAX or LONG_MIN when the input overflows.) - result != long_value - // The parsed value overflows as an Int32. - ) { - Message msg; - msg << "WARNING: " << src_text - << " is expected to be a 32-bit integer, but actually" - << " has value " << str << ", which overflows.\n"; - printf("%s", msg.GetString().c_str()); - fflush(stdout); - return false; - } - - *value = result; - return true; -} - -// Reads and returns the Boolean environment variable corresponding to -// the given flag; if it's not set, returns default_value. -// -// The value is considered true iff it's not "0". -bool BoolFromGTestEnv(const char* flag, bool default_value) { - const std::string env_var = FlagToEnvVar(flag); - const char* const string_value = posix::GetEnv(env_var.c_str()); - return string_value == NULL ? - default_value : strcmp(string_value, "0") != 0; -} - -// Reads and returns a 32-bit integer stored in the environment -// variable corresponding to the given flag; if it isn't set or -// doesn't represent a valid 32-bit integer, returns default_value. -Int32 Int32FromGTestEnv(const char* flag, Int32 default_value) { - const std::string env_var = FlagToEnvVar(flag); - const char* const string_value = posix::GetEnv(env_var.c_str()); - if (string_value == NULL) { - // The environment variable is not set. - return default_value; - } - - Int32 result = default_value; - if (!ParseInt32(Message() << "Environment variable " << env_var, - string_value, &result)) { - printf("The default value %s is used.\n", - (Message() << default_value).GetString().c_str()); - fflush(stdout); - return default_value; - } - - return result; -} - -// Reads and returns the string environment variable corresponding to -// the given flag; if it's not set, returns default_value. -const char* StringFromGTestEnv(const char* flag, const char* default_value) { - const std::string env_var = FlagToEnvVar(flag); - const char* const value = posix::GetEnv(env_var.c_str()); - return value == NULL ? default_value : value; -} - -} // namespace internal -} // namespace testing -// Copyright 2007, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: wan@google.com (Zhanyong Wan) - -// Google Test - The Google C++ Testing Framework -// -// This file implements a universal value printer that can print a -// value of any type T: -// -// void ::testing::internal::UniversalPrinter::Print(value, ostream_ptr); -// -// It uses the << operator when possible, and prints the bytes in the -// object otherwise. A user can override its behavior for a class -// type Foo by defining either operator<<(::std::ostream&, const Foo&) -// or void PrintTo(const Foo&, ::std::ostream*) in the namespace that -// defines Foo. - -#include -#include -#include // NOLINT -#include - -namespace testing { - -namespace { - -using ::std::ostream; - -// Prints a segment of bytes in the given object. -void PrintByteSegmentInObjectTo(const unsigned char* obj_bytes, size_t start, - size_t count, ostream* os) { - char text[5] = ""; - for (size_t i = 0; i != count; i++) { - const size_t j = start + i; - if (i != 0) { - // Organizes the bytes into groups of 2 for easy parsing by - // human. - if ((j % 2) == 0) - *os << ' '; - else - *os << '-'; - } - GTEST_SNPRINTF_(text, sizeof(text), "%02X", obj_bytes[j]); - *os << text; - } -} - -// Prints the bytes in the given value to the given ostream. -void PrintBytesInObjectToImpl(const unsigned char* obj_bytes, size_t count, - ostream* os) { - // Tells the user how big the object is. - *os << count << "-byte object <"; - - const size_t kThreshold = 132; - const size_t kChunkSize = 64; - // If the object size is bigger than kThreshold, we'll have to omit - // some details by printing only the first and the last kChunkSize - // bytes. - // TODO(wan): let the user control the threshold using a flag. - if (count < kThreshold) { - PrintByteSegmentInObjectTo(obj_bytes, 0, count, os); - } else { - PrintByteSegmentInObjectTo(obj_bytes, 0, kChunkSize, os); - *os << " ... "; - // Rounds up to 2-byte boundary. - const size_t resume_pos = (count - kChunkSize + 1)/2*2; - PrintByteSegmentInObjectTo(obj_bytes, resume_pos, count - resume_pos, os); - } - *os << ">"; -} - -} // namespace - -namespace internal2 { - -// Delegates to PrintBytesInObjectToImpl() to print the bytes in the -// given object. The delegation simplifies the implementation, which -// uses the << operator and thus is easier done outside of the -// ::testing::internal namespace, which contains a << operator that -// sometimes conflicts with the one in STL. -void PrintBytesInObjectTo(const unsigned char* obj_bytes, size_t count, - ostream* os) { - PrintBytesInObjectToImpl(obj_bytes, count, os); -} - -} // namespace internal2 - -namespace internal { - -// Depending on the value of a char (or wchar_t), we print it in one -// of three formats: -// - as is if it's a printable ASCII (e.g. 'a', '2', ' '), -// - as a hexidecimal escape sequence (e.g. '\x7F'), or -// - as a special escape sequence (e.g. '\r', '\n'). -enum CharFormat { - kAsIs, - kHexEscape, - kSpecialEscape -}; - -// Returns true if c is a printable ASCII character. We test the -// value of c directly instead of calling isprint(), which is buggy on -// Windows Mobile. -inline bool IsPrintableAscii(wchar_t c) { - return 0x20 <= c && c <= 0x7E; -} - -// Prints a wide or narrow char c as a character literal without the -// quotes, escaping it when necessary; returns how c was formatted. -// The template argument UnsignedChar is the unsigned version of Char, -// which is the type of c. -template -static CharFormat PrintAsCharLiteralTo(Char c, ostream* os) { - switch (static_cast(c)) { - case L'\0': - *os << "\\0"; - break; - case L'\'': - *os << "\\'"; - break; - case L'\\': - *os << "\\\\"; - break; - case L'\a': - *os << "\\a"; - break; - case L'\b': - *os << "\\b"; - break; - case L'\f': - *os << "\\f"; - break; - case L'\n': - *os << "\\n"; - break; - case L'\r': - *os << "\\r"; - break; - case L'\t': - *os << "\\t"; - break; - case L'\v': - *os << "\\v"; - break; - default: - if (IsPrintableAscii(c)) { - *os << static_cast(c); - return kAsIs; - } else { - *os << "\\x" + String::FormatHexInt(static_cast(c)); - return kHexEscape; - } - } - return kSpecialEscape; -} - -// Prints a wchar_t c as if it's part of a string literal, escaping it when -// necessary; returns how c was formatted. -static CharFormat PrintAsStringLiteralTo(wchar_t c, ostream* os) { - switch (c) { - case L'\'': - *os << "'"; - return kAsIs; - case L'"': - *os << "\\\""; - return kSpecialEscape; - default: - return PrintAsCharLiteralTo(c, os); - } -} - -// Prints a char c as if it's part of a string literal, escaping it when -// necessary; returns how c was formatted. -static CharFormat PrintAsStringLiteralTo(char c, ostream* os) { - return PrintAsStringLiteralTo( - static_cast(static_cast(c)), os); -} - -// Prints a wide or narrow character c and its code. '\0' is printed -// as "'\\0'", other unprintable characters are also properly escaped -// using the standard C++ escape sequence. The template argument -// UnsignedChar is the unsigned version of Char, which is the type of c. -template -void PrintCharAndCodeTo(Char c, ostream* os) { - // First, print c as a literal in the most readable form we can find. - *os << ((sizeof(c) > 1) ? "L'" : "'"); - const CharFormat format = PrintAsCharLiteralTo(c, os); - *os << "'"; - - // To aid user debugging, we also print c's code in decimal, unless - // it's 0 (in which case c was printed as '\\0', making the code - // obvious). - if (c == 0) - return; - *os << " (" << static_cast(c); - - // For more convenience, we print c's code again in hexidecimal, - // unless c was already printed in the form '\x##' or the code is in - // [1, 9]. - if (format == kHexEscape || (1 <= c && c <= 9)) { - // Do nothing. - } else { - *os << ", 0x" << String::FormatHexInt(static_cast(c)); - } - *os << ")"; -} - -void PrintTo(unsigned char c, ::std::ostream* os) { - PrintCharAndCodeTo(c, os); -} -void PrintTo(signed char c, ::std::ostream* os) { - PrintCharAndCodeTo(c, os); -} - -// Prints a wchar_t as a symbol if it is printable or as its internal -// code otherwise and also as its code. L'\0' is printed as "L'\\0'". -void PrintTo(wchar_t wc, ostream* os) { - PrintCharAndCodeTo(wc, os); -} - -// Prints the given array of characters to the ostream. CharType must be either -// char or wchar_t. -// The array starts at begin, the length is len, it may include '\0' characters -// and may not be NUL-terminated. -template -static void PrintCharsAsStringTo( - const CharType* begin, size_t len, ostream* os) { - const char* const kQuoteBegin = sizeof(CharType) == 1 ? "\"" : "L\""; - *os << kQuoteBegin; - bool is_previous_hex = false; - for (size_t index = 0; index < len; ++index) { - const CharType cur = begin[index]; - if (is_previous_hex && IsXDigit(cur)) { - // Previous character is of '\x..' form and this character can be - // interpreted as another hexadecimal digit in its number. Break string to - // disambiguate. - *os << "\" " << kQuoteBegin; - } - is_previous_hex = PrintAsStringLiteralTo(cur, os) == kHexEscape; - } - *os << "\""; -} - -// Prints a (const) char/wchar_t array of 'len' elements, starting at address -// 'begin'. CharType must be either char or wchar_t. -template -static void UniversalPrintCharArray( - const CharType* begin, size_t len, ostream* os) { - // The code - // const char kFoo[] = "foo"; - // generates an array of 4, not 3, elements, with the last one being '\0'. - // - // Therefore when printing a char array, we don't print the last element if - // it's '\0', such that the output matches the string literal as it's - // written in the source code. - if (len > 0 && begin[len - 1] == '\0') { - PrintCharsAsStringTo(begin, len - 1, os); - return; - } - - // If, however, the last element in the array is not '\0', e.g. - // const char kFoo[] = { 'f', 'o', 'o' }; - // we must print the entire array. We also print a message to indicate - // that the array is not NUL-terminated. - PrintCharsAsStringTo(begin, len, os); - *os << " (no terminating NUL)"; -} - -// Prints a (const) char array of 'len' elements, starting at address 'begin'. -void UniversalPrintArray(const char* begin, size_t len, ostream* os) { - UniversalPrintCharArray(begin, len, os); -} - -// Prints a (const) wchar_t array of 'len' elements, starting at address -// 'begin'. -void UniversalPrintArray(const wchar_t* begin, size_t len, ostream* os) { - UniversalPrintCharArray(begin, len, os); -} - -// Prints the given C string to the ostream. -void PrintTo(const char* s, ostream* os) { - if (s == NULL) { - *os << "NULL"; - } else { - *os << ImplicitCast_(s) << " pointing to "; - PrintCharsAsStringTo(s, strlen(s), os); - } -} - -// MSVC compiler can be configured to define whar_t as a typedef -// of unsigned short. Defining an overload for const wchar_t* in that case -// would cause pointers to unsigned shorts be printed as wide strings, -// possibly accessing more memory than intended and causing invalid -// memory accesses. MSVC defines _NATIVE_WCHAR_T_DEFINED symbol when -// wchar_t is implemented as a native type. -#if !defined(_MSC_VER) || defined(_NATIVE_WCHAR_T_DEFINED) -// Prints the given wide C string to the ostream. -void PrintTo(const wchar_t* s, ostream* os) { - if (s == NULL) { - *os << "NULL"; - } else { - *os << ImplicitCast_(s) << " pointing to "; - PrintCharsAsStringTo(s, wcslen(s), os); - } -} -#endif // wchar_t is native - -// Prints a ::string object. -#if GTEST_HAS_GLOBAL_STRING -void PrintStringTo(const ::string& s, ostream* os) { - PrintCharsAsStringTo(s.data(), s.size(), os); -} -#endif // GTEST_HAS_GLOBAL_STRING - -void PrintStringTo(const ::std::string& s, ostream* os) { - PrintCharsAsStringTo(s.data(), s.size(), os); -} - -// Prints a ::wstring object. -#if GTEST_HAS_GLOBAL_WSTRING -void PrintWideStringTo(const ::wstring& s, ostream* os) { - PrintCharsAsStringTo(s.data(), s.size(), os); -} -#endif // GTEST_HAS_GLOBAL_WSTRING - -#if GTEST_HAS_STD_WSTRING -void PrintWideStringTo(const ::std::wstring& s, ostream* os) { - PrintCharsAsStringTo(s.data(), s.size(), os); -} -#endif // GTEST_HAS_STD_WSTRING - -} // namespace internal - -} // namespace testing -// Copyright 2008, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: mheule@google.com (Markus Heule) -// -// The Google C++ Testing Framework (Google Test) - - -// Indicates that this translation unit is part of Google Test's -// implementation. It must come before gtest-internal-inl.h is -// included, or there will be a compiler error. This trick is to -// prevent a user from accidentally including gtest-internal-inl.h in -// his code. -#define GTEST_IMPLEMENTATION_ 1 -#undef GTEST_IMPLEMENTATION_ - -namespace testing { - -using internal::GetUnitTestImpl; - -// Gets the summary of the failure message by omitting the stack trace -// in it. -std::string TestPartResult::ExtractSummary(const char* message) { - const char* const stack_trace = strstr(message, internal::kStackTraceMarker); - return stack_trace == NULL ? message : - std::string(message, stack_trace); -} - -// Prints a TestPartResult object. -std::ostream& operator<<(std::ostream& os, const TestPartResult& result) { - return os - << result.file_name() << ":" << result.line_number() << ": " - << (result.type() == TestPartResult::kSuccess ? "Success" : - result.type() == TestPartResult::kFatalFailure ? "Fatal failure" : - "Non-fatal failure") << ":\n" - << result.message() << std::endl; -} - -// Appends a TestPartResult to the array. -void TestPartResultArray::Append(const TestPartResult& result) { - array_.push_back(result); -} - -// Returns the TestPartResult at the given index (0-based). -const TestPartResult& TestPartResultArray::GetTestPartResult(int index) const { - if (index < 0 || index >= size()) { - printf("\nInvalid index (%d) into TestPartResultArray.\n", index); - internal::posix::Abort(); - } - - return array_[index]; -} - -// Returns the number of TestPartResult objects in the array. -int TestPartResultArray::size() const { - return static_cast(array_.size()); -} - -namespace internal { - -HasNewFatalFailureHelper::HasNewFatalFailureHelper() - : has_new_fatal_failure_(false), - original_reporter_(GetUnitTestImpl()-> - GetTestPartResultReporterForCurrentThread()) { - GetUnitTestImpl()->SetTestPartResultReporterForCurrentThread(this); -} - -HasNewFatalFailureHelper::~HasNewFatalFailureHelper() { - GetUnitTestImpl()->SetTestPartResultReporterForCurrentThread( - original_reporter_); -} - -void HasNewFatalFailureHelper::ReportTestPartResult( - const TestPartResult& result) { - if (result.fatally_failed()) - has_new_fatal_failure_ = true; - original_reporter_->ReportTestPartResult(result); -} - -} // namespace internal - -} // namespace testing -// Copyright 2008 Google Inc. -// All Rights Reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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. -// -// Author: wan@google.com (Zhanyong Wan) - - -namespace testing { -namespace internal { - -#if GTEST_HAS_TYPED_TEST_P - -// Skips to the first non-space char in str. Returns an empty string if str -// contains only whitespace characters. -static const char* SkipSpaces(const char* str) { - while (IsSpace(*str)) - str++; - return str; -} - -// Verifies that registered_tests match the test names in -// defined_test_names_; returns registered_tests if successful, or -// aborts the program otherwise. -const char* TypedTestCasePState::VerifyRegisteredTestNames( - const char* file, int line, const char* registered_tests) { - typedef ::std::set::const_iterator DefinedTestIter; - registered_ = true; - - // Skip initial whitespace in registered_tests since some - // preprocessors prefix stringizied literals with whitespace. - registered_tests = SkipSpaces(registered_tests); - - Message errors; - ::std::set tests; - for (const char* names = registered_tests; names != NULL; - names = SkipComma(names)) { - const std::string name = GetPrefixUntilComma(names); - if (tests.count(name) != 0) { - errors << "Test " << name << " is listed more than once.\n"; - continue; - } - - bool found = false; - for (DefinedTestIter it = defined_test_names_.begin(); - it != defined_test_names_.end(); - ++it) { - if (name == *it) { - found = true; - break; - } - } - - if (found) { - tests.insert(name); - } else { - errors << "No test named " << name - << " can be found in this test case.\n"; - } - } - - for (DefinedTestIter it = defined_test_names_.begin(); - it != defined_test_names_.end(); - ++it) { - if (tests.count(*it) == 0) { - errors << "You forgot to list test " << *it << ".\n"; - } - } - - const std::string& errors_str = errors.GetString(); - if (errors_str != "") { - fprintf(stderr, "%s %s", FormatFileLocation(file, line).c_str(), - errors_str.c_str()); - fflush(stderr); - posix::Abort(); - } - - return registered_tests; -} - -#endif // GTEST_HAS_TYPED_TEST_P - -} // namespace internal -} // namespace testing diff --git a/lib/test/gtest/src/gtest_main.cc b/lib/test/gtest/src/gtest_main.cc deleted file mode 100644 index f3028225523..00000000000 --- a/lib/test/gtest/src/gtest_main.cc +++ /dev/null @@ -1,38 +0,0 @@ -// Copyright 2006, Google Inc. -// All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are -// met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// * 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. -// * Neither the name of Google Inc. 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 "gtest/gtest.h" - -GTEST_API_ int main(int argc, char **argv) { - printf("Running main() from gtest_main.cc\n"); - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/src/test/.gitignore b/src/test/.gitignore new file mode 100644 index 00000000000..796b96d1c40 --- /dev/null +++ b/src/test/.gitignore @@ -0,0 +1 @@ +/build diff --git a/src/test/CMakeLists.txt b/src/test/CMakeLists.txt new file mode 100644 index 00000000000..2c9adc21d89 --- /dev/null +++ b/src/test/CMakeLists.txt @@ -0,0 +1,17 @@ +cmake_minimum_required(VERSION 3.10) + +project(INAVTests) + +set(CMAKE_C_STANDARD 11) +set(CMAKE_C_EXTENSIONS ON) +set(CMAKE_C_STANDARD_REQUIRED ON) +set(CMAKE_CXX_STANDARD 11) +set(CMAKE_CXX_EXTENSIONS ON) +set(CMAKE_CXX_STANDARD_REQUIRED ON) + +include(cmake/gtest.cmake) + +enable_testing() +include(GoogleTest) +#add_subdirectory(googletest) +add_subdirectory(unit) diff --git a/src/test/Makefile b/src/test/Makefile deleted file mode 100644 index 676bd496e7c..00000000000 --- a/src/test/Makefile +++ /dev/null @@ -1,769 +0,0 @@ -# A sample Makefile for building Google Test and using it in user -# tests. Please tweak it to suit your environment and project. You -# may want to move it to your project's root directory. -# -# SYNOPSIS: -# -# make [all] - makes everything. -# make TARGET - makes the given target. -# make clean - removes all files generated by make. - -# Please tweak the following variable definitions as needed by your -# project, except GTEST_HEADERS, which you can use in your own targets -# but shouldn't modify. - -# Points to the root of Google Test, relative to where this file is. -# Remember to tweak this if you move this file. -GTEST_DIR = ../../lib/test/gtest - -# Where to find user code. -USER_DIR = ../main -TEST_DIR = unit -USER_INCLUDE_DIR = $(USER_DIR) - -OBJECT_DIR = ../../obj/test - -COMMON_FLAGS = \ - -g \ - -Wall \ - -pthread \ - -Wextra \ - -ggdb3 \ - -O0 \ - -DUNIT_TEST \ - -isystem $(GTEST_DIR)/inc \ - -MMD -MP - -# Flags passed to the C compiler. -C_FLAGS = $(COMMON_FLAGS) \ - -std=gnu99 - -# Flags passed to the C++ compiler. -CXX_FLAGS = $(COMMON_FLAGS) \ - -std=gnu++11 - -# Gather up all of the tests. -TEST_SRC = $(sort $(wildcard $(TEST_DIR)/*.cc)) -TESTS = $(TEST_SRC:$(TEST_DIR)/%.cc=%) -TEST_BINARIES = $(TESTS:%=$(OBJECT_DIR)/%) - -# All Google Test headers. Usually you shouldn't change this -# definition. -GTEST_HEADERS = $(GTEST_DIR)/inc/gtest/*.h - -# House-keeping build targets. - -all : $(TEST_BINARIES) - -clean : - rm -rf $(OBJECT_DIR) - -# Builds gtest.a and gtest_main.a. - -# Usually you shouldn't tweak such internal variables, indicated by a -# trailing _. -GTEST_SRCS_ = $(GTEST_DIR)/src/*.cc $(GTEST_DIR)/inc/gtest/*.h $(GTEST_HEADERS) - -# For simplicity and to avoid depending on Google Test's -# implementation details, the dependencies specified below are -# conservative and not optimized. This is fine as Google Test -# compiles fast and for ordinary users its source rarely changes. -$(OBJECT_DIR)/gtest-all.o : $(GTEST_SRCS_) - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) -I$(GTEST_DIR) -Wno-missing-field-initializers -Wno-unused-const-variable -c \ - $(GTEST_DIR)/src/gtest-all.cc -o $@ - -$(OBJECT_DIR)/gtest_main.o : $(GTEST_SRCS_) - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) -I$(GTEST_DIR) -c \ - $(GTEST_DIR)/src/gtest_main.cc -o $@ - -$(OBJECT_DIR)/gtest.a : $(OBJECT_DIR)/gtest-all.o - $(AR) $(ARFLAGS) $@ $^ - -$(OBJECT_DIR)/gtest_main.a : $(OBJECT_DIR)/gtest-all.o $(OBJECT_DIR)/gtest_main.o - $(AR) $(ARFLAGS) $@ $^ - -# Builds a sample test. A test should link with either gtest.a or -# gtest_main.a, depending on whether it defines its own main() -# function. - -# includes in test dir must override includes in user dir -TEST_INCLUDE_DIRS := $(TEST_DIR) \ - $(USER_INCLUDE_DIR) - -TEST_CFLAGS = $(addprefix -I,$(TEST_INCLUDE_DIRS)) - -DEPS = $(TEST_BINARIES:%=%.d) - -$(OBJECT_DIR)/common/maths.o : \ - $(USER_DIR)/common/maths.c \ - $(USER_DIR)/common/maths.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/common/maths.c -o $@ - - -$(OBJECT_DIR)/common/calibration.o : \ - $(USER_DIR)/common/calibration.c \ - $(USER_DIR)/common/calibration.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/common/calibration.c -o $@ - - -$(OBJECT_DIR)/common/bitarray.o : \ - $(USER_DIR)/common/bitarray.c \ - $(USER_DIR)/common/bitarray.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/common/bitarray.c -o $@ - - -$(OBJECT_DIR)/common/string_light.o : \ - $(USER_DIR)/common/string_light.c \ - $(USER_DIR)/common/string_light.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/common/string_light.c -o $@ - - -$(OBJECT_DIR)/sensors/battery.o : $(USER_DIR)/sensors/battery.c $(USER_DIR)/sensors/battery.h $(GTEST_HEADERS) - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/sensors/battery.c -o $@ - -$(OBJECT_DIR)/battery_unittest.o : \ - $(TEST_DIR)/battery_unittest.cc \ - $(USER_DIR)/sensors/battery.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $< -o $@ - -$(OBJECT_DIR)/battery_unittest : \ - $(OBJECT_DIR)/sensors/battery.o \ - $(OBJECT_DIR)/common/maths.o \ - $(OBJECT_DIR)/battery_unittest.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $@ - -$(OBJECT_DIR)/common/encoding.o : $(USER_DIR)/common/encoding.c $(USER_DIR)/common/encoding.h $(GTEST_HEADERS) - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/common/encoding.c -o $@ - -$(OBJECT_DIR)/encoding_unittest.o : \ - $(TEST_DIR)/encoding_unittest.cc \ - $(USER_DIR)/common/encoding.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/encoding_unittest.cc -o $@ - -$(OBJECT_DIR)/encoding_unittest : \ - $(OBJECT_DIR)/common/encoding.o \ - $(OBJECT_DIR)/encoding_unittest.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - -$(OBJECT_DIR)/flight/imu.o : \ - $(USER_DIR)/flight/imu.c \ - $(USER_DIR)/flight/imu.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/imu.c -o $@ - -$(OBJECT_DIR)/common/filter.o : \ - $(USER_DIR)/common/filter.c \ - $(USER_DIR)/common/filter.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/common/filter.c -o $@ - -$(OBJECT_DIR)/flight_imu_unittest.o : \ - $(TEST_DIR)/flight_imu_unittest.cc \ - $(USER_DIR)/flight/imu.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/flight_imu_unittest.cc -o $@ - -$(OBJECT_DIR)/flight_imu_unittest : \ - $(OBJECT_DIR)/flight/imu.o \ - $(OBJECT_DIR)/flight_imu_unittest.o \ - $(OBJECT_DIR)/common/filter.o \ - $(OBJECT_DIR)/common/maths.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - -$(OBJECT_DIR)/maths_unittest.o : \ - $(TEST_DIR)/maths_unittest.cc \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/maths_unittest.cc -o $@ - -$(OBJECT_DIR)/maths_unittest : \ - $(OBJECT_DIR)/maths_unittest.o \ - $(OBJECT_DIR)/common/maths.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - - -$(OBJECT_DIR)/common/gps_conversion.o : \ - $(USER_DIR)/common/gps_conversion.c \ - $(USER_DIR)/common/gps_conversion.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/common/gps_conversion.c -o $@ - -$(OBJECT_DIR)/gps_conversion_unittest.o : \ - $(TEST_DIR)/gps_conversion_unittest.cc \ - $(USER_DIR)/common/gps_conversion.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/gps_conversion_unittest.cc -o $@ - -$(OBJECT_DIR)/gps_conversion_unittest : \ - $(OBJECT_DIR)/common/gps_conversion.o \ - $(OBJECT_DIR)/gps_conversion_unittest.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - - - -$(OBJECT_DIR)/telemetry/hott.o : \ - $(USER_DIR)/telemetry/hott.c \ - $(USER_DIR)/telemetry/hott.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/telemetry/hott.c -o $@ - -$(OBJECT_DIR)/telemetry_hott_unittest.o : \ - $(TEST_DIR)/telemetry_hott_unittest.cc \ - $(USER_DIR)/telemetry/hott.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/telemetry_hott_unittest.cc -o $@ - -$(OBJECT_DIR)/telemetry_hott_unittest : \ - $(OBJECT_DIR)/telemetry/hott.o \ - $(OBJECT_DIR)/telemetry_hott_unittest.o \ - $(OBJECT_DIR)/common/gps_conversion.o \ - $(OBJECT_DIR)/common/string_light.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - - - -$(OBJECT_DIR)/fc/rc_controls.o : \ - $(USER_DIR)/fc/rc_controls.c \ - $(USER_DIR)/fc/rc_controls.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/fc/rc_controls.c -o $@ - -$(OBJECT_DIR)/fc/rc_modes.o : \ - $(USER_DIR)/fc/rc_modes.c \ - $(USER_DIR)/fc/rc_modes.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/fc/rc_modes.c -o $@ - -$(OBJECT_DIR)/rc_controls_unittest.o : \ - $(TEST_DIR)/rc_controls_unittest.cc \ - $(USER_DIR)/fc/rc_controls.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/rc_controls_unittest.cc -o $@ - -$(OBJECT_DIR)/rc_controls_unittest : \ - $(OBJECT_DIR)/common/maths.o \ - $(OBJECT_DIR)/io/rc_controls.o \ - $(OBJECT_DIR)/rc_controls_unittest.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - - -$(OBJECT_DIR)/io/ledstrip.o : \ - $(USER_DIR)/io/ledstrip.c \ - $(USER_DIR)/io/ledstrip.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/io/ledstrip.c -o $@ - -$(OBJECT_DIR)/ledstrip_unittest.o : \ - $(TEST_DIR)/ledstrip_unittest.cc \ - $(USER_DIR)/io/ledstrip.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/ledstrip_unittest.cc -o $@ - -$(OBJECT_DIR)/ledstrip_unittest : \ - $(OBJECT_DIR)/io/ledstrip.o \ - $(OBJECT_DIR)/ledstrip_unittest.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - - - -$(OBJECT_DIR)/drivers/light_ws2811strip.o : \ - $(USER_DIR)/drivers/light_ws2811strip.c \ - $(USER_DIR)/drivers/light_ws2811strip.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/drivers/light_ws2811strip.c -o $@ - -$(OBJECT_DIR)/ws2811_unittest.o : \ - $(TEST_DIR)/ws2811_unittest.cc \ - $(USER_DIR)/drivers/light_ws2811strip.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/ws2811_unittest.cc -o $@ - -$(OBJECT_DIR)/ws2811_unittest : \ - $(OBJECT_DIR)/drivers/light_ws2811strip.o \ - $(OBJECT_DIR)/ws2811_unittest.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - - -$(OBJECT_DIR)/flight/lowpass.o : \ - $(USER_DIR)/flight/lowpass.c \ - $(USER_DIR)/flight/lowpass.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/lowpass.c -o $@ - -$(OBJECT_DIR)/lowpass_unittest.o : \ - $(TEST_DIR)/lowpass_unittest.cc \ - $(USER_DIR)/flight/lowpass.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/lowpass_unittest.cc -o $@ - -$(OBJECT_DIR)/lowpass_unittest : \ - $(OBJECT_DIR)/flight/lowpass.o \ - $(OBJECT_DIR)/lowpass_unittest.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - -$(OBJECT_DIR)/flight/mixer.o : \ - $(USER_DIR)/flight/mixer.c \ - $(USER_DIR)/flight/mixer.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/mixer.c -o $@ - -$(OBJECT_DIR)/flight_mixer_unittest.o : \ - $(TEST_DIR)/flight_mixer_unittest.cc \ - $(USER_DIR)/flight/mixer.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/flight_mixer_unittest.cc -o $@ - -$(OBJECT_DIR)/flight_mixer_unittest : \ - $(OBJECT_DIR)/flight/mixer.o \ - $(OBJECT_DIR)/flight_mixer_unittest.o \ - $(OBJECT_DIR)/common/maths.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - -$(OBJECT_DIR)/flight/failsafe.o : \ - $(USER_DIR)/flight/failsafe.c \ - $(USER_DIR)/flight/failsafe.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/flight/failsafe.c -o $@ - -$(OBJECT_DIR)/flight_failsafe_unittest.o : \ - $(TEST_DIR)/flight_failsafe_unittest.cc \ - $(USER_DIR)/flight/failsafe.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/flight_failsafe_unittest.cc -o $@ - -$(OBJECT_DIR)/flight_failsafe_unittest : \ - $(OBJECT_DIR)/flight/failsafe.o \ - $(OBJECT_DIR)/flight_failsafe_unittest.o \ - $(OBJECT_DIR)/common/maths.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - -$(OBJECT_DIR)/io/serial.o : \ - $(USER_DIR)/io/serial.c \ - $(USER_DIR)/io/serial.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/io/serial.c -o $@ - -$(OBJECT_DIR)/io_serial_unittest.o : \ - $(TEST_DIR)/io_serial_unittest.cc \ - $(USER_DIR)/io/serial.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/io_serial_unittest.cc -o $@ - -$(OBJECT_DIR)/io_serial_unittest : \ - $(OBJECT_DIR)/io/serial.o \ - $(OBJECT_DIR)/io_serial_unittest.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - -$(OBJECT_DIR)/rx/rx.o : \ - $(USER_DIR)/rx/rx.c \ - $(USER_DIR)/rx/rx.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/rx/rx.c -o $@ - -$(OBJECT_DIR)/rx_rx_unittest.o : \ - $(TEST_DIR)/rx_rx_unittest.cc \ - $(USER_DIR)/rx/rx.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/rx_rx_unittest.cc -o $@ - -$(OBJECT_DIR)/rx_rx_unittest : \ - $(OBJECT_DIR)/rx/rx.o \ - $(OBJECT_DIR)/rx_rx_unittest.o \ - $(OBJECT_DIR)/common/maths.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - -$(OBJECT_DIR)/rx_ranges_unittest.o : \ - $(TEST_DIR)/rx_ranges_unittest.cc \ - $(USER_DIR)/rx/rx.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/rx_ranges_unittest.cc -o $@ - -$(OBJECT_DIR)/rx_ranges_unittest : \ - $(OBJECT_DIR)/rx/rx.o \ - $(OBJECT_DIR)/rx_ranges_unittest.o \ - $(OBJECT_DIR)/common/maths.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - -$(OBJECT_DIR)/drivers/barometer_ms56xx.o : \ - $(USER_DIR)/drivers/barometer_ms56xx.c \ - $(USER_DIR)/drivers/barometer_ms56xx.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/drivers/barometer_ms56xx.c -o $@ - -$(OBJECT_DIR)/baro_ms5611_unittest.o : \ - $(TEST_DIR)/baro_ms5611_unittest.cc \ - $(USER_DIR)/drivers/barometer_ms5611.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/baro_ms5611_unittest.cc -o $@ - -$(OBJECT_DIR)/baro_ms5611_unittest : \ - $(OBJECT_DIR)/drivers/barometer_ms5611.o \ - $(OBJECT_DIR)/baro_ms5611_unittest.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - -$(OBJECT_DIR)/drivers/barometer_bmp085.o : \ - $(USER_DIR)/drivers/barometer_bmp085.c \ - $(USER_DIR)/drivers/barometer_bmp085.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/drivers/barometer_bmp085.c -o $@ - -$(OBJECT_DIR)/baro_bmp085_unittest.o : \ - $(TEST_DIR)/baro_bmp085_unittest.cc \ - $(USER_DIR)/drivers/barometer_bmp085.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/baro_bmp085_unittest.cc -o $@ - -$(OBJECT_DIR)/baro_bmp085_unittest : \ - $(OBJECT_DIR)/drivers/barometer_bmp085.o \ - $(OBJECT_DIR)/baro_bmp085_unittest.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - -$(OBJECT_DIR)/drivers/barometer_bmp280.o : \ - $(USER_DIR)/drivers/barometer_bmp280.c \ - $(USER_DIR)/drivers/barometer_bmp280.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/drivers/barometer_bmp280.c -o $@ - -$(OBJECT_DIR)/baro_bmp280_unittest.o : \ - $(TEST_DIR)/baro_bmp280_unittest.cc \ - $(USER_DIR)/drivers/barometer_bmp280.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/baro_bmp280_unittest.cc -o $@ - -$(OBJECT_DIR)/baro_bmp280_unittest : \ - $(OBJECT_DIR)/drivers/barometer_bmp280.o \ - $(OBJECT_DIR)/baro_bmp280_unittest.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - -$(OBJECT_DIR)/drivers/rangefinder_hcsr04.o : \ - $(USER_DIR)/drivers/rangefinder_hcsr04.c \ - $(USER_DIR)/drivers/rangefinder_hcsr04.h \ - $(GTEST_HEADERS) - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -DSONAR -c $(USER_DIR)/drivers/rangefinder_hcsr04.c -o $@ - -$(OBJECT_DIR)/sensors/sonar.o : \ - $(USER_DIR)/sensors/sonar.c \ - $(USER_DIR)/sensors/sonar.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -DSONAR -c $(USER_DIR)/sensors/sonar.c -o $@ - -$(OBJECT_DIR)/sonar_unittest.o : \ - $(TEST_DIR)/sonar_unittest.cc \ - $(USER_DIR)/drivers/rangefinder_hcsr04.h \ - $(USER_DIR)/sensors/sonar.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/sonar_unittest.cc -o $@ - -$(OBJECT_DIR)/sonar_unittest : \ - $(OBJECT_DIR)/common/maths.o \ - $(OBJECT_DIR)/drivers/rangefinder_hcsr04.o \ - $(OBJECT_DIR)/sensors/sonar.o \ - $(OBJECT_DIR)/sonar_unittest.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - -$(OBJECT_DIR)/sensors/boardalignment.o : \ - $(USER_DIR)/sensors/boardalignment.c \ - $(USER_DIR)/sensors/boardalignment.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/sensors/boardalignment.c -o $@ - -$(OBJECT_DIR)/alignsensor_unittest.o : \ - $(TEST_DIR)/alignsensor_unittest.cc \ - $(USER_DIR)/sensors/boardalignment.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/alignsensor_unittest.cc -o $@ - -$(OBJECT_DIR)/alignsensor_unittest : \ - $(OBJECT_DIR)/common/maths.o \ - $(OBJECT_DIR)/sensors/boardalignment.o \ - $(OBJECT_DIR)/alignsensor_unittest.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - -$(OBJECT_DIR)/build/debug.o : \ - $(USER_DIR)/build/debug.c \ - $(USER_DIR)/build/debug.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/build/debug.c -o $@ - -$(OBJECT_DIR)/drivers/accgyro/accgyro_fake.o : \ - $(USER_DIR)/drivers/accgyro/accgyro_fake.c \ - $(USER_DIR)/drivers/accgyro/accgyro_fake.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/drivers/accgyro/accgyro_fake.c -o $@ - -$(OBJECT_DIR)/sensors/gyro.o : \ - $(USER_DIR)/sensors/gyro.c \ - $(USER_DIR)/sensors/gyro.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/sensors/gyro.c -o $@ - -$(OBJECT_DIR)/sensor_gyro_unittest.o : \ - $(TEST_DIR)/sensor_gyro_unittest.cc \ - $(USER_DIR)/sensors/gyro.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/sensor_gyro_unittest.cc -o $@ - -$(OBJECT_DIR)/sensor_gyro_unittest : \ - $(OBJECT_DIR)/build/debug.o \ - $(OBJECT_DIR)/common/maths.o \ - $(OBJECT_DIR)/common/calibration.o \ - $(OBJECT_DIR)/common/filter.o \ - $(OBJECT_DIR)/drivers/accgyro/accgyro_fake.o \ - $(OBJECT_DIR)/sensors/gyro.o \ - $(OBJECT_DIR)/sensors/boardalignment.o \ - $(OBJECT_DIR)/sensor_gyro_unittest.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - -$(OBJECT_DIR)/common/crc.o : \ - $(USER_DIR)/common/crc.c \ - $(USER_DIR)/common/crc.h - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/common/crc.c -o $@ - -$(OBJECT_DIR)/io/rcdevice.o : \ - $(USER_DIR)/io/rcdevice.c \ - $(USER_DIR)/io/rcdevice.h - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -DUSE_RCDEVICE -c $(USER_DIR)/io/rcdevice.c -o $@ - -$(OBJECT_DIR)/io/rcdevice_cam.o : \ - $(USER_DIR)/io/rcdevice.c \ - $(USER_DIR)/io/rcdevice.h \ - $(USER_DIR)/io/rcdevice_cam.c \ - $(USER_DIR)/io/rcdevice_cam.h - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -DUSE_RCDEVICE -c $(USER_DIR)/io/rcdevice_cam.c -o $@ - - -$(OBJECT_DIR)/rcdevice_unittest.o : \ - $(TEST_DIR)/rcdevice_unittest.cc \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -DUSE_RCDEVICE -c $(TEST_DIR)/rcdevice_unittest.cc -o $@ - -$(OBJECT_DIR)/rcdevice_unittest : \ - $(OBJECT_DIR)/rcdevice_unittest.o \ - $(OBJECT_DIR)/common/bitarray.o \ - $(OBJECT_DIR)/common/crc.o \ - $(OBJECT_DIR)/io/rcdevice.o \ - $(OBJECT_DIR)/io/rcdevice_cam.o \ - $(OBJECT_DIR)/fc/rc_modes.o \ - $(OBJECT_DIR)/common/maths.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - -$(OBJECT_DIR)/drivers/time.o : \ - $(USER_DIR)/drivers/time.c \ - $(USER_DIR)/drivers/time.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/drivers/time.c -o $@ - -$(OBJECT_DIR)/time_unittest.o : \ - $(TEST_DIR)/time_unittest.cc \ - $(USER_DIR)/drivers/time.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/time_unittest.cc -o $@ - -$(OBJECT_DIR)/time_unittest : \ - $(OBJECT_DIR)/drivers/time.o \ - $(OBJECT_DIR)/time_unittest.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - -$(OBJECT_DIR)/bitarray_unittest.o : \ - $(TEST_DIR)/bitarray_unittest.cc \ - $(USER_DIR)/common/bitarray.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/bitarray_unittest.cc -o $@ - -$(OBJECT_DIR)/bitarray_unittest : \ - $(OBJECT_DIR)/common/bitarray.o \ - $(OBJECT_DIR)/bitarray_unittest.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - -$(OBJECT_DIR)/common/olc.o : $(USER_DIR)/common/olc.c $(USER_DIR)/common/olc.h $(GTEST_HEADERS) - @mkdir -p $(dir $@) - $(CC) $(C_FLAGS) $(TEST_CFLAGS) -c $(USER_DIR)/common/olc.c -o $@ - -$(OBJECT_DIR)/olc_unittest.o : \ - $(TEST_DIR)/olc_unittest.cc \ - $(USER_DIR)/common/olc.h \ - $(GTEST_HEADERS) - - @mkdir -p $(dir $@) - $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) -c $(TEST_DIR)/olc_unittest.cc -o $@ - -$(OBJECT_DIR)/olc_unittest : \ - $(OBJECT_DIR)/common/olc.o \ - $(OBJECT_DIR)/olc_unittest.o \ - $(OBJECT_DIR)/gtest_main.a - - $(CXX) $(CXX_FLAGS) $^ -o $(OBJECT_DIR)/$@ - - - -test: $(TESTS:%=test-%) - -test-%: $(OBJECT_DIR)/% - $< - --include $(DEPS) - diff --git a/src/test/cmake/CMakeListsGTest.txt.in b/src/test/cmake/CMakeListsGTest.txt.in new file mode 100644 index 00000000000..7163000b175 --- /dev/null +++ b/src/test/cmake/CMakeListsGTest.txt.in @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 3.10) + +project(googletest-download NONE) + +include(ExternalProject) +ExternalProject_Add(googletest + GIT_REPOSITORY https://github.com/google/googletest.git + GIT_TAG master + SOURCE_DIR "${CMAKE_CURRENT_BINARY_DIR}/googletest-src" + BINARY_DIR "${CMAKE_CURRENT_BINARY_DIR}/googletest-build" + CONFIGURE_COMMAND "" + BUILD_COMMAND "" + INSTALL_COMMAND "" + TEST_COMMAND "" +) diff --git a/src/test/cmake/gtest.cmake b/src/test/cmake/gtest.cmake new file mode 100644 index 00000000000..2f8bf52da4e --- /dev/null +++ b/src/test/cmake/gtest.cmake @@ -0,0 +1,31 @@ +# Download and unpack googletest at configure time +configure_file(cmake/CMakeListsGTest.txt.in googletest-download/CMakeLists.txt) +execute_process(COMMAND ${CMAKE_COMMAND} -G "${CMAKE_GENERATOR}" . + RESULT_VARIABLE result + WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/googletest-download ) +if(result) + message(FATAL_ERROR "CMake step for googletest failed: ${result}") +endif() +execute_process(COMMAND ${CMAKE_COMMAND} --build . + RESULT_VARIABLE result + WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/googletest-download ) +if(result) + message(FATAL_ERROR "Build step for googletest failed: ${result}") +endif() + +# Prevent overriding the parent project's compiler/linker +# settings on Windows +set(gtest_force_shared_crt ON CACHE BOOL "" FORCE) + +# Add googletest directly to our build. This defines +# the gtest and gtest_main targets. +add_subdirectory(${CMAKE_CURRENT_BINARY_DIR}/googletest-src + ${CMAKE_CURRENT_BINARY_DIR}/googletest-build + EXCLUDE_FROM_ALL) + +# The gtest/gtest_main targets carry header search path +# dependencies automatically when using CMake 2.8.11 or +# later. Otherwise we have to add them here ourselves. +if (CMAKE_VERSION VERSION_LESS 2.8.11) + include_directories("${gtest_SOURCE_DIR}/include") +endif() diff --git a/src/test/unit/CMakeLists.txt b/src/test/unit/CMakeLists.txt new file mode 100644 index 00000000000..42567db71a1 --- /dev/null +++ b/src/test/unit/CMakeLists.txt @@ -0,0 +1,58 @@ +# XXX: This should come from main project once everything +# uses cmake +set(MAIN_DIR "${CMAKE_CURRENT_SOURCE_DIR}/../../../src/main") + +# Keep these alphabetically sorted by test name + +set_property(SOURCE alignsensor_unittest.cc PROPERTY depends + "common/maths.c" "sensors/boardalignment.c") + +set_property(SOURCE bitarray_unittest.cc PROPERTY depends "common/bitarray.c") + +set_property(SOURCE maths_unittest.cc PROPERTY depends "common/maths.c") + +set_property(SOURCE olc_unittest.cc PROPERTY depends "common/olc.c") + +set_property(SOURCE rcdevice_unittest.cc PROPERTY definitions USE_RCDEVICE) +set_property(SOURCE rcdevice_unittest.cc PROPERTY depends + "common/bitarray.c" "common/crc.c" "io/rcdevice.c" "io/rcdevice_cam.c" + "fc/rc_modes.c" "common/maths.c") + +set_property(SOURCE sensor_gyro_unittest.cc PROPERTY depends + "build/debug.c" "common/maths.c" "common/calibration.c" "common/filter.c" + "drivers/accgyro/accgyro_fake.c" "sensors/gyro.c" "sensors/boardalignment.c") + +set_property(SOURCE telemetry_hott_unittest.cc PROPERTY depends + "telemetry/hott.c" "common/gps_conversion.c" "common/string_light.c") + +set_property(SOURCE time_unittest.cc PROPERTY depends "drivers/time.c") + +function(unit_test src) + get_filename_component(basename ${src} NAME) + string(REPLACE ".cc" "" name ${basename} ) + get_property(deps SOURCE ${src} PROPERTY depends) + set(headers "${deps}") + list(TRANSFORM headers REPLACE "\.c$" ".h") + list(APPEND deps ${headers}) + get_property(defs SOURCE ${src} PROPERTY definitions) + set(test_definitions "UNIT_TEST") + if (defs) + list(APPEND test_definitions ${defs}) + endif() + list(TRANSFORM deps PREPEND "${MAIN_DIR}/") + add_executable(${name} ${src} ${deps}) + target_include_directories(${name} PRIVATE . ${MAIN_DIR}) + target_compile_definitions(${name} PRIVATE ${test_definitions}) + set_target_properties(${name} PROPERTIES COMPILE_FLAGS "-pthread -Wall -Wextra -Wno-extern-c-compat -ggdb3 -O0") + target_link_libraries(${name} gtest_main) + gtest_discover_tests(${name}) + add_custom_target("run-${name}" "${name}" DEPENDS ${name}) + set(test_targets ${test_targets} "${name}" PARENT_SCOPE) +endfunction() + +file(GLOB TEST_PROGRAMS *_unittest.cc) +foreach(source ${TEST_PROGRAMS}) + unit_test(${source}) +endforeach() + +add_custom_target(check COMMAND ${CMAKE_CTEST_COMMAND} DEPENDS ${test_targets}) diff --git a/src/test/unit/platform.h b/src/test/unit/platform.h index 4dcf2092c71..f8a337fecec 100644 --- a/src/test/unit/platform.h +++ b/src/test/unit/platform.h @@ -17,6 +17,8 @@ #pragma once +#include + #define U_ID_0 0 #define U_ID_1 1 #define U_ID_2 2 @@ -87,4 +89,4 @@ extern SysTick_Type *SysTick; #define FUNCTION_COMPILE_FOR_SPEED #define FILE_COMPILE_FOR_SIZE #define FILE_COMPILE_NORMAL -#define FILE_COMPILE_FOR_SPEED \ No newline at end of file +#define FILE_COMPILE_FOR_SPEED From 55943a06309e6ac491cbddba157c828a92bb64c1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sat, 16 May 2020 17:13:44 +0100 Subject: [PATCH 093/248] [SETTINGS] Cleanup the settings generator a bit - Don't include target.h explicitely, it's already included by platform.h - Fix an error in compiled file as a test for discovering contstants. Since we rely on compiler errors to give us the resolved value, that lets us get one extra value on each run - Always compile the test files for setting discovery in c++11 even if no -std=XXX argument is passed from the caller. --- src/utils/compiler.rb | 3 ++- src/utils/settings.rb | 4 ++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/src/utils/compiler.rb b/src/utils/compiler.rb index 8cc243f6084..39f7d57184f 100644 --- a/src/utils/compiler.rb +++ b/src/utils/compiler.rb @@ -57,6 +57,7 @@ def initialize def default_args cflags = Shellwords.split(ENV["CFLAGS"] || "") args = [@path] + args << "-std=c++11" cflags.each do |flag| # Don't generate temporary files if flag == "" || flag == "-MMD" || flag == "-MP" || flag.start_with?("-save-temps") @@ -67,7 +68,7 @@ def default_args next end if flag.start_with? "-std=" - flag = "-std=c++11" + next end if flag.start_with? "-D'" # Cleanup flag. Done by the shell when called from diff --git a/src/utils/settings.rb b/src/utils/settings.rb index 77955523088..bb517de362b 100644 --- a/src/utils/settings.rb +++ b/src/utils/settings.rb @@ -718,7 +718,7 @@ def mktmpdir def compile_test_file(prog) buf = StringIO.new # cstddef for offsetof() - headers = ["platform.h", "target.h", "cstddef"] + headers = ["platform.h", "cstddef"] @data["groups"].each do |group| gh = group["headers"] if gh @@ -925,7 +925,7 @@ def resolve_constants(constants) buf << "static_assert(V == 42 && 0 == 1, \"FAIL\");\n" buf << "public:\n" buf << "Fail() {};\n" - buf << "int64_t v = V\n" + buf << "int64_t v = V;\n" buf << "};\n" ii = 0 s.each do |c| From 30146b482ea2bd8d8b57718da5c90cf917d59f00 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sat, 16 May 2020 18:39:38 +0100 Subject: [PATCH 094/248] [SETTINGS] Add missing headers in PG_GENERAL_SETTINGS and PG_RPM_FILTER_CONFIG Otherwise some constants might fail to be resolved depending on the compilation order. --- src/main/fc/settings.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index fcd367dba4b..6181f88f605 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1184,6 +1184,7 @@ groups: max: 1000 - name: PG_GENERAL_SETTINGS + headers: ["config/general_settings.h"] type: generalSettings_t members: - name: applied_defaults @@ -1195,6 +1196,7 @@ groups: max: 3 - name: PG_RPM_FILTER_CONFIG + headers: ["flight/rpm_filter.h"] condition: USE_RPM_FILTER type: rpmFilterConfig_t members: From 8035a59639dca261f69d3eede475fede39c44b22 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sat, 16 May 2020 21:57:03 +0100 Subject: [PATCH 095/248] [BUILD] Initial and very basic support for CMake Only F411 based targets have been ported for now --- .gitignore | 9 +- CMakeLists.txt | 51 ++++ cmake/arm-none-eabi.cmake | 63 +++++ cmake/inav.cmake | 65 +++++ cmake/settings.cmake | 25 ++ cmake/stm32-usb.cmake | 65 +++++ cmake/stm32.cmake | 263 ++++++++++++++++++++ src/main/CMakeLists.txt | 276 +++++++++++++++++++++ src/main/io/flashfs.c | 9 +- src/main/target/CMakeLists.txt | 7 + src/main/target/MATEKF411/CMakeLists.txt | 4 + src/main/target/MATEKF411SE/CMakeLists.txt | 1 + src/main/target/NOX/CMakeLists.txt | 1 + 13 files changed, 834 insertions(+), 5 deletions(-) create mode 100644 CMakeLists.txt create mode 100644 cmake/arm-none-eabi.cmake create mode 100644 cmake/inav.cmake create mode 100644 cmake/settings.cmake create mode 100644 cmake/stm32-usb.cmake create mode 100644 cmake/stm32.cmake create mode 100644 src/main/CMakeLists.txt create mode 100644 src/main/target/CMakeLists.txt create mode 100644 src/main/target/MATEKF411/CMakeLists.txt create mode 100644 src/main/target/MATEKF411SE/CMakeLists.txt create mode 100644 src/main/target/NOX/CMakeLists.txt diff --git a/.gitignore b/.gitignore index 3d99991cd42..f4edd67c172 100644 --- a/.gitignore +++ b/.gitignore @@ -12,10 +12,11 @@ startup_stm32f10x_md_gcc.s .vagrant/ .vscode/ cov-int* -obj/ -patches/ -tools/ -downloads/ +/build/ +/obj/ +/patches/ +/tools/ +/downloads/ # script-generated files docs/Manual.pdf diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 00000000000..df804980cd1 --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,51 @@ +cmake_minimum_required(VERSION 3.17) + +set(TOOLCHAIN_OPTIONS "arm-none-eabi") +set(TOOLCHAIN "arm-none-eabi" CACHE STRING "Toolchain to use. Available: ${TOOLCHAIN_OPTIONS}") +set_property(CACHE TOOLCHAIN PROPERTY STRINGS ${TOOLCHAIN_OPTIONS}) +if (NOT ${TOOLCHAIN} IN_LIST TOOLCHAIN_OPTIONS) + message(FATAL_ERROR "Invalid toolchain ${TOOLCHAIN}") +endif() + +set(CMAKE_TOOLCHAIN_FILE "${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}.cmake") + +project(INAV VERSION 2.5.0) + +ENABLE_LANGUAGE(ASM) + +set(CMAKE_C_STANDARD 99) +set(CMAKE_C_EXTENSIONS ON) +set(CMAKE_C_STANDARD_REQUIRED ON) +set(CMAKE_CXX_STANDARD 11) +set(CMAKE_CXX_EXTENSIONS ON) +set(CMAKE_CXX_STANDARD_REQUIRED ON) + +find_program(RUBY_EXECUTABLE ruby) +if (NOT RUBY_EXECUTABLE) + message(FATAL_ERROR "Could not find ruby") +endif() + +execute_process(COMMAND git rev-parse --short HEAD + OUTPUT_STRIP_TRAILING_WHITESPACE + RESULT_VARIABLE NO_GIT_HASH + OUTPUT_VARIABLE GIT_SHORT_HASH) +if (NO_GIT_HASH) + message(FATAL_ERROR "Could not find git revision. Is git installed?") +endif() + +set(INAV_DIR "${CMAKE_CURRENT_SOURCE_DIR}") +set(INAV_LIB_DIR "${CMAKE_CURRENT_SOURCE_DIR}/lib") +set(INAV_UTILS_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src/utils") +set(INAV_MAIN_SRC_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src/main") + +list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake") + +include(settings) +include(inav) +include(stm32) + +add_subdirectory(src) + +collect_targets() + +message("-- Build type: ${CMAKE_BUILD_TYPE}") diff --git a/cmake/arm-none-eabi.cmake b/cmake/arm-none-eabi.cmake new file mode 100644 index 00000000000..18c6102991a --- /dev/null +++ b/cmake/arm-none-eabi.cmake @@ -0,0 +1,63 @@ +set(CMAKE_SYSTEM_NAME Generic) +set(CMAKE_SYSTEM_PROCESSOR arm) + +if(WIN32) + set(TOOL_EXECUTABLE_SUFFIX ".exe") +endif() + +set(TARGET_TRIPLET "arm-none-eabi") +set(gcc "${TARGET_TRIPLET}-gcc${TOOL_EXECUTABLE_SUFFIX}") + +find_program(GCC "${gcc}") +if (NOT GCC) + message(FATAL_ERROR "Could not find ${gcc}") +endif() + +set(ARM_NONE_EABI_GCC_VERSION 9.2.1) + +execute_process(COMMAND "${GCC}" -dumpversion + OUTPUT_STRIP_TRAILING_WHITESPACE + OUTPUT_VARIABLE GCC_VERSION) + +if (NOT ${ARM_NONE_EABI_GCC_VERSION} STREQUAL ${GCC_VERSION}) + # TODO: Show how to override on cmdline or install builtin compiler + message(FATAL_ERROR "Expecting gcc version ${ARM_NONE_EABI_GCC_VERSION}, but found ${GCC_VERSION}") +endif() + +get_filename_component(TOOLCHAIN_BIN_DIR "${GCC}" DIRECTORY) + +set(CMAKE_TRY_COMPILE_TARGET_TYPE STATIC_LIBRARY) +set(CMAKE_ASM_COMPILER "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-gcc${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "asm compiler") +set(CMAKE_C_COMPILER "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-gcc${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c compiler") +set(CMAKE_CXX_COMPILER "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-g++${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c++ compiler") +set(CMAKE_OBJCOPY "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-objcopy${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "objcopy tool") +set(CMAKE_OBJDUMP "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-objdump${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "objdump tool") +set(CMAKE_SIZE "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-size${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "size tool") +set(CMAKE_DEBUGER "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-gdb${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "debuger") +set(CMAKE_CPPFILT "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-c++filt${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c++filt") +set(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER) +set(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY) +set(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE ONLY) +set(CMAKE_EXECUTABLE_SUFFIX ".elf") + +if(NOT CMAKE_CONFIGURATION_TYPES) + set(CMAKE_CONFIGURATION_TYPES Debug Release RelWithDebInfo) +endif() +set(CMAKE_BUILD_TYPE RelWithDebInfo CACHE STRING "Build Type" FORCE) +set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS ${CMAKE_CONFIGURATION_TYPES}) + +set(arm_none_eabi_debug "-Og -g") +set(arm_none_eabi_release "-O2 -DNDEBUG -flto -fuse-linker-plugin") +set(arm_none_eabi_relwithdebinfo "-ggdb3 ${arm_none_eabi_release}") + +SET(CMAKE_C_FLAGS_DEBUG ${arm_none_eabi_debug} CACHE INTERNAL "c compiler flags debug") +SET(CMAKE_CXX_FLAGS_DEBUG ${arm_none_eabi_debug} CACHE INTERNAL "c++ compiler flags debug") +SET(CMAKE_ASM_FLAGS_DEBUG ${arm_none_eabi_debug} CACHE INTERNAL "asm compiler flags debug") + +SET(CMAKE_C_FLAGS_RELEASE ${arm_none_eabi_release} CACHE INTERNAL "c compiler flags release") +SET(CMAKE_CXX_FLAGS_RELEASE ${arm_none_eabi_release} CACHE INTERNAL "cxx compiler flags release") +SET(CMAKE_ASM_FLAGS_RELEASE ${arm_none_eabi_release} CACHE INTERNAL "asm compiler flags release") + +SET(CMAKE_C_FLAGS_RELWITHDEBINFO ${arm_none_eabi_relwithdebinfo} CACHE INTERNAL "c compiler flags release") +SET(CMAKE_CXX_FLAGS_RELWITHDEBINFO ${arm_none_eabi_relwithdebinfo} CACHE INTERNAL "cxx compiler flags release") +SET(CMAKE_ASM_FLAGS_RELWITHDEBINFO ${arm_none_eabi_relwithdebinfo} CACHE INTERNAL "asm compiler flags release") diff --git a/cmake/inav.cmake b/cmake/inav.cmake new file mode 100644 index 00000000000..190fb08193d --- /dev/null +++ b/cmake/inav.cmake @@ -0,0 +1,65 @@ +set(INAV_INCLUDE_DIRS + "${INAV_LIB_DIR}" + "${INAV_MAIN_SRC_DIR}" + "${INAV_LIB_DIR}/main/MAVLink" +) + +# TODO: We need a way to override HSE_VALUE +set(INAV_DEFINITIONS + __FORKNAME__=inav + __REVISION__="${GIT_SHORT_HASH}" + HSE_VALUE=8000000 +) + +set(INAV_COMPILE_OPTIONS + -Wall + -Wextra + -Wunsafe-loop-optimizations + -Wdouble-promotion + -Wstrict-prototypes + -Werror=switch +) + +macro(main_sources) # list-var + list(TRANSFORM ${ARGV0} PREPEND "${INAV_MAIN_SRC_DIR}/") +endmacro() + +macro(exclude_basenames) # list-var excludes-var + set(_filtered "") + foreach(item ${${ARGV0}}) + get_filename_component(basename ${item} NAME) + if (NOT ${basename} IN_LIST ${ARGV1}) + list(APPEND _filtered ${item}) + endif() + endforeach() + set(${ARGV0} ${_filtered}) +endmacro() + +macro(glob_except) # var-name pattern excludes-var + file(GLOB ${ARGV0} ${ARGV1}) + exclude_basenames(${ARGV0} ${ARGV2}) +endmacro() + +function(setup_firmware_target name) + target_compile_options(${name} PRIVATE ${INAV_COMPILE_OPTIONS}) + target_include_directories(${name} PRIVATE ${INAV_INCLUDE_DIRS}) + target_compile_definitions(${name} PRIVATE ${INAV_DEFINITIONS} __TARGET__="${name}") + enable_settings(${name}) + # XXX: Don't make SETTINGS_GENERATED_C part of the build, + # since it's compiled via #include in settings.c. This will + # change once we move off PGs + target_sources(${name} PRIVATE "${CMAKE_CURRENT_BINARY_DIR}/${name}/${SETTINGS_GENERATED_H}") + set_target_properties(${name} PROPERTIES + RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin" + ) + get_property(targets GLOBAL PROPERTY VALID_TARGETS) + set_property(GLOBAL PROPERTY VALID_TARGETS "${targets} ${name}") +endfunction() + +function(collect_targets) + get_property(targets GLOBAL PROPERTY VALID_TARGETS) + list(SORT targets) + add_custom_target("targets" + COMMAND cmake -E echo "Valid targets: ${targets}") + set_property(TARGET "targets" PROPERTY TARGET_MESSAGES OFF) +endfunction() diff --git a/cmake/settings.cmake b/cmake/settings.cmake new file mode 100644 index 00000000000..f74f6589d99 --- /dev/null +++ b/cmake/settings.cmake @@ -0,0 +1,25 @@ +set(SETTINGS_GENERATED "settings_generated") +set(SETTINGS_GENERATED_C "${SETTINGS_GENERATED}.c") +set(SETTINGS_GENERATED_H "${SETTINGS_GENERATED}.h") +set(SETTINGS_FILE "${INAV_MAIN_SRC_DIR}/fc/settings.yaml") +set(SETTINGS_GENERATOR "${INAV_UTILS_DIR}/settings.rb") + +function(enable_settings target) + set(dir "${CMAKE_CURRENT_BINARY_DIR}/${target}") + target_include_directories(${target} PRIVATE ${dir}) + get_target_property(options ${target} COMPILE_OPTIONS) + get_target_property(includes ${target} INCLUDE_DIRECTORIES) + list(TRANSFORM includes PREPEND "-I") + get_target_property(defs ${target} COMPILE_DEFINITIONS) + list(TRANSFORM defs PREPEND "-D") + list(APPEND cflags ${options}) + list(APPEND cflags ${includes}) + list(APPEND cflags ${defs}) + add_custom_command( + OUTPUT ${dir}/${SETTINGS_GENERATED_H} ${dir}/${SETTINGS_GENERATED_C} + COMMAND + ${CMAKE_COMMAND} -E env CFLAGS="${cflags}" TARGET=${target} + ${RUBY_EXECUTABLE} ${SETTINGS_GENERATOR} ${INAV_DIR} ${SETTINGS_FILE} -o "${dir}" + DEPENDS ${SETTINGS_GENERATOR} ${SETTINGS_FILE} + ) +endfunction() diff --git a/cmake/stm32-usb.cmake b/cmake/stm32-usb.cmake new file mode 100644 index 00000000000..40dbf413b5a --- /dev/null +++ b/cmake/stm32-usb.cmake @@ -0,0 +1,65 @@ +set(STM32_STDPERIPH_USBOTG_DIR "${INAV_LIB_DIR}/main/STM32_USB_OTG_Driver") +set(STM32_STDPERIPH_USBCORE_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Core") +set(STM32_STDPERIPH_USBCDC_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/cdc") +set(STM32_STDPERIPH_USBHID_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/hid") +set(STM32_STDPERIPH_USBWRAPPER_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/hid_cdc_wrapper") +set(STM32_STDPERIPH_USBMSC_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/msc") +set(STM32_STDPERIPH_USBFS_DIR "${INAV_LIB_DIR}/main/STM32_USB-FS-Device_Driver") + +set(STM32_STDPERIPH_USB_INCLUDE_DIRS + "${STM32_STDPERIPH_USBOTG_DIR}/inc" + "${STM32_STDPERIPH_USBCORE_DIR}/inc" + "${STM32_STDPERIPH_USBCDC_DIR}/inc" + "${STM32_STDPERIPH_USBHID_DIR}/inc" + "${STM32_STDPERIPH_USBWRAPPER_DIR}/inc" + "${STM32_STDPERIPH_USBMSC_DIR}/inc" + "${STM32_STDPERIPH_USBFS_DIR}/inc" +) + +SET(STM32_STDPERIPH_USBOTG_SRC_EXCLUDES + usb_bsp_template.c + usb_conf_template.c + usb_hcd_int.c + usb_hcd.c + usb_otg.c +) +set(STM32_STDPERIPH_USBOTG_SRC + usb_core.c + usb_dcd.c + usb_dcd_int.c +) +list(TRANSFORM STM32_STDPERIPH_USBOTG_SRC PREPEND "${STM32_STDPERIPH_USBOTG_DIR}/src/") + +set(STM32_STDPERIPH_USBCORE_SRC + usbd_core.c + usbd_ioreq.c + usbd_req.c +) +list(TRANSFORM STM32_STDPERIPH_USBCORE_SRC PREPEND "${STM32_STDPERIPH_USBCORE_DIR}/src/") + +set(STM32_STDPERIPH_USBCDC_SRC + "${STM32_STDPERIPH_USBCDC_DIR}/src/usbd_cdc_core.c" +) + +set(STM32_STDPERIPH_USBHID_SRC + "${STM32_STDPERIPH_USBHID_DIR}/src/usbd_hid_core.c" +) + +set(STM32_STDPERIPH_USBWRAPPER_SRC + "${STM32_STDPERIPH_USBWRAPPER_DIR}/src/usbd_hid_cdc_wrapper.c" +) + +set(STM32_STDPERIPH_USBMSC_SRC + usbd_msc_bot.c + usbd_msc_core.c + usbd_msc_data.c + usbd_msc_scsi.c +) +list(TRANSFORM STM32_STDPERIPH_USBMSC_SRC PREPEND "${STM32_STDPERIPH_USBMSC_DIR}/src/") + +list(APPEND STM32_STDPERIPH_USB_SRC ${STM32_STDPERIPH_USBOTG_SRC}) +list(APPEND STM32_STDPERIPH_USB_SRC ${STM32_STDPERIPH_USBCORE_SRC}) +list(APPEND STM32_STDPERIPH_USB_SRC ${STM32_STDPERIPH_USBCDC_SRC}) +list(APPEND STM32_STDPERIPH_USB_SRC ${STM32_STDPERIPH_USBHID_SRC}) +list(APPEND STM32_STDPERIPH_USB_SRC ${STM32_STDPERIPH_USBWRAPPER_SRC}) +list(APPEND STM32_STDPERIPH_USB_SRC ${STM32_STDPERIPH_USBMSC_SRC}) diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake new file mode 100644 index 00000000000..d22eb104a6e --- /dev/null +++ b/cmake/stm32.cmake @@ -0,0 +1,263 @@ +include(arm-none-eabi) +include(stm32-usb) + +set(CMSIS_DIR "${INAV_LIB_DIR}/main/CMSIS") +set(CMSIS_INCLUDE_DIR "${CMSIS_DIR}/Core/Include") +set(CMSIS_DSP_DIR "${INAV_LIB_DIR}/main/CMSIS/DSP") +set(CMSIS_DSP_INCLUDE_DIR "${CMSIS_DSP_DIR}/Include") + +set(CMSIS_DSP_SRC + BasicMathFunctions/arm_mult_f32.c + TransformFunctions/arm_rfft_fast_f32.c + TransformFunctions/arm_cfft_f32.c + TransformFunctions/arm_rfft_fast_init_f32.c + TransformFunctions/arm_cfft_radix8_f32.c + TransformFunctions/arm_bitreversal2.S + CommonTables/arm_common_tables.c + ComplexMathFunctions/arm_cmplx_mag_f32.c + StatisticsFunctions/arm_max_f32.c +) +list(TRANSFORM CMSIS_DSP_SRC PREPEND "${CMSIS_DSP_DIR}/Source/") + +set(STM32_STARTUP_DIR "${INAV_MAIN_SRC_DIR}/startup") + +set(STM32_VCP_SRC + drivers/serial_usb_vcp.c + drivers/usb_io.c +) +main_sources(STM32_VCP_SRC) + +set(STM32_MSC_SRC + msc/usbd_msc_desc.c + msc/usbd_storage.c +) +main_sources(STM32_MSC_SRC) + +set(STM32_MSC_FLASH_SRC + msc/usbd_storage_emfat.c + msc/emfat.c + msc/emfat_file.c +) +main_sources(STM32_MSC_FLASH_SRC) + +set(STM32F4_STDPERIPH_DIR "${INAV_LIB_DIR}/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver") +set(STM32F4_CMSIS_DEVICE_DIR "${INAV_LIB_DIR}/main/STM32F4/Drivers/CMSIS/Device/ST/STM32F4xx") +set(STM32F4_CMSIS_DRIVERS_DIR "${INAV_LIB_DIR}/main/STM32F4/Drivers/CMSIS") +set(STM32F4_VCP_DIR "${INAV_MAIN_SRC_DIR}/vcpf4") + +set(STM32F4_STDPERIPH_SRC_EXCLUDES + stm32f4xx_can.c + stm32f4xx_cec.c + stm32f4xx_crc.c + stm32f4xx_cryp.c + stm32f4xx_cryp_aes.c + stm32f4xx_cryp_des.c + stm32f4xx_cryp_tdes.c + stm32f4xx_dbgmcu.c + stm32f4xx_dsi.c + stm32f4xx_flash_ramfunc.c + stm32f4xx_fmpi2c.c + stm32f4xx_fmc.c + stm32f4xx_hash.c + stm32f4xx_hash_md5.c + stm32f4xx_hash_sha1.c + stm32f4xx_lptim.c + stm32f4xx_qspi.c + stm32f4xx_sai.c + stm32f4xx_spdifrx.c +) + +set(STM32F4_STDPERIPH_SRC_DIR "${STM32F4_STDPERIPH_DIR}/Src") +glob_except(STM32F4_STDPERIPH_SRC "${STM32F4_STDPERIPH_SRC_DIR}/*.c" STM32F4_STDPERIPH_SRC_EXCLUDES) + +set(STM32F4_VCP_SRC + stm32f4xx_it.c + usb_bsp.c + usbd_desc.c + usbd_usr.c + usbd_cdc_vcp.c +) +list(TRANSFORM STM32F4_VCP_SRC PREPEND "${STM32F4_VCP_DIR}/") + +set(STM32F4_MSC_SRC + drivers/usb_msc_f4xx.c +) +main_sources(STM32F4_MSC_SRC) + +set(STM32F4_INCLUDE_DIRS + "${CMSIS_INCLUDE_DIR}" + "${CMSIS_DSP_INCLUDE_DIR}" + "${STM32F4_STDPERIPH_DIR}/inc" + "${STM32F4_CMSIS_DEVICE_DIR}" + "${STM32F4_CMSIS_DRIVERS_DIR}" + "${STM32F4_VCP_DIR}" +) + +set(STM32_INCLUDE_DIRS + "${INAV_MAIN_SRC_DIR}/target" +) + +set(STM32_LINKER_DIR "${INAV_MAIN_SRC_DIR}/target/link") + +#if(SEMIHOSTING) +# set(SEMIHOSTING_DEFINITIONS "SEMIHOSTING") +# set(SEMIHOSTING_LDFLAGS +# --specs=rdimon.specs +# -lc +# -lrdimon +# ) +#else() +# set(SYS) +#endif() +#ifneq ($(SEMIHOSTING),) +#SEMIHOSTING_CFLAGS = -DSEMIHOSTING +#SEMIHOSTING_LDFLAGS = --specs=rdimon.specs -lc -lrdimon +#SYSLIB := +#else +#SEMIHOSTING_LDFLAGS = +#SEMIHOSTING_CFLAGS = +#SYSLIB := -lnosys +#endif + +set(STM32_LINK_LIBRARIES + -lm + -lc +) + +set(STM32_LINK_OPTIONS + -nostartfiles + --specs=nano.specs + -static + -Wl,-gc-sections,-Map,target.map + -Wl,-L${STM32_LINKER_DIR} + -Wl,--cref + -Wl,--no-wchar-size-warning + -Wl,--print-memory-usage +) + +set(STM32F4_SRC + target/system_stm32f4xx.c + drivers/accgyro/accgyro.c + drivers/accgyro/accgyro_mpu.c + drivers/adc_stm32f4xx.c + drivers/adc_stm32f4xx.c + drivers/bus_i2c_stm32f40x.c + drivers/serial_softserial.c + drivers/serial_uart_stm32f4xx.c + drivers/system_stm32f4xx.c + drivers/timer.c + drivers/timer_impl_stdperiph.c + drivers/timer_stm32f4xx.c + drivers/uart_inverter.c + drivers/dma_stm32f4xx.c + drivers/sdcard/sdmmc_sdio_f4xx.c +) + +main_sources(STM32F4_SRC) + +set(STM32F4_DEFINITIONS + STM32F4 + USE_STDPERIPH_DRIVER + ARM_MATH_MATRIX_CHECK + ARM_MATH_ROUNDING + __FPU_PRESENT=1 + UNALIGNED_SUPPORT_DISABLE + ARM_MATH_CM4 +) + +set(STM32F4_COMMON_OPTIONS + -mthumb + -mcpu=cortex-m4 + -march=armv7e-m + -mfloat-abi=hard + -mfpu=fpv4-sp-d16 + -fsingle-precision-constant +) + +set(STM32F4_COMPILE_OPTIONS +) + +set(SETM32F4_LINK_OPTIONS +) + +set(STM32F411_STDPERIPH_SRC_EXCLUDES "stm32f4xx_fsmc.c") + +set(STM32F411_COMPILE_DEFINITIONS + FLASH_SIZE=512 +) + +macro(get_stm32_target_features) # out-var dir + file(READ "${ARGV1}/target.h" _contents) + string(REGEX MATCH "#define[\t ]+USE_VCP" HAS_VCP ${_contents}) + if(HAS_VCP) + list(APPEND ${ARGV0} VCP) + endif() + string(REGEX MATCH "define[\t ]+USE_FLASHFS" HAS_FLASHFS ${_contents}) + if(HAS_FLASHFS) + list(APPEND ${ARGV0} FLASHFS) + endif() + if (HAS_FLASHFS) # || SDCARD + list(APPEND ${ARGV0} MSC) + endif() +endmacro() + +function(target_stm32 name) + # Main .elf target + add_executable(${name} ${COMMON_SRC} ${CMSIS_DSP_SRC}) + file(GLOB target_c_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.c") + file(GLOB target_h_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.h") + target_sources(${name} PRIVATE ${target_c_sources} ${target_h_sources}) + target_include_directories(${name} PRIVATE . ${STM32_INCLUDE_DIRS}) + target_link_libraries(${name} PRIVATE ${STM32_LINK_LIBRARIES}) + target_link_options(${name} PRIVATE ${STM32_LINK_OPTIONS}) + get_stm32_target_features(features "${CMAKE_CURRENT_SOURCE_DIR}") + set_property(TARGET ${name} PROPERTY FEATURES ${features}) + if(VCP IN_LIST features) + target_sources(${name} PRIVATE ${STM32_VCP_SRC}) + endif() + if(MSC IN_LIST features) + target_sources(${name} PRIVATE ${STM32_MSC_SRC}) + if (FLASHFS IN_LIST features) + target_sources(${name} PRIVATE ${STM32_MSC_FLASH_SRC}) + endif() + endif() + # Generate .hex + set(hexdir "${CMAKE_BINARY_DIR}/hex") + set(hex "${hexdir}/$.hex") + add_custom_command(TARGET ${name} POST_BUILD + COMMAND ${CMAKE_COMMAND} -E make_directory "${hexdir}" + COMMAND ${CMAKE_OBJCOPY} -Oihex $ "${hex}") + # clean_ + set(clean_target "clean_${name}") + add_custom_target(${clean_target} + COMMAND cmake -E rm -r "${CMAKE_CURRENT_BINARY_DIR}" + COMMENT "Removeng intermediate files for ${name}") + set_property(TARGET ${clean_target} PROPERTY TARGET_MESSAGES OFF) +endfunction() + +function(target_stm32f4xx name) + target_stm32(${name}) + target_sources(${name} PRIVATE ${STM32F4_SRC}) + target_compile_options(${name} PRIVATE ${STM32F4_COMMON_OPTIONS} ${STM32F4_COMPILE_OPTIONS}) + target_include_directories(${name} PRIVATE ${STM32_STDPERIPH_USB_INCLUDE_DIRS} ${STM32F4_INCLUDE_DIRS}) + target_compile_definitions(${name} PRIVATE ${STM32F4_DEFINITIONS}) + target_link_options(${name} PRIVATE ${STM32F4_COMMON_OPTIONS} ${STM32F4_LINK_OPTIONS}) + + get_property(features TARGET ${name} PROPERTY FEATURES) + if(VCP IN_LIST features) + target_sources(${name} PRIVATE ${STM32_STDPERIPH_USB_SRC} ${STM32F4_VCP_SRC}) + endif() + if(MSC IN_LIST features) + target_sources(${name} PRIVATE ${STM32F4_MSC_SRC}) + endif() +endfunction() + +function(target_stm32f411 name) + target_stm32f4xx(${name}) + set(STM32F411_STDPERIPH_SRC ${STM32F4_STDPERIPH_SRC}) + exclude_basenames(STM32F411_STDPERIPH_SRC STM32F411_STDPERIPH_SRC_EXCLUDES) + target_sources(${name} PRIVATE "${STM32_STARTUP_DIR}/startup_stm32f411xe.s" ${STM32F411_STDPERIPH_SRC}) + target_link_options(${name} PRIVATE "-T${STM32_LINKER_DIR}/stm32_flash_f411.ld") + target_compile_definitions(${name} PRIVATE STM32F411xE ${STM32F411_COMPILE_DEFINITIONS}) + setup_firmware_target(${name}) +endfunction() diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt new file mode 100644 index 00000000000..a631d744480 --- /dev/null +++ b/src/main/CMakeLists.txt @@ -0,0 +1,276 @@ +set(COMMON_SRC + main.c + + target/common_hardware.c + + build/assert.c + build/build_config.c + build/debug.c + build/version.c + + common/bitarray.c + common/calibration.c + common/colorconversion.c + common/crc.c + common/encoding.c + common/filter.c + common/gps_conversion.c + common/log.c + common/logic_condition.c + common/global_functions.c + common/global_variables.c + common/maths.c + common/memory.c + common/olc.c + common/printf.c + common/streambuf.c + common/string_light.c + common/time.c + common/typeconversion.c + common/uvarint.c + + config/config_eeprom.c + config/config_streamer.c + config/feature.c + config/parameter_group.c + config/general_settings.c + + drivers/adc.c + drivers/buf_writer.c + drivers/bus.c + drivers/bus_busdev_i2c.c + drivers/bus_busdev_spi.c + drivers/bus_i2c_soft.c + drivers/bus_spi.c + drivers/display.c + drivers/display_canvas.c + drivers/display_font_metadata.c + drivers/exti.c + drivers/io.c + drivers/io_pca9685.c + drivers/irlock.c + drivers/light_led.c + drivers/osd.c + drivers/persistent.c + drivers/resource.c + drivers/rx_nrf24l01.c + drivers/rx_spi.c + drivers/rx_xn297.c + drivers/pitotmeter_adc.c + drivers/pitotmeter_virtual.c + drivers/pwm_esc_detect.c + drivers/pwm_mapping.c + drivers/pwm_output.c + drivers/pinio.c + drivers/rcc.c + drivers/rx_pwm.c + drivers/serial.c + drivers/serial_uart.c + drivers/sound_beeper.c + drivers/stack_check.c + drivers/system.c + drivers/time.c + drivers/timer.c + drivers/usb_msc.c + drivers/lights_io.c + drivers/1-wire.c + drivers/1-wire/ds_crc.c + drivers/1-wire/ds2482.c + drivers/temperature/ds18b20.c + drivers/temperature/lm75.c + drivers/pitotmeter_ms4525.c + + fc/cli.c + fc/config.c + fc/controlrate_profile.c + fc/fc_core.c + fc/fc_init.c + fc/fc_tasks.c + fc/fc_hardfaults.c + fc/fc_msp.c + fc/fc_msp_box.c + fc/rc_smoothing.c + fc/rc_adjustments.c + fc/rc_controls.c + fc/rc_curves.c + fc/rc_modes.c + fc/runtime_config.c + fc/settings.c + fc/stats.c + + flight/failsafe.c + flight/hil.c + flight/imu.c + flight/mixer.c + flight/pid.c + flight/pid_autotune.c + flight/rth_estimator.c + flight/servos.c + flight/wind_estimator.c + flight/gyroanalyse.c + flight/rpm_filter.c + flight/dynamic_gyro_notch.c + + io/beeper.c + io/esc_serialshot.c + io/servo_sbus.c + io/frsky_osd.c + io/osd_dji_hd.c + io/lights.c + io/piniobox.c + io/pwmdriver_i2c.c + io/serial.c + io/serial_4way.c + io/serial_4way_avrootloader.c + io/serial_4way_stk500v2.c + io/statusindicator.c + io/rcdevice.c + io/rcdevice_cam.c + + msp/msp_serial.c + + rx/crsf.c + rx/eleres.c + rx/fport.c + rx/ibus.c + rx/jetiexbus.c + rx/msp.c + rx/msp_override.c + rx/nrf24_cx10.c + rx/nrf24_inav.c + rx/nrf24_h8_3d.c + rx/nrf24_syma.c + rx/nrf24_v202.c + rx/pwm.c + rx/frsky_crc.c + rx/rx.c + rx/rx_spi.c + rx/sbus.c + rx/sbus_channels.c + rx/spektrum.c + rx/sumd.c + rx/sumh.c + rx/uib_rx.c + rx/xbus.c + + scheduler/scheduler.c + + sensors/acceleration.c + sensors/battery.c + sensors/boardalignment.c + sensors/compass.c + sensors/diagnostics.c + sensors/gyro.c + sensors/initialisation.c + sensors/esc_sensor.c + sensors/irlock.c + sensors/temperature.c + + uav_interconnect/uav_interconnect_bus.c + uav_interconnect/uav_interconnect_rangefinder.c + + blackbox/blackbox.c + blackbox/blackbox_encoding.c + blackbox/blackbox_io.c + + cms/cms.c + cms/cms_menu_battery.c + cms/cms_menu_blackbox.c + cms/cms_menu_builtin.c + cms/cms_menu_imu.c + cms/cms_menu_ledstrip.c + cms/cms_menu_misc.c + cms/cms_menu_mixer_servo.c + cms/cms_menu_navigation.c + cms/cms_menu_osd.c + cms/cms_menu_saveexit.c + cms/cms_menu_vtx.c + + drivers/accgyro/accgyro_mpu6000.c + drivers/accgyro/accgyro_mpu6500.c + drivers/barometer/barometer_bmp085.c + drivers/barometer/barometer_bmp280.c + drivers/barometer/barometer_ms56xx.c + drivers/compass/compass_ak8975.c + drivers/compass/compass_hmc5883l.c + drivers/compass/compass_mag3110.c + drivers/compass/compass_qmc5883l.c + drivers/compass/compass_ist8308.c + drivers/compass/compass_ist8310.c + drivers/compass/compass_lis3mdl.c + drivers/display_ug2864hsweg01.c + drivers/flash.c + drivers/flash_m25p16.c + drivers/light_ws2811strip.c + drivers/max7456.c + drivers/rangefinder/rangefinder_hcsr04.c + drivers/rangefinder/rangefinder_hcsr04_i2c.c + drivers/rangefinder/rangefinder_srf10.c + drivers/rangefinder/rangefinder_vl53l0x.c + drivers/rangefinder/rangefinder_virtual.c + drivers/opflow/opflow_fake.c + drivers/opflow/opflow_virtual.c + drivers/pitotmeter_adc.c + drivers/vtx_common.c + + io/rangefinder_msp.c + io/rangefinder_benewake.c + io/opflow_cxof.c + io/opflow_msp.c + io/dashboard.c + io/displayport_frsky_osd.c + io/displayport_max7456.c + io/displayport_msp.c + io/displayport_oled.c + io/displayport_hott.c + io/flashfs.c + io/gps.c + io/gps_ublox.c + io/gps_nmea.c + io/gps_naza.c + io/ledstrip.c + io/osd.c + io/osd_canvas.c + io/osd_common.c + io/osd_grid.c + io/osd_hud.c + + navigation/navigation.c + navigation/navigation_fixedwing.c + navigation/navigation_fw_launch.c + navigation/navigation_geo.c + navigation/navigation_multicopter.c + navigation/navigation_pos_estimator.c + navigation/navigation_pos_estimator_agl.c + navigation/navigation_pos_estimator_flow.c + navigation/navigation_rover_boat.c + + sensors/barometer.c + sensors/pitotmeter.c + sensors/rangefinder.c + sensors/opflow.c + + telemetry/crsf.c + telemetry/frsky.c + telemetry/frsky_d.c + telemetry/hott.c + telemetry/ibus_shared.c + telemetry/ibus.c + telemetry/ltm.c + telemetry/mavlink.c + telemetry/msp_shared.c + telemetry/smartport.c + telemetry/sim.c + telemetry/telemetry.c + + io/vtx.c + io/vtx_string.c + io/vtx_smartaudio.c + io/vtx_tramp.c + io/vtx_ffpv24g.c + io/vtx_control.c +) + +main_sources(COMMON_SRC) + +add_subdirectory(target) diff --git a/src/main/io/flashfs.c b/src/main/io/flashfs.c index bb50b269f2f..d75282cf8bf 100644 --- a/src/main/io/flashfs.c +++ b/src/main/io/flashfs.c @@ -30,8 +30,13 @@ #include #include +#include "platform.h" + +#if defined(USE_FLASHFS) + #include "drivers/flash.h" -#include "flashfs.h" + +#include "io/flashfs.h" static flashPartition_t *flashPartition; @@ -559,3 +564,5 @@ void flashfsInit(void) flashfsSeekAbs(flashfsIdentifyStartOfFreeSpace()); } } + +#endif diff --git a/src/main/target/CMakeLists.txt b/src/main/target/CMakeLists.txt new file mode 100644 index 00000000000..65f9a19c489 --- /dev/null +++ b/src/main/target/CMakeLists.txt @@ -0,0 +1,7 @@ +file(GLOB entries *) +foreach(subdir ${entries}) + set(entry "${subdir}/CMakeLists.txt") + if (EXISTS ${entry}) + add_subdirectory(${subdir}) + endif() +endforeach() diff --git a/src/main/target/MATEKF411/CMakeLists.txt b/src/main/target/MATEKF411/CMakeLists.txt new file mode 100644 index 00000000000..426c86cb5d2 --- /dev/null +++ b/src/main/target/MATEKF411/CMakeLists.txt @@ -0,0 +1,4 @@ +target_stm32f411(MATEKF411) +target_stm32f411(MATEKF411_FD_SFTSRL) +target_stm32f411(MATEKF411_RSSI) +target_stm32f411(MATEKF411_SFTSRL2) diff --git a/src/main/target/MATEKF411SE/CMakeLists.txt b/src/main/target/MATEKF411SE/CMakeLists.txt new file mode 100644 index 00000000000..0031ec68c21 --- /dev/null +++ b/src/main/target/MATEKF411SE/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f411(MATEKF411SE) diff --git a/src/main/target/NOX/CMakeLists.txt b/src/main/target/NOX/CMakeLists.txt new file mode 100644 index 00000000000..588b589c87b --- /dev/null +++ b/src/main/target/NOX/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f411(NOX) From 9c1bc1afc23173ad5893bfb5d16832cb4b303572 Mon Sep 17 00:00:00 2001 From: Stefan Naewe Date: Fri, 24 Jul 2020 18:38:32 +0200 Subject: [PATCH 096/248] [CMS] fix editing of negative servo weights The OSD/CMS doesn't allow correct editing of negative servo mixer weights. The value can only be made larger (towards positive) but not smaller. Fix that by setting the min. value for the weight to -1000. Signed-off-by: Stefan Naewe --- src/main/cms/cms_menu_mixer_servo.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/cms/cms_menu_mixer_servo.c b/src/main/cms/cms_menu_mixer_servo.c index e83869b57f0..92d18ab3a0a 100644 --- a/src/main/cms/cms_menu_mixer_servo.c +++ b/src/main/cms/cms_menu_mixer_servo.c @@ -202,7 +202,7 @@ static const OSD_Entry cmsx_menuServoMixerEntries[] = OSD_UINT8_CALLBACK_ENTRY("SERVO MIX", cmsx_menuServoMixerIndexOnChange, (&(const OSD_UINT8_t){ &tmpcurrentServoMixerIndex, 1, MAX_SERVO_RULES, 1})), OSD_UINT8_DYN_ENTRY("SERVO", (&(const OSD_UINT8_t){ &tmpServoMixer.targetChannel, 0, MAX_SUPPORTED_SERVOS, 1})), OSD_TAB_DYN_ENTRY("INPUT", (&(const OSD_TAB_t){ &tmpServoMixer.inputSource, SERVO_MIXER_INPUT_CMS_NAMES_COUNT - 1, servoMixerInputCmsNames})), - OSD_INT16_DYN_ENTRY("WEIGHT", (&(const OSD_INT16_t){&tmpServoMixer.rate, 0, 1000, 1})), + OSD_INT16_DYN_ENTRY("WEIGHT", (&(const OSD_INT16_t){&tmpServoMixer.rate, -1000, 1000, 1})), OSD_UINT8_DYN_ENTRY("SPEED", (&(const OSD_UINT8_t){&tmpServoMixer.speed, 0, 255, 1})), OSD_BACK_AND_END_ENTRY }; From 8611b37563e99c42e481727884bc9fa089dd28bd Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Wed, 24 Jun 2020 11:48:21 +0200 Subject: [PATCH 097/248] [NAV] Allow using GPS altitude instead of barometer --- src/main/fc/fc_msp_box.c | 2 +- src/main/fc/settings.yaml | 3 +++ src/main/navigation/navigation.h | 2 ++ src/main/navigation/navigation_pos_estimator.c | 5 +++-- 4 files changed, 9 insertions(+), 3 deletions(-) diff --git a/src/main/fc/fc_msp_box.c b/src/main/fc/fc_msp_box.c index 05187869d8d..9039990d568 100644 --- a/src/main/fc/fc_msp_box.c +++ b/src/main/fc/fc_msp_box.c @@ -189,7 +189,7 @@ void initActiveBoxIds(void) activeBoxIds[activeBoxIdCount++] = BOXCAMSTAB; #ifdef USE_GPS - if (STATE(ALTITUDE_CONTROL) && (sensors(SENSOR_BARO) || (STATE(AIRPLANE) && feature(FEATURE_GPS)))) { + if (STATE(ALTITUDE_CONTROL) && (sensors(SENSOR_BARO) || (feature(FEATURE_GPS) && (STATE(AIRPLANE) || positionEstimationConfig()->use_gps_no_baro)))) { activeBoxIds[activeBoxIdCount++] = BOXNAVALTHOLD; activeBoxIds[activeBoxIdCount++] = BOXSURFACE; } diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 0f56f1d9fa5..389b0b02189 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1858,6 +1858,9 @@ groups: default_value: "ON" field: use_gps_velned type: bool + - name: inav_use_gps_no_baro + field: use_gps_no_baro + type: bool - name: inav_allow_dead_reckoning description: "Defines if inav will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation" default_value: "OFF" diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 6ae99506030..cf54897bcaa 100755 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -136,6 +136,8 @@ typedef struct positionEstimationConfig_s { float max_eph_epv; // Max estimated position error acceptable for estimation (cm) float baro_epv; // Baro position error + + uint8_t use_gps_no_baro; } positionEstimationConfig_t; PG_DECLARE(positionEstimationConfig_t, positionEstimationConfig); diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c index d4dbb9a2c62..91c9938ba5c 100755 --- a/src/main/navigation/navigation_pos_estimator.c +++ b/src/main/navigation/navigation_pos_estimator.c @@ -62,7 +62,8 @@ PG_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig, .reset_altitude_type = NAV_RESET_ON_FIRST_ARM, .reset_home_type = NAV_RESET_ON_FIRST_ARM, .gravity_calibration_tolerance = 5, // 5 cm/s/s calibration error accepted (0.5% of gravity) - .use_gps_velned = 1, // "Disabled" is mandatory with gps_dyn_model = Pedestrian + .use_gps_velned = 1, // "Disabled" is mandatory with gps_dyn_model = Pedestrian + .use_gps_no_baro = 0, // Use GPS altitude if no baro is available on all aircrafts .allow_dead_reckoning = 0, .max_surface_altitude = 200, @@ -581,7 +582,7 @@ static bool estimationCalculateCorrection_Z(estimationContext_t * ctx) return true; } - else if (STATE(FIXED_WING_LEGACY) && (ctx->newFlags & EST_GPS_Z_VALID)) { + else if ((STATE(FIXED_WING_LEGACY) || positionEstimationConfig()->use_gps_no_baro) && (ctx->newFlags & EST_GPS_Z_VALID)) { // If baro is not available - use GPS Z for correction on a plane // Reset current estimate to GPS altitude if estimate not valid if (!(ctx->newFlags & EST_Z_VALID)) { From 764f2b61c468ee2e509db5ad5c1fe6125d8025a3 Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Sat, 25 Jul 2020 14:18:17 +0200 Subject: [PATCH 098/248] [NAV] Bump PG_POSITION_ESTIMATION_CONFIG version --- src/main/navigation/navigation_pos_estimator.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c index 91c9938ba5c..ddaa1b8f4f0 100755 --- a/src/main/navigation/navigation_pos_estimator.c +++ b/src/main/navigation/navigation_pos_estimator.c @@ -54,7 +54,7 @@ navigationPosEstimator_t posEstimator; -PG_REGISTER_WITH_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig, PG_POSITION_ESTIMATION_CONFIG, 4); +PG_REGISTER_WITH_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig, PG_POSITION_ESTIMATION_CONFIG, 5); PG_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig, // Inertial position estimator parameters From 72c6c682a09ec656c367e1d5174173fc7e60469d Mon Sep 17 00:00:00 2001 From: stronnag Date: Sat, 25 Jul 2020 21:22:23 +0100 Subject: [PATCH 099/248] [DOCS] document flash_ commands (#5983) --- docs/Cli.md | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/docs/Cli.md b/docs/Cli.md index a538fb2ccdc..ecc4ce4f3e6 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -123,6 +123,17 @@ A shorter form is also supported to enable and disable functions using `serial < `serial` can also be used without any argument to print the current configuration of all the serial ports. +## Flash chip management + +For targets that have a flash data chip, typically used for blackbox logs, the following additional comamnds are provided. + +| Command | Effect | +| ------- | ------ | +| `flash_erase` | Erases the flash chip | +| `flash_info` | Displays flash chip information (used, free etc.) | +| `flash_read
` | Reads `length` bytes from `address` | +| `flash_write
` | Writes `data` to `address` | + ## CLI Variable Reference See [Settings.md](Settings.md). From b5633bb28a4a1bbb3f3d1c2c9e96c04174c6b56c Mon Sep 17 00:00:00 2001 From: azol Date: Sun, 8 Mar 2020 16:43:09 +0800 Subject: [PATCH 100/248] add speedy bee f7 target --- src/main/target/SPEEDYBEEF7/config.c | 55 +++++++++ src/main/target/SPEEDYBEEF7/target.c | 38 +++++++ src/main/target/SPEEDYBEEF7/target.h | 158 ++++++++++++++++++++++++++ src/main/target/SPEEDYBEEF7/target.mk | 17 +++ 4 files changed, 268 insertions(+) create mode 100644 src/main/target/SPEEDYBEEF7/config.c create mode 100644 src/main/target/SPEEDYBEEF7/target.c create mode 100644 src/main/target/SPEEDYBEEF7/target.h create mode 100644 src/main/target/SPEEDYBEEF7/target.mk diff --git a/src/main/target/SPEEDYBEEF7/config.c b/src/main/target/SPEEDYBEEF7/config.c new file mode 100644 index 00000000000..f5bc752e356 --- /dev/null +++ b/src/main/target/SPEEDYBEEF7/config.c @@ -0,0 +1,55 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include + +#include + +#include "common/axis.h" + +#include "config/config_master.h" +#include "config/feature.h" + +#include "drivers/sensor.h" +#include "drivers/pwm_esc_detect.h" +#include "drivers/pwm_output.h" +#include "drivers/serial.h" + +#include "fc/rc_controls.h" + +#include "flight/failsafe.h" +#include "flight/mixer.h" +#include "flight/pid.h" + +#include "rx/rx.h" + +#include "io/serial.h" + +#include "sensors/battery.h" +#include "sensors/sensors.h" + +#include "telemetry/telemetry.h" + + +#define BLUETOOTH_MSP_BAUDRATE BAUD_19200 + +void targetConfiguration(void) +{ + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART3)].functionMask = FUNCTION_MSP; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART3)].msp_baudrateIndex = BLUETOOTH_MSP_BAUDRATE; +} diff --git a/src/main/target/SPEEDYBEEF7/target.c b/src/main/target/SPEEDYBEEF7/target.c new file mode 100644 index 00000000000..9d4fafb6cd8 --- /dev/null +++ b/src/main/target/SPEEDYBEEF7/target.c @@ -0,0 +1,38 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include + +#include +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/bus.h" + +const timerHardware_t timerHardware[] = { + DEF_TIM(TIM5, CH4, PA3, TIM_USE_PPM, 0, 0), // PPM + + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 + DEF_TIM(TIM3, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 + DEF_TIM(TIM3, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 1), // S5 + + DEF_TIM(TIM4, CH2, PB7, TIM_USE_LED | TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // LED/S6 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/SPEEDYBEEF7/target.h b/src/main/target/SPEEDYBEEF7/target.h new file mode 100644 index 00000000000..2a743133fd6 --- /dev/null +++ b/src/main/target/SPEEDYBEEF7/target.h @@ -0,0 +1,158 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "SBF7" +#define USBD_PRODUCT_STRING "SpeedyBeeF7" + +#define LED0 PC14 + +// UARTs +#define USB_IO +#define USE_VCP +#define VBUS_SENSING_PIN PC15 +#define VBUS_SENSING_ENABLED + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PC11 +#define UART3_TX_PIN PC10 + +#define USE_UART4 +#define UART4_RX_PIN PA1 +#define UART4_TX_PIN PA0 + +#define USE_UART5 +#define UART5_RX_PIN PD2 +#define UART5_TX_PIN PC12 + +#define SERIAL_PORT_COUNT 6 + +// GYRO -- SPI1 +#define USE_SPI +#define USE_SPI_DEVICE_1 + +#define USE_ACC +#define USE_GYRO +#define USE_MPU_DATA_READY_SIGNAL +#define USE_EXTI + +#define USE_ACC_ICM20689 +#define USE_GYRO_ICM20689 + +#define GYRO_INT_EXTI PC4 +#define ICM20689_CS_PIN PA4 +#define ICM20689_SPI_BUS BUS_SPI1 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +// OSD -- SPI2 +#define USE_SPI_DEVICE_2 +#define USE_OSD +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN PB12 + +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +// Onboard 32MB Flash +#define USE_SPI_DEVICE_3 + +#define M25P16_CS_PIN PC0 +#define M25P16_SPI_BUS BUS_SPI3 +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +// Onboard BMP280 Baro --- I2C1 +#define USE_I2C +#define USE_BARO +#define USE_BARO_BMP280 +#define BARO_I2C_BUS BUS_I2C1 + +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 +#define I2C1_SDA PB9 + +// External I2C Pads -- I2C2 +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C2 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +#define TEMPERATURE_I2C_BUS BUS_I2C2 + +#define PITOT_I2C_BUS BUS_I2C2 + +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS BUS_I2C2 + +// ADC +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC1 +#define ADC_CHANNEL_3_PIN PC3 + +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 + +// FC Default Config +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX) +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define SERIALRX_UART SERIAL_PORT_USART2 +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS + +#define MAX_PWM_OUTPUT_PORTS 6 + +#define CURRENT_METER_SCALE 102 + +// Used Pins +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) + + diff --git a/src/main/target/SPEEDYBEEF7/target.mk b/src/main/target/SPEEDYBEEF7/target.mk new file mode 100644 index 00000000000..c582b37531e --- /dev/null +++ b/src/main/target/SPEEDYBEEF7/target.mk @@ -0,0 +1,17 @@ +F7X2RE_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH + +TARGET_SRC = \ + drivers/accgyro/accgyro_icm20689.c \ + drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_bmp085.c \ + drivers/barometer/barometer_ms56xx.c \ + drivers/compass/compass_hmc5883l.c \ + drivers/compass/compass_qmc5883l.c \ + drivers/compass/compass_ist8310.c \ + drivers/compass/compass_ist8308.c \ + drivers/compass/compass_mag3110.c \ + drivers/compass/compass_lis3mdl.c \ + drivers/pitotmeter_adc.c \ + drivers/light_ws2811strip.c \ + drivers/max7456.c From 9576fa30351123121f8d5cde537581e867110ac1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Tue, 28 Jul 2020 21:36:34 +0100 Subject: [PATCH 101/248] [BOXES] Expose constants for permanent box IDs for USER1 and USER2 This way targets can reference them by the constant name instead of having to hardcode 47 and 48. --- src/main/fc/fc_msp_box.c | 4 ++-- src/main/fc/fc_msp_box.h | 4 +++- src/main/io/piniobox.c | 2 +- src/main/target/FLYWOOF7DUAL/target.c | 8 ++++++-- src/main/target/HGLRCF722/config.c | 8 ++++++-- src/main/target/MATEKF411SE/config.c | 5 ++++- src/main/target/MATEKF722PX/config.c | 10 +++++++--- src/main/target/MATEKF722SE/config.c | 8 ++++++-- src/main/target/MATEKF765/config.c | 8 ++++++-- 9 files changed, 41 insertions(+), 16 deletions(-) diff --git a/src/main/fc/fc_msp_box.c b/src/main/fc/fc_msp_box.c index 9039990d568..3afe82c9cbc 100644 --- a/src/main/fc/fc_msp_box.c +++ b/src/main/fc/fc_msp_box.c @@ -82,8 +82,8 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = { { BOXOSDALT3, "OSD ALT 3", 44 }, { BOXNAVCRUISE, "NAV CRUISE", 45 }, { BOXBRAKING, "MC BRAKING", 46 }, - { BOXUSER1, "USER1", 47 }, - { BOXUSER2, "USER2", 48 }, + { BOXUSER1, "USER1", BOX_PERMANENT_ID_USER1 }, + { BOXUSER2, "USER2", BOX_PERMANENT_ID_USER2 }, { BOXLOITERDIRCHN, "LOITER CHANGE", 49 }, { BOXMSPRCOVERRIDE, "MSP RC OVERRIDE", 50 }, { CHECKBOX_ITEM_COUNT, NULL, 0xFF } diff --git a/src/main/fc/fc_msp_box.h b/src/main/fc/fc_msp_box.h index b5ca2559915..cefbeab29f1 100644 --- a/src/main/fc/fc_msp_box.h +++ b/src/main/fc/fc_msp_box.h @@ -19,7 +19,9 @@ #include "fc/rc_modes.h" -#define PERMANENT_ID_NONE 255 // A permanent ID for no box mode +#define BOX_PERMANENT_ID_USER1 47 +#define BOX_PERMANENT_ID_USER2 48 +#define BOX_PERMANENT_ID_NONE 255 // A permanent ID for no box mode typedef struct box_s { const uint8_t boxId; // see boxId_e diff --git a/src/main/io/piniobox.c b/src/main/io/piniobox.c index 3bcc7cd5b86..b8b01ad3298 100644 --- a/src/main/io/piniobox.c +++ b/src/main/io/piniobox.c @@ -40,7 +40,7 @@ PG_REGISTER_WITH_RESET_TEMPLATE(pinioBoxConfig_t, pinioBoxConfig, PG_PINIOBOX_CONFIG, 1); PG_RESET_TEMPLATE(pinioBoxConfig_t, pinioBoxConfig, - { PERMANENT_ID_NONE, PERMANENT_ID_NONE, PERMANENT_ID_NONE, PERMANENT_ID_NONE } + { BOX_PERMANENT_ID_NONE, BOX_PERMANENT_ID_NONE, BOX_PERMANENT_ID_NONE, BOX_PERMANENT_ID_NONE } ); typedef struct pinioBoxRuntimeConfig_s { diff --git a/src/main/target/FLYWOOF7DUAL/target.c b/src/main/target/FLYWOOF7DUAL/target.c index d9dc7ccc9bc..da50075f953 100644 --- a/src/main/target/FLYWOOF7DUAL/target.c +++ b/src/main/target/FLYWOOF7DUAL/target.c @@ -18,11 +18,15 @@ #include #include #include + #include "drivers/io.h" #include "drivers/bus.h" #include "drivers/timer.h" #include "drivers/sensor.h" #include "drivers/pwm_mapping.h" + +#include "fc/fc_msp_box.h" + #include "io/piniobox.h" // IMU 1 @@ -50,6 +54,6 @@ const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); void targetConfiguration(void) { - pinioBoxConfigMutable()->permanentId[0] = 47; - pinioBoxConfigMutable()->permanentId[1] = 48; + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; } diff --git a/src/main/target/HGLRCF722/config.c b/src/main/target/HGLRCF722/config.c index 17131889016..4f04f3b4aaa 100644 --- a/src/main/target/HGLRCF722/config.c +++ b/src/main/target/HGLRCF722/config.c @@ -23,11 +23,15 @@ */ #include + #include "platform.h" + +#include "fc/fc_msp_box.h" + #include "io/piniobox.h" void targetConfiguration(void) { - pinioBoxConfigMutable()->permanentId[0] = 47; - pinioBoxConfigMutable()->permanentId[1] = 48; + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; } diff --git a/src/main/target/MATEKF411SE/config.c b/src/main/target/MATEKF411SE/config.c index e5fcb7a1379..07f6de46971 100755 --- a/src/main/target/MATEKF411SE/config.c +++ b/src/main/target/MATEKF411SE/config.c @@ -17,9 +17,12 @@ #include #include "platform.h" + +#include "fc/fc_msp_box.h" + #include "io/piniobox.h" void targetConfiguration(void) { - pinioBoxConfigMutable()->permanentId[0] = 47; + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; } diff --git a/src/main/target/MATEKF722PX/config.c b/src/main/target/MATEKF722PX/config.c index 34cd163fe84..cd7d7d0e4a9 100755 --- a/src/main/target/MATEKF722PX/config.c +++ b/src/main/target/MATEKF722PX/config.c @@ -17,16 +17,20 @@ #include #include "platform.h" -#include "io/piniobox.h" + #include "config/config_master.h" #include "config/feature.h" + +#include "fc/fc_msp_box.h" + +#include "io/piniobox.h" #include "io/serial.h" #include "io/frsky_osd.h" void targetConfiguration(void) { - pinioBoxConfigMutable()->permanentId[0] = 47; - pinioBoxConfigMutable()->permanentId[1] = 48; + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; serialConfigMutable()->portConfigs[6].functionMask = FUNCTION_FRSKY_OSD; } diff --git a/src/main/target/MATEKF722SE/config.c b/src/main/target/MATEKF722SE/config.c index c7d6689cddd..7e47e5bf6b7 100644 --- a/src/main/target/MATEKF722SE/config.c +++ b/src/main/target/MATEKF722SE/config.c @@ -16,11 +16,15 @@ */ #include + #include "platform.h" + +#include "fc/fc_msp_box.h" + #include "io/piniobox.h" void targetConfiguration(void) { - pinioBoxConfigMutable()->permanentId[0] = 47; - pinioBoxConfigMutable()->permanentId[1] = 48; + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; } diff --git a/src/main/target/MATEKF765/config.c b/src/main/target/MATEKF765/config.c index c7d6689cddd..7e47e5bf6b7 100644 --- a/src/main/target/MATEKF765/config.c +++ b/src/main/target/MATEKF765/config.c @@ -16,11 +16,15 @@ */ #include + #include "platform.h" + +#include "fc/fc_msp_box.h" + #include "io/piniobox.h" void targetConfiguration(void) { - pinioBoxConfigMutable()->permanentId[0] = 47; - pinioBoxConfigMutable()->permanentId[1] = 48; + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; + pinioBoxConfigMutable()->permanentId[1] = BOX_PERMANENT_ID_USER2; } From ae842aaeceabd3a73d421ade5d81c68848d1e0b7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Tue, 28 Jul 2020 17:43:52 +0100 Subject: [PATCH 102/248] [SPEEDYBEEF7] Fix target compilation --- src/main/target/SPEEDYBEEF7/target.h | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/src/main/target/SPEEDYBEEF7/target.h b/src/main/target/SPEEDYBEEF7/target.h index 2a743133fd6..ea338680ee4 100644 --- a/src/main/target/SPEEDYBEEF7/target.h +++ b/src/main/target/SPEEDYBEEF7/target.h @@ -54,13 +54,11 @@ #define USE_SPI #define USE_SPI_DEVICE_1 -#define USE_ACC -#define USE_GYRO #define USE_MPU_DATA_READY_SIGNAL #define USE_EXTI -#define USE_ACC_ICM20689 -#define USE_GYRO_ICM20689 +#define USE_IMU_ICM20689 +#define IMU_ICM20689_ALIGN CW180_DEG #define GYRO_INT_EXTI PC4 #define ICM20689_CS_PIN PA4 From b6f26ffc76744fca0b2852807e9feab9c38c3a01 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Tue, 28 Jul 2020 21:56:48 +0100 Subject: [PATCH 103/248] [PINIO] Add support to targets to define PINIO pin flags This way a target can declare a PINIO pin as inverted --- src/main/drivers/pinio.c | 20 ++++++++++++++++---- 1 file changed, 16 insertions(+), 4 deletions(-) diff --git a/src/main/drivers/pinio.c b/src/main/drivers/pinio.c index c093b78d828..9eb88c37820 100644 --- a/src/main/drivers/pinio.c +++ b/src/main/drivers/pinio.c @@ -32,19 +32,31 @@ /*** Hardware definitions ***/ const pinioHardware_t pinioHardware[] = { #if defined(PINIO1_PIN) - { .ioTag = IO_TAG(PINIO1_PIN), .ioMode = IOCFG_OUT_PP, .flags = 0 }, +#if !defined(PINIO1_FLAGS) +#define PINIO1_FLAGS 0 +#endif + { .ioTag = IO_TAG(PINIO1_PIN), .ioMode = IOCFG_OUT_PP, .flags = PINIO1_FLAGS }, #endif #if defined(PINIO2_PIN) - { .ioTag = IO_TAG(PINIO2_PIN), .ioMode = IOCFG_OUT_PP, .flags = 0 }, +#if !defined(PINIO2_FLAGS) +#define PINIO2_FLAGS 0 +#endif + { .ioTag = IO_TAG(PINIO2_PIN), .ioMode = IOCFG_OUT_PP, .flags = PINIO2_FLAGS }, #endif #if defined(PINIO3_PIN) - { .ioTag = IO_TAG(PINIO3_PIN), .ioMode = IOCFG_OUT_PP, .flags = 0 }, +#if !defined(PINIO3_FLAGS) +#define PINIO3_FLAGS 0 +#endif + { .ioTag = IO_TAG(PINIO3_PIN), .ioMode = IOCFG_OUT_PP, .flags = PINIO3_FLAGS }, #endif #if defined(PINIO4_PIN) - { .ioTag = IO_TAG(PINIO4_PIN), .ioMode = IOCFG_OUT_PP, .flags = 0 }, +#if !defined(PINIO4_FLAGS) +#define PINIO4_FLAGS 0 +#endif + { .ioTag = IO_TAG(PINIO4_PIN), .ioMode = IOCFG_OUT_PP, .flags = PINIO4_FLAGS }, #endif }; From 4b148920b994c797eed6f77af9470c58a31bf37e Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Thu, 30 Jul 2020 10:09:06 +0200 Subject: [PATCH 104/248] [NAV] Fallback to RTH in case of WP activation with no mission loaded; Fix the bug when RTH will terminate if GPS is briefly lost even if FSM logic accounts for that --- src/main/navigation/navigation.c | 35 ++++++++++++++++++++++++++------ 1 file changed, 29 insertions(+), 6 deletions(-) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 63b5f35f954..94789ba95de 100755 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -3097,6 +3097,11 @@ static bool canActivateNavigationModes(void) return (posControl.flags.estPosStatus == EST_TRUSTED) && (posControl.flags.estVelStatus == EST_TRUSTED) && (posControl.flags.estHeadingStatus >= EST_USABLE); } +static bool isWaypointMissionValid(void) +{ + return posControl.waypointListValid && (posControl.waypointCount > 0); +} + static navigationFSMEvent_t selectNavEventFromBoxModeInput(void) { static bool canActivateWaypoint = false; @@ -3110,9 +3115,16 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void) } // Flags if we can activate certain nav modes (check if we have required sensors and they provide valid data) - bool canActivateAltHold = canActivateAltHoldMode(); - bool canActivatePosHold = canActivatePosHoldMode(); - bool canActivateNavigation = canActivateNavigationModes(); + const bool canActivateAltHold = canActivateAltHoldMode(); + const bool canActivatePosHold = canActivatePosHoldMode(); + const bool canActivateNavigation = canActivateNavigationModes(); + const bool isExecutingRTH = navGetStateFlags(posControl.navState) & NAV_AUTO_RTH; + + // Keep canActivateWaypoint flag at FALSE if there is no mission loaded + // Also block WP mission if we are executing RTH + if (!isWaypointMissionValid() || isExecutingRTH) { + canActivateWaypoint = false; + } // LAUNCH mode has priority over any other NAV mode if (STATE(FIXED_WING_LEGACY)) { @@ -3139,21 +3151,32 @@ static navigationFSMEvent_t selectNavEventFromBoxModeInput(void) } // RTH/Failsafe_RTH can override MANUAL - if (posControl.flags.forcedRTHActivated || (IS_RC_MODE_ACTIVE(BOXNAVRTH) && canActivatePosHold && canActivateNavigation && canActivateAltHold && STATE(GPS_FIX_HOME))) { + if (posControl.flags.forcedRTHActivated) { // If we request forced RTH - attempt to activate it no matter what // This might switch to emergency landing controller if GPS is unavailable - canActivateWaypoint = false; // Block WP mode if we switched to RTH for whatever reason return NAV_FSM_EVENT_SWITCH_TO_RTH; } + // Pilot-triggered RTH, also fall-back for WP if there is no mission loaded + if (IS_RC_MODE_ACTIVE(BOXNAVRTH) || (IS_RC_MODE_ACTIVE(BOXNAVWP) && !canActivateWaypoint)) { + // Check for isExecutingRTH to prevent switching our from RTH in case of a brief GPS loss + // If don't keep this, loss of any of the canActivatePosHold && canActivateNavigation && canActivateAltHold + // will kick us out of RTH state machine via NAV_FSM_EVENT_SWITCH_TO_IDLE and will prevent any of the fall-back + // logic to kick in (waiting for GPS on airplanes, switch to emergency landing etc) + if (isExecutingRTH || (canActivatePosHold && canActivateNavigation && canActivateAltHold && STATE(GPS_FIX_HOME))) { + return NAV_FSM_EVENT_SWITCH_TO_RTH; + } + } + // MANUAL mode has priority over WP/PH/AH if (IS_RC_MODE_ACTIVE(BOXMANUAL)) { canActivateWaypoint = false; // Block WP mode if we are in PASSTHROUGH mode return NAV_FSM_EVENT_SWITCH_TO_IDLE; } + // Pilot-activated waypoint mission. Fall-back to RTH in case of no mission loaded if (IS_RC_MODE_ACTIVE(BOXNAVWP)) { - if ((FLIGHT_MODE(NAV_WP_MODE)) || (canActivateNavigation && canActivateWaypoint && canActivatePosHold && canActivateAltHold && STATE(GPS_FIX_HOME) && ARMING_FLAG(ARMED) && posControl.waypointListValid && (posControl.waypointCount > 0))) + if (FLIGHT_MODE(NAV_WP_MODE) || (canActivateWaypoint && canActivatePosHold && canActivateNavigation && canActivateAltHold && STATE(GPS_FIX_HOME))) return NAV_FSM_EVENT_SWITCH_TO_WAYPOINT; } else { From e4752db5badc31cb8b7dfab464c138219a63b675 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 30 Jul 2020 11:06:26 +0200 Subject: [PATCH 105/248] Move Kalman setting to PID profile --- src/main/fc/settings.yaml | 46 +++++++++++++++++++++++---------------- src/main/flight/kalman.c | 16 +++++++------- src/main/flight/kalman.h | 2 +- src/main/flight/pid.c | 12 ++++++---- src/main/flight/pid.h | 4 ++++ src/main/sensors/gyro.c | 6 +---- src/main/sensors/gyro.h | 4 ---- 7 files changed, 49 insertions(+), 41 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 94b7cdb7501..f49b8774fcf 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -229,25 +229,6 @@ groups: condition: USE_DYNAMIC_FILTERS min: 30 max: 1000 - - name: gyro_kalman_enabled - condition: USE_GYRO_KALMAN - field: kalmanEnabled - type: bool - - name: gyro_kalman_q - field: kalman_q - condition: USE_GYRO_KALMAN - min: 1 - max: 16000 - - name: gyro_kalman_w - field: kalman_w - condition: USE_GYRO_KALMAN - min: 1 - max: 40 - - name: gyro_kalman_sharpness - field: kalman_sharpness - condition: USE_GYRO_KALMAN - min: 1 - max: 16000 - name: gyro_to_use condition: USE_DUAL_GYRO min: 0 @@ -1802,6 +1783,33 @@ groups: field: controlDerivativeLpfHz min: 0 max: 200 + - name: setpoint_kalman_enabled + description: "Enable Kalman filter on the PID controller setpoint" + default_value: "OFF" + condition: USE_GYRO_KALMAN + field: kalmanEnabled + type: bool + - name: setpoint_kalman_q + description: "Quality factor of the setpoint Kalman filter. Higher values means less filtering and lower phase delay. On 3-7 inch multirotors can be usually increased to 200-300 or even higher of clean builds" + default_value: "100" + field: kalman_q + condition: USE_GYRO_KALMAN + min: 1 + max: 16000 + - name: setpoint_kalman_w + description: "Window size for the setpoint Kalman filter. Wider the window, more samples are used to compute variance. In general, wider window results in smoother filter response" + default_value: "4" + field: kalman_w + condition: USE_GYRO_KALMAN + min: 1 + max: 40 + - name: setpoint_kalman_sharpness + description: "Dynamic factor for the setpoint Kalman filter. In general, the higher the value, the more dynamic Kalman filter gets" + default_value: "100" + field: kalman_sharpness + condition: USE_GYRO_KALMAN + min: 1 + max: 16000 - name: PG_PID_AUTOTUNE_CONFIG type: pidAutotuneConfig_t diff --git a/src/main/flight/kalman.c b/src/main/flight/kalman.c index 70855b46b8f..99b0a00b2b9 100755 --- a/src/main/flight/kalman.c +++ b/src/main/flight/kalman.c @@ -30,23 +30,23 @@ FILE_COMPILE_FOR_SPEED kalman_t kalmanFilterStateRate[XYZ_AXIS_COUNT]; -static void gyroKalmanInitAxis(kalman_t *filter) +static void gyroKalmanInitAxis(kalman_t *filter, uint16_t q, uint16_t w, uint16_t sharpness) { memset(filter, 0, sizeof(kalman_t)); - filter->q = gyroConfig()->kalman_q * 0.03f; //add multiplier to make tuning easier + filter->q = q * 0.03f; //add multiplier to make tuning easier filter->r = 88.0f; //seeding R at 88.0f filter->p = 30.0f; //seeding P at 30.0f filter->e = 1.0f; - filter->s = gyroConfig()->kalman_sharpness / 10.0f; - filter->w = gyroConfig()->kalman_w * 8; + filter->s = sharpness / 10.0f; + filter->w = w * 8; filter->inverseN = 1.0f / (float)(filter->w); } -void gyroKalmanInitialize(void) +void gyroKalmanInitialize(uint16_t q, uint16_t w, uint16_t sharpness) { - gyroKalmanInitAxis(&kalmanFilterStateRate[X]); - gyroKalmanInitAxis(&kalmanFilterStateRate[Y]); - gyroKalmanInitAxis(&kalmanFilterStateRate[Z]); + gyroKalmanInitAxis(&kalmanFilterStateRate[X], q, w, sharpness); + gyroKalmanInitAxis(&kalmanFilterStateRate[Y], q, w, sharpness); + gyroKalmanInitAxis(&kalmanFilterStateRate[Z], q, w, sharpness); } float kalman_process(kalman_t *kalmanState, float input, float target) diff --git a/src/main/flight/kalman.h b/src/main/flight/kalman.h index 0a27ca2514c..17b714b8ffe 100755 --- a/src/main/flight/kalman.h +++ b/src/main/flight/kalman.h @@ -49,5 +49,5 @@ typedef struct kalman uint16_t w; } kalman_t; -void gyroKalmanInitialize(void); +void gyroKalmanInitialize(uint16_t q, uint16_t w, uint16_t sharpness); float gyroKalmanUpdate(uint8_t axis, float input, float setpoint); diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 8c0486c6a5e..a3a638b50bd 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -155,7 +155,7 @@ static EXTENDED_FASTRAM filterApplyFnPtr dTermLpfFilterApplyFn; static EXTENDED_FASTRAM filterApplyFnPtr dTermLpf2FilterApplyFn; static EXTENDED_FASTRAM bool levelingEnabled = false; -PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 13); +PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 14); PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .bank_mc = { @@ -276,6 +276,10 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .pidControllerType = PID_TYPE_AUTO, .navFwPosHdgPidsumLimit = PID_SUM_LIMIT_YAW_DEFAULT, .controlDerivativeLpfHz = 30, + .kalman_q = 100, + .kalman_w = 4, + .kalman_sharpness = 100, + .kalmanEnabled = 0, ); bool pidInitFilters(void) @@ -976,7 +980,7 @@ void FAST_CODE pidController(float dT) pidState[axis].rateTarget = constrainf(rateTarget, -GYRO_SATURATION_LIMIT, +GYRO_SATURATION_LIMIT); #ifdef USE_GYRO_KALMAN - if (gyroConfig()->kalmanEnabled) { + if (pidProfile()->kalmanEnabled) { pidState[axis].gyroRate = gyroKalmanUpdate(axis, pidState[axis].gyroRate, pidState[axis].rateTarget); } #endif @@ -1113,8 +1117,8 @@ void pidInit(void) pidResetTPAFilter(); #ifdef USE_GYRO_KALMAN - if (gyroConfig()->kalmanEnabled) { - gyroKalmanInitialize(); + if (pidProfile()->kalmanEnabled) { + gyroKalmanInitialize(pidProfile()->kalman_q, pidProfile()->kalman_w, pidProfile()->kalman_sharpness); } #endif } diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index c6862661509..d105f67ae2f 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -151,6 +151,10 @@ typedef struct pidProfile_s { uint16_t navFwPosHdgPidsumLimit; uint8_t controlDerivativeLpfHz; + uint16_t kalman_q; + uint16_t kalman_w; + uint16_t kalman_sharpness; + uint8_t kalmanEnabled; } pidProfile_t; typedef struct pidAutotuneConfig_s { diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 7db921eb73a..d9cd15891d9 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -101,7 +101,7 @@ EXTENDED_FASTRAM dynamicGyroNotchState_t dynamicGyroNotchState; #endif -PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 9); +PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 10); PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .gyro_lpf = GYRO_LPF_42HZ, // 42HZ value is defined for Invensense/TDK gyros @@ -120,10 +120,6 @@ PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .dynamicGyroNotchQ = 120, .dynamicGyroNotchMinHz = 150, .dynamicGyroNotchEnabled = 0, - .kalman_q = 100, - .kalman_w = 4, - .kalman_sharpness = 100, - .kalmanEnabled = 0, ); STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev, gyroSensor_e gyroHardware) diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 39e04c84800..b709294b553 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -74,10 +74,6 @@ typedef struct gyroConfig_s { uint16_t dynamicGyroNotchQ; uint16_t dynamicGyroNotchMinHz; uint8_t dynamicGyroNotchEnabled; - uint16_t kalman_q; - uint16_t kalman_w; - uint16_t kalman_sharpness; - uint8_t kalmanEnabled; } gyroConfig_t; PG_DECLARE(gyroConfig_t, gyroConfig); From 03a014d0e1684d6ae44ca8f06aca5081ed78ffed Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 31 Jul 2020 10:30:16 +0200 Subject: [PATCH 106/248] Bump the number of logic conditions to 32 --- src/main/programming/logic_condition.c | 2 +- src/main/programming/logic_condition.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index 4d3181e1153..4184a87ebbc 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -49,7 +49,7 @@ #include "io/vtx.h" #include "drivers/vtx_common.h" -PG_REGISTER_ARRAY_WITH_RESET_FN(logicCondition_t, MAX_LOGIC_CONDITIONS, logicConditions, PG_LOGIC_CONDITIONS, 1); +PG_REGISTER_ARRAY_WITH_RESET_FN(logicCondition_t, MAX_LOGIC_CONDITIONS, logicConditions, PG_LOGIC_CONDITIONS, 2); EXTENDED_FASTRAM uint64_t logicConditionsGlobalFlags; EXTENDED_FASTRAM int logicConditionValuesByType[LOGIC_CONDITION_LAST]; diff --git a/src/main/programming/logic_condition.h b/src/main/programming/logic_condition.h index 5f1b6937105..fa13d964fd7 100644 --- a/src/main/programming/logic_condition.h +++ b/src/main/programming/logic_condition.h @@ -26,7 +26,7 @@ #include "config/parameter_group.h" #include "common/time.h" -#define MAX_LOGIC_CONDITIONS 16 +#define MAX_LOGIC_CONDITIONS 32 typedef enum { LOGIC_CONDITION_TRUE = 0, From 101e98aaeb657eea06a5e7cf85d00c9d05f3b038 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 31 Jul 2020 11:48:14 +0200 Subject: [PATCH 107/248] MSP2_BLACKBOX_CONFIG --- src/main/flight/servos.c | 4 ++++ src/main/flight/servos.h | 4 ++++ src/main/programming/global_variables.h | 2 +- 3 files changed, 9 insertions(+), 1 deletion(-) diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index dbd910e2733..f70b0d5327a 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -271,6 +271,10 @@ void servoMixer(float dT) input[INPUT_GVAR_1] = constrain(gvGet(1), -1000, 1000); input[INPUT_GVAR_2] = constrain(gvGet(2), -1000, 1000); input[INPUT_GVAR_3] = constrain(gvGet(3), -1000, 1000); + input[INPUT_GVAR_4] = constrain(gvGet(4), -1000, 1000); + input[INPUT_GVAR_5] = constrain(gvGet(5), -1000, 1000); + input[INPUT_GVAR_6] = constrain(gvGet(6), -1000, 1000); + input[INPUT_GVAR_7] = constrain(gvGet(7), -1000, 1000); #endif if (IS_RC_MODE_ACTIVE(BOXCAMSTAB)) { diff --git a/src/main/flight/servos.h b/src/main/flight/servos.h index 14df882289b..3b536ad3d6c 100644 --- a/src/main/flight/servos.h +++ b/src/main/flight/servos.h @@ -58,6 +58,10 @@ typedef enum { INPUT_GVAR_1 = 31, INPUT_GVAR_2 = 32, INPUT_GVAR_3 = 33, + INPUT_GVAR_4 = 34, + INPUT_GVAR_5 = 35, + INPUT_GVAR_6 = 36, + INPUT_GVAR_7 = 37, INPUT_SOURCE_COUNT } inputSource_e; diff --git a/src/main/programming/global_variables.h b/src/main/programming/global_variables.h index cbeb500348b..99db0aebad9 100644 --- a/src/main/programming/global_variables.h +++ b/src/main/programming/global_variables.h @@ -26,7 +26,7 @@ #include "config/parameter_group.h" -#define MAX_GLOBAL_VARIABLES 4 +#define MAX_GLOBAL_VARIABLES 8 typedef struct globalVariableConfig_s { int32_t min; From 316b39147d72f157bf73fa919f6767ce58387bba Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 31 Jul 2020 11:50:23 +0200 Subject: [PATCH 108/248] Bump PG version --- src/main/programming/global_variables.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/programming/global_variables.c b/src/main/programming/global_variables.c index df2faace763..d3294a723dc 100644 --- a/src/main/programming/global_variables.c +++ b/src/main/programming/global_variables.c @@ -38,7 +38,7 @@ FILE_COMPILE_FOR_SIZE static EXTENDED_FASTRAM int32_t globalVariableState[MAX_GLOBAL_VARIABLES]; -PG_REGISTER_ARRAY_WITH_RESET_FN(globalVariableConfig_t, MAX_GLOBAL_VARIABLES, globalVariableConfigs, PG_GLOBAL_VARIABLE_CONFIG, 0); +PG_REGISTER_ARRAY_WITH_RESET_FN(globalVariableConfig_t, MAX_GLOBAL_VARIABLES, globalVariableConfigs, PG_GLOBAL_VARIABLE_CONFIG, 1); void pgResetFn_globalVariableConfigs(globalVariableConfig_t *globalVariableConfigs) { From f3da1c210daf8e4cb8966b7af1957dec57bfe2ce Mon Sep 17 00:00:00 2001 From: tonyyng Date: Fri, 31 Jul 2020 10:05:21 -0400 Subject: [PATCH 109/248] Add safehomes (#5995) * Merge Safehome feature from development repo * Remove set nav_rth_home_offset_* to avoid confusion --- docs/Safehomes.md | 70 +++++++++++++++++++++++++++ src/main/config/parameter_group_ids.h | 3 +- src/main/fc/cli.c | 68 ++++++++++++++++++++++++++ src/main/fc/settings.yaml | 10 ---- src/main/io/osd.c | 17 ++++++- src/main/navigation/navigation.c | 66 ++++++++++++++++++++----- src/main/navigation/navigation.h | 22 ++++++++- src/main/target/common.h | 1 + 8 files changed, 232 insertions(+), 25 deletions(-) create mode 100644 docs/Safehomes.md diff --git a/docs/Safehomes.md b/docs/Safehomes.md new file mode 100644 index 00000000000..58c2cd76560 --- /dev/null +++ b/docs/Safehomes.md @@ -0,0 +1,70 @@ +# INav - Safehomes + +## Introduction + +The "Home" position is used for the landing point when landing is enabled or in an emergency situation. It is usually determined by the GPS location where the aircraft is armed. + +For airplanes, the landing procedure is explained very well by Pawel Spychalski [here.](https://quadmeup.com/inav-1-8-automated-landing-for-fixed-wings/) + + + +One potential risk when landing is that there might be buildings, trees and other obstacles in the way as the airplance circles lower toward the ground at the arming point. Most people don't go the middle of the field when arming their airplanes. + +## Safehome + +Safehomes are a list of GPS coordinates that identify safe landing points. When the flight controller is armed, it checks the list of safehomes. The first one that is enabled and within 200m of the current position will be selected. Otherwise, it reverts to the old behaviour of using your current GPS position as home. + +You can define up to 8 safehomes for different locations you fly at. + +When you are choosing safehome locations, ensure that the location is clear of obstructions for a radius more than 50m (`nav_fw_loiter_radius`). As the plane descends, the circles aren't always symmetrical, as wind direction could result in some wider or tighter turns. Also, the direction and length of the final landing stage is also unknown. You want to choose a point that has provides a margin for variation and the final landing. + +## OSD Message when Armed + +When the aircraft is armed, the OSD briefly shows `ARMED` and the current GPS position and current date and time. + +If a safehome is selected, an additional message appears: +``` + H - DIST -> SAFEHOME n <- New message + n is the Safehome index (0-7) + ARMED DIST is the distance from + GPS LATITUDE your current position to this safehome + GPS LONGITUDE + GPS PLUS CODE + + CURRENT DATE + CURRENT TIME +``` +The GPS details are those of the selected safehome. +To draw your attention to "HOME" being replaced, the message flashes and stays visible longer. + +## CLI command `safehome` to manage safehomes + +`safehome` - List all safehomes + +`safehome reset` - Clears all safehomes. + +`safehome ` - Set the parameters of a safehome with index ``. + +Parameters: + + * `` - 0 is disabled, 1 is enabled. + * `` - Latitude (WGS84), in degrees * 1E7 (for example 123456789 means 12.3456789). + * `` - Longitude. + +Safehomes are saved along with your regular settings and will appear in `diff` and `dump` output. Use `save` to save any changes, as with other settings. + +### `safehome` example + +``` +# safehome +safehome 0 1 543533193 -45179273 +safehome 1 1 435464846 -78654544 +safehome 2 0 0 0 +safehome 3 0 0 0 +safehome 4 0 0 0 +safehome 5 0 0 0 +safehome 6 0 0 0 +safehome 7 0 0 0 + +``` + diff --git a/src/main/config/parameter_group_ids.h b/src/main/config/parameter_group_ids.h index 078352ce746..67d86a1b9e6 100644 --- a/src/main/config/parameter_group_ids.h +++ b/src/main/config/parameter_group_ids.h @@ -113,7 +113,8 @@ #define PG_GLOBAL_VARIABLE_CONFIG 1023 #define PG_SMARTPORT_MASTER_CONFIG 1024 #define PG_OSD_LAYOUTS_CONFIG 1025 -#define PG_INAV_END 1025 +#define PG_SAFE_HOME_CONFIG 1026 +#define PG_INAV_END 1026 // OSD configuration (subject to change) //#define PG_OSD_FONT_CONFIG 2047 diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 7693a0856e4..cdeac26521d 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -1276,6 +1276,67 @@ static void cliTempSensor(char *cmdline) } #endif +#if defined(USE_SAFE_HOME) +static void printSafeHomes(uint8_t dumpMask, const navSafeHome_t *navSafeHome, const navSafeHome_t *defaultSafeHome) +{ + const char *format = "safehome %u %u %d %d"; // uint8_t enabled, int32_t lat; int32_t lon + for (uint8_t i = 0; i < MAX_SAFE_HOMES; i++) { + bool equalsDefault = false; + if (defaultSafeHome) { + equalsDefault = navSafeHome[i].enabled == defaultSafeHome[i].enabled + && navSafeHome[i].lat == defaultSafeHome[i].lat + && navSafeHome[i].lon == defaultSafeHome[i].lon; + cliDefaultPrintLinef(dumpMask, equalsDefault, format, i, + defaultSafeHome[i].enabled, defaultSafeHome[i].lat, defaultSafeHome[i].lon); + } + cliDumpPrintLinef(dumpMask, equalsDefault, format, i, + navSafeHome[i].enabled, navSafeHome[i].lat, navSafeHome[i].lon); + } +} + +static void cliSafeHomes(char *cmdline) +{ + if (isEmpty(cmdline)) { + printSafeHomes(DUMP_MASTER, safeHomeConfig(0), NULL); + } else if (sl_strcasecmp(cmdline, "reset") == 0) { + resetSafeHomes(); + } else { + int32_t lat, lon; + bool enabled; + uint8_t validArgumentCount = 0; + const char *ptr = cmdline; + int8_t i = fastA2I(ptr); + if (i < 0 || i >= MAX_SAFE_HOMES) { + cliShowArgumentRangeError("safehome index", 0, MAX_SAFE_HOMES - 1); + } else { + if ((ptr = nextArg(ptr))) { + enabled = fastA2I(ptr); + validArgumentCount++; + } + if ((ptr = nextArg(ptr))) { + lat = fastA2I(ptr); + validArgumentCount++; + } + if ((ptr = nextArg(ptr))) { + lon = fastA2I(ptr); + validArgumentCount++; + } + if ((ptr = nextArg(ptr))) { + // check for too many arguments + validArgumentCount++; + } + if (validArgumentCount != 3) { + cliShowParseError(); + } else { + safeHomeConfigMutable(i)->enabled = enabled; + safeHomeConfigMutable(i)->lat = lat; + safeHomeConfigMutable(i)->lon = lon; + } + } + } +} + +#endif #if defined(USE_NAV) && defined(NAV_NON_VOLATILE_WAYPOINT_STORAGE) && defined(NAV_NON_VOLATILE_WAYPOINT_CLI) static void printWaypoints(uint8_t dumpMask, const navWaypoint_t *navWaypoint, const navWaypoint_t *defaultNavWaypoint) { @@ -3214,6 +3275,10 @@ static void printConfig(const char *cmdline, bool doDiff) cliPrintHashLine("servo"); printServo(dumpMask, servoParams_CopyArray, servoParams(0)); +#if defined(USE_SAFE_HOME) + cliPrintHashLine("safehome"); + printSafeHomes(dumpMask, safeHomeConfig_CopyArray, safeHomeConfig(0)); +#endif #ifdef USE_PROGRAMMING_FRAMEWORK cliPrintHashLine("logic"); printLogic(dumpMask, logicConditions_CopyArray, logicConditions(0)); @@ -3454,6 +3519,9 @@ const clicmd_t cmdTable[] = { CLI_COMMAND_DEF("resource", "view currently used resources", NULL, cliResource), #endif CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange), +#if defined(USE_SAFE_HOME) + CLI_COMMAND_DEF("safehome", "safe home list", NULL, cliSafeHomes), +#endif CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave), CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial), #ifdef USE_SERIAL_PASSTHROUGH diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index f49b8774fcf..92a5a9a720a 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2115,16 +2115,6 @@ groups: default_value: "0" field: general.rth_home_altitude max: 65000 - - name: nav_rth_home_offset_distance - description: "Distance offset from GPS established home to \"safe\" position used for RTH (cm, 0 disables)" - default_value: "0" - field: general.rth_home_offset_distance - max: 65000 - - name: nav_rth_home_offset_direction - description: "Direction offset from GPS established home to \"safe\" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance)" - default_value: "0" - field: general.rth_home_offset_direction - max: 359 - name: nav_mc_bank_angle description: "Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude" default_value: "30" diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 66a1a9f2a3a..29bdaedd902 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -3003,6 +3003,16 @@ static void osdShowArmed(void) olc_encode(GPS_home.lat, GPS_home.lon, digits, buf, sizeof(buf)); displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y + 2, buf); y += 4; +#if defined (USE_SAFE_HOME) + if (isSafeHomeInUse()) { + textAttributes_t elemAttr = _TEXT_ATTRIBUTES_BLINK_BIT; + char buf2[12]; // format the distance first + osdFormatDistanceStr(buf2, safehome_distance); + tfp_sprintf(buf, "%c - %s -> SAFEHOME %u", SYM_HOME, buf2, safehome_used); + // write this message above the ARMED message to make it obvious + displayWriteWithAttr(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y - 8, buf, elemAttr); + } +#endif } else { strcpy(buf, "!NO HOME POSITION!"); displayWrite(osdDisplayPort, (osdDisplayPort->cols - strlen(buf)) / 2, y, buf); @@ -3062,7 +3072,12 @@ static void osdRefresh(timeUs_t currentTimeUs) if (ARMING_FLAG(ARMED)) { osdResetStats(); osdShowArmed(); // reset statistic etc - osdSetNextRefreshIn(ARMED_SCREEN_DISPLAY_TIME); + uint32_t delay = ARMED_SCREEN_DISPLAY_TIME; +#if defined(USE_SAFE_HOME) + if (isSafeHomeInUse()) + delay *= 3; +#endif + osdSetNextRefreshIn(delay); } else { osdShowStats(); // show statistic osdSetNextRefreshIn(STATS_SCREEN_DISPLAY_TIME); diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 94789ba95de..c16aa048ebb 100755 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -18,7 +18,7 @@ #include #include #include - +#include #include "platform.h" @@ -74,6 +74,13 @@ uint32_t GPS_distanceToHome; // distance to home point in meters int16_t GPS_directionToHome; // direction to home point in degrees radar_pois_t radar_pois[RADAR_MAX_POIS]; +#if defined(USE_SAFE_HOME) +int8_t safehome_used; // -1 if no safehome, 0 to MAX_SAFEHOMES -1 otherwise +uint32_t safehome_distance; // distance to the selected safehome + +PG_REGISTER_ARRAY(navSafeHome_t, MAX_SAFE_HOMES, safeHomeConfig, PG_SAFE_HOME_CONFIG , 0); + +#endif #if defined(USE_NAV) #if defined(NAV_NON_VOLATILE_WAYPOINT_STORAGE) @@ -115,8 +122,6 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, .rth_home_altitude = 0, // altitude in centimeters .rth_abort_threshold = 50000, // centimeters - 500m should be safe for all aircraft .max_terrain_follow_altitude = 100, // max altitude in centimeters in terrain following mode - .rth_home_offset_distance = 0, // Distance offset from GPS established home to "safe" position used for RTH (cm, 0 disables) - .rth_home_offset_direction = 0, // Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) }, // MC-specific @@ -2403,6 +2408,42 @@ static navigationHomeFlags_t navigationActualStateHomeValidity(void) return flags; } +#if defined(USE_SAFE_HOME) + +/******************************************************* + * Is a safehome being used instead of the arming point? + *******************************************************/ +bool isSafeHomeInUse(void) +{ + return (safehome_used > -1 && safehome_used < MAX_SAFE_HOMES); +} + +/*********************************************************** + * See if there are any safehomes near where we are arming. + * If so, use it instead of the arming point for home. + **********************************************************/ +bool foundNearbySafeHome(void) +{ + safehome_used = -1; + fpVector3_t safeHome; + gpsLocation_t shLLH; + shLLH.alt = 0; + for (uint8_t i = 0; i < MAX_SAFE_HOMES; i++) { + shLLH.lat = safeHomeConfig(i)->lat; + shLLH.lon = safeHomeConfig(i)->lon; + geoConvertGeodeticToLocal(&safeHome, &posControl.gpsOrigin, &shLLH, GEO_ALT_RELATIVE); + safehome_distance = calculateDistanceToDestination(&safeHome); + if (safehome_distance < 20000) { // 200 m + safehome_used = i; + setHomePosition(&safeHome, 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING, navigationActualStateHomeValidity()); + return true; + } + } + safehome_distance = 0; + return false; +} +#endif + /*----------------------------------------------------------- * Update home position, calculate distance and bearing to home *-----------------------------------------------------------*/ @@ -2424,15 +2465,10 @@ void updateHomePosition(void) break; } if (setHome) { - if (navConfig()->general.rth_home_offset_distance != 0) { // apply user defined offset - fpVector3_t offsetHome; - offsetHome.x = posControl.actualState.abs.pos.x + navConfig()->general.rth_home_offset_distance * cos_approx(DEGREES_TO_RADIANS(navConfig()->general.rth_home_offset_direction)); - offsetHome.y = posControl.actualState.abs.pos.y + navConfig()->general.rth_home_offset_distance * sin_approx(DEGREES_TO_RADIANS(navConfig()->general.rth_home_offset_direction)); - offsetHome.z = posControl.actualState.abs.pos.z; - setHomePosition(&offsetHome, 0, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING, navigationActualStateHomeValidity()); - } else { +#if defined(USE_SAFE_HOME) + if (!foundNearbySafeHome()) +#endif setHomePosition(&posControl.actualState.abs.pos, posControl.actualState.yaw, NAV_POS_UPDATE_XY | NAV_POS_UPDATE_Z | NAV_POS_UPDATE_HEADING, navigationActualStateHomeValidity()); - } } } } @@ -2880,6 +2916,14 @@ bool saveNonVolatileWaypointList(void) } #endif +#if defined(USE_SAFE_HOME) + +void resetSafeHomes(void) +{ + memset(safeHomeConfigMutable(0), 0, sizeof(navSafeHome_t) * MAX_SAFE_HOMES); +} +#endif + static void mapWaypointToLocalPosition(fpVector3_t * localPos, const navWaypoint_t * waypoint) { gpsLocation_t wpLLH; diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index cf54897bcaa..1d8b853902f 100755 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -39,6 +39,26 @@ extern bool autoThrottleManuallyIncreased; /* Navigation system updates */ void onNewGPSData(void); +#if defined(USE_SAFE_HOME) + +#define MAX_SAFE_HOMES 8 + +typedef struct { + uint8_t enabled; + int32_t lat; + int32_t lon; +} navSafeHome_t; + +PG_DECLARE_ARRAY(navSafeHome_t, MAX_SAFE_HOMES, safeHomeConfig); + +extern int8_t safehome_used; // -1 if no safehome, 0 to MAX_SAFEHOMES -1 otherwise +extern uint32_t safehome_distance; // distance to the selected safehome + +void resetSafeHomes(void); // remove all safehomes +bool isSafeHomeInUse(void); // Are we using a safehome instead of the arming point? +bool foundNearbySafeHome(void); // Did we find a safehome nearby? + +#endif // defined(USE_SAFE_HOME) #if defined(USE_NAV) #if defined(USE_BLACKBOX) @@ -174,8 +194,6 @@ typedef struct navConfig_s { uint16_t min_rth_distance; // 0 Disables. Minimal distance for RTH in cm, otherwise it will just autoland uint16_t rth_abort_threshold; // Initiate emergency landing if during RTH we get this much [cm] away from home uint16_t max_terrain_follow_altitude; // Max altitude to be used in SURFACE TRACKING mode - uint16_t rth_home_offset_distance; // Distance offset from GPS established home to "safe" position used for RTH (cm, 0 disables) - uint16_t rth_home_offset_direction; // Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) } general; struct { diff --git a/src/main/target/common.h b/src/main/target/common.h index 95d55be5360..08876545592 100755 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -129,6 +129,7 @@ #if (FLASH_SIZE > 128) #define NAV_FIXED_WING_LANDING +#define USE_SAFE_HOME #define USE_AUTOTUNE_FIXED_WING #define USE_LOG #define USE_STATS From 6c5323a941050c9545706bae39eccfad77af53f7 Mon Sep 17 00:00:00 2001 From: giacomo892 Date: Sat, 1 Aug 2020 11:07:23 +0200 Subject: [PATCH 110/248] fix frequency calculation --- src/main/flight/rpm_filter.c | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/src/main/flight/rpm_filter.c b/src/main/flight/rpm_filter.c index e2b2c9849d5..6a9604651e6 100644 --- a/src/main/flight/rpm_filter.c +++ b/src/main/flight/rpm_filter.c @@ -41,7 +41,7 @@ #ifdef USE_RPM_FILTER -#define RPM_TO_HZ 60.0f +#define HZ_TO_RPM 1/60.0f #define RPM_FILTER_RPM_LPF_HZ 150 #define RPM_FILTER_HARMONICS 3 @@ -66,7 +66,6 @@ typedef float (*rpmFilterApplyFnPtr)(rpmFilterBank_t *filter, uint8_t axis, floa typedef void (*rpmFilterUpdateFnPtr)(rpmFilterBank_t *filterBank, uint8_t motor, float baseFrequency); static EXTENDED_FASTRAM pt1Filter_t motorFrequencyFilter[MAX_SUPPORTED_MOTORS]; -static EXTENDED_FASTRAM float erpmToHz; static EXTENDED_FASTRAM rpmFilterBank_t gyroRpmFilters; static EXTENDED_FASTRAM rpmFilterApplyFnPtr rpmGyroApplyFn; static EXTENDED_FASTRAM rpmFilterUpdateFnPtr rpmGyroUpdateFn; @@ -163,7 +162,6 @@ void rpmFiltersInit(void) { pt1FilterInit(&motorFrequencyFilter[i], RPM_FILTER_RPM_LPF_HZ, RPM_FILTER_UPDATE_RATE_US * 1e-6f); } - erpmToHz = ERPM_PER_LSB / (motorConfig()->motorPoleCount / 2) / RPM_TO_HZ; rpmGyroUpdateFn = (rpmFilterUpdateFnPtr)nullRpmFilterUpdate; @@ -190,7 +188,7 @@ void rpmFilterUpdateTask(timeUs_t currentTimeUs) for (uint8_t i = 0; i < motorCount; i++) { const escSensorData_t *escState = getEscTelemetry(i); //Get ESC telemetry - const float baseFrequency = pt1FilterApply(&motorFrequencyFilter[i], escState->rpm * erpmToHz); //Filter motor frequency + const float baseFrequency = pt1FilterApply(&motorFrequencyFilter[i], escState->rpm * HZ_TO_RPM); //Filter motor frequency if (i < 4) { DEBUG_SET(DEBUG_RPM_FREQ, i, (int)baseFrequency); From f812d5c6ac590b04d8fe8aea9fcc113c59266b2d Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 31 Jul 2020 20:46:18 +0200 Subject: [PATCH 111/248] Drop gyro method of ITerm relax --- src/main/build/debug.h | 1 - src/main/common/maths.c | 9 --------- src/main/common/maths.h | 1 - src/main/fc/settings.yaml | 8 +------- src/main/flight/pid.c | 33 +++++++++------------------------ src/main/flight/pid.h | 6 ------ 6 files changed, 10 insertions(+), 48 deletions(-) diff --git a/src/main/build/debug.h b/src/main/build/debug.h index e385bf0bb1f..ec5670f9a48 100644 --- a/src/main/build/debug.h +++ b/src/main/build/debug.h @@ -63,7 +63,6 @@ typedef enum { DEBUG_REM_FLIGHT_TIME, DEBUG_SMARTAUDIO, DEBUG_ACC, - DEBUG_ITERM_RELAX, DEBUG_ERPM, DEBUG_RPM_FILTER, DEBUG_RPM_FREQ, diff --git a/src/main/common/maths.c b/src/main/common/maths.c index cb7904252e4..d3d5a2410db 100644 --- a/src/main/common/maths.c +++ b/src/main/common/maths.c @@ -142,15 +142,6 @@ int32_t applyDeadband(int32_t value, int32_t deadband) return value; } -float fapplyDeadbandf(float value, float deadband) -{ - if (fabsf(value) < deadband) { - return 0; - } - - return value >= 0 ? value - deadband : value + deadband; -} - int constrain(int amt, int low, int high) { if (amt < low) diff --git a/src/main/common/maths.h b/src/main/common/maths.h index 728df5e57ac..a5a375e9f8b 100644 --- a/src/main/common/maths.h +++ b/src/main/common/maths.h @@ -130,7 +130,6 @@ bool sensorCalibrationSolveForScale(sensorCalibrationState_t * state, float resu int gcd(int num, int denom); int32_t applyDeadband(int32_t value, int32_t deadband); -float fapplyDeadbandf(float value, float deadband); int constrain(int amt, int low, int high); float constrainf(float amt, float low, float high); diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 92a5a9a720a..b673ffa204f 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -82,7 +82,7 @@ tables: - name: debug_modes values: ["NONE", "GYRO", "AGL", "FLOW_RAW", "FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE", - "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "ITERM_RELAX", + "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "ERPM", "RPM_FILTER", "RPM_FREQ", "NAV_YAW", "DYNAMIC_FILTER", "DYNAMIC_FILTER_FREQUENCY", "IRLOCK", "CD", "KALMAN_GAIN", "PID_MEASUREMENT", "SPM_CELLS", "SPM_VS600", "SPM_VARIO", "PCF8574"] - name: async_mode @@ -124,9 +124,6 @@ tables: - name: iterm_relax values: ["OFF", "RP", "RPY"] enum: itermRelax_e - - name: iterm_relax_type - values: ["GYRO", "SETPOINT"] - enum: itermRelaxType_e - name: airmodeHandlingType values: ["STICK_CENTER", "THROTTLE_THRESHOLD"] - name: nav_extra_arming_safety @@ -1727,9 +1724,6 @@ groups: field: navFwPosHdgPidsumLimit min: PID_SUM_LIMIT_MIN max: PID_SUM_LIMIT_MAX - - name: mc_iterm_relax_type - field: iterm_relax_type - table: iterm_relax_type - name: mc_iterm_relax field: iterm_relax table: iterm_relax diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index a3a638b50bd..c76b36cfec2 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -124,7 +124,6 @@ int32_t axisPID_P[FLIGHT_DYNAMICS_INDEX_COUNT], axisPID_I[FLIGHT_DYNAMICS_INDEX_ static EXTENDED_FASTRAM pidState_t pidState[FLIGHT_DYNAMICS_INDEX_COUNT]; static EXTENDED_FASTRAM pt1Filter_t windupLpf[XYZ_AXIS_COUNT]; static EXTENDED_FASTRAM uint8_t itermRelax; -static EXTENDED_FASTRAM uint8_t itermRelaxType; #ifdef USE_ANTIGRAVITY static EXTENDED_FASTRAM pt1Filter_t antigravityThrottleLpf; @@ -155,7 +154,7 @@ static EXTENDED_FASTRAM filterApplyFnPtr dTermLpfFilterApplyFn; static EXTENDED_FASTRAM filterApplyFnPtr dTermLpf2FilterApplyFn; static EXTENDED_FASTRAM bool levelingEnabled = false; -PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 14); +PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 15); PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .bank_mc = { @@ -264,7 +263,6 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .navVelXyDtermAttenuation = 90, .navVelXyDtermAttenuationStart = 10, .navVelXyDtermAttenuationEnd = 60, - .iterm_relax_type = ITERM_RELAX_SETPOINT, .iterm_relax_cutoff = MC_ITERM_RELAX_CUTOFF_DEFAULT, .iterm_relax = ITERM_RELAX_RP, .dBoostFactor = 1.25f, @@ -636,31 +634,20 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh #endif } -static void FAST_CODE applyItermRelax(const int axis, const float gyroRate, float currentPidSetpoint, float *itermErrorRate) +static float FAST_CODE applyItermRelax(const int axis, float currentPidSetpoint, float itermErrorRate) { - const float setpointLpf = pt1FilterApply(&windupLpf[axis], currentPidSetpoint); - const float setpointHpf = fabsf(currentPidSetpoint - setpointLpf); - if (itermRelax) { if (axis < FD_YAW || itermRelax == ITERM_RELAX_RPY) { + const float setpointLpf = pt1FilterApply(&windupLpf[axis], currentPidSetpoint); + const float setpointHpf = fabsf(currentPidSetpoint - setpointLpf); + const float itermRelaxFactor = MAX(0, 1 - setpointHpf / MC_ITERM_RELAX_SETPOINT_THRESHOLD); - - if (itermRelaxType == ITERM_RELAX_SETPOINT) { - *itermErrorRate *= itermRelaxFactor; - } else if (itermRelaxType == ITERM_RELAX_GYRO ) { - *itermErrorRate = fapplyDeadbandf(setpointLpf - gyroRate, setpointHpf); - } else { - *itermErrorRate = 0.0f; - } - - if (axis == FD_ROLL) { - DEBUG_SET(DEBUG_ITERM_RELAX, 0, lrintf(setpointHpf)); - DEBUG_SET(DEBUG_ITERM_RELAX, 1, lrintf(itermRelaxFactor * 100.0f)); - DEBUG_SET(DEBUG_ITERM_RELAX, 2, lrintf(*itermErrorRate)); - } + return itermErrorRate * itermRelaxFactor; } } + + return itermErrorRate; } #ifdef USE_D_BOOST static float FAST_CODE applyDBoost(pidState_t *pidState, float dT) { @@ -727,8 +714,7 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid const float newOutput = newPTerm + newDTerm + pidState->errorGyroIf + newCDTerm; const float newOutputLimited = constrainf(newOutput, -pidState->pidSumLimit, +pidState->pidSumLimit); - float itermErrorRate = rateError; - applyItermRelax(axis, pidState->gyroRate, pidState->rateTarget, &itermErrorRate); + float itermErrorRate = applyItermRelax(axis, pidState->rateTarget, rateError); #ifdef USE_ANTIGRAVITY itermErrorRate *= iTermAntigravityGain; @@ -1046,7 +1032,6 @@ void pidInit(void) pidGainsUpdateRequired = false; itermRelax = pidProfile()->iterm_relax; - itermRelaxType = pidProfile()->iterm_relax_type; yawLpfHz = pidProfile()->yaw_lpf_hz; motorItermWindupPoint = 1.0f - (pidProfile()->itermWindupPointPercent / 100.0f); diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index d105f67ae2f..c9849800afd 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -97,11 +97,6 @@ typedef enum { ITERM_RELAX_RPY } itermRelax_e; -typedef enum { - ITERM_RELAX_GYRO = 0, - ITERM_RELAX_SETPOINT -} itermRelaxType_e; - typedef struct pidProfile_s { uint8_t pidControllerType; pidBank_t bank_fw; @@ -138,7 +133,6 @@ typedef struct pidProfile_s { uint8_t navVelXyDtermAttenuation; // VEL_XY dynamic Dterm scale: Dterm will be attenuatedby this value (in percent) when UAV is traveling with more than navVelXyDtermAttenuationStart percents of max velocity uint8_t navVelXyDtermAttenuationStart; // VEL_XY dynamic Dterm scale: Dterm attenuation will begin at this percent of max velocity uint8_t navVelXyDtermAttenuationEnd; // VEL_XY dynamic Dterm scale: Dterm will be fully attenuated at this percent of max velocity - uint8_t iterm_relax_type; // Specifies type of relax algorithm uint8_t iterm_relax_cutoff; // This cutoff frequency specifies a low pass filter which predicts average response of the quad to setpoint uint8_t iterm_relax; // Enable iterm suppression during stick input From d946907af257b68f0daf20cd96c8c559e6d5f94f Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Tue, 4 Aug 2020 12:02:05 +0200 Subject: [PATCH 112/248] Increase MAX_ADJUSTMENT_RANGE_COUNT to 20 (#6018) --- src/main/fc/rc_adjustments.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/rc_adjustments.h b/src/main/fc/rc_adjustments.h index 747f75a2816..c629086c13a 100644 --- a/src/main/fc/rc_adjustments.h +++ b/src/main/fc/rc_adjustments.h @@ -131,7 +131,7 @@ typedef struct adjustmentState_s { #define MAX_SIMULTANEOUS_ADJUSTMENT_COUNT 4 // enough for 4 x 3position switches / 4 aux channel #endif -#define MAX_ADJUSTMENT_RANGE_COUNT 12 // enough for 2 * 6pos switches. +#define MAX_ADJUSTMENT_RANGE_COUNT 20 // enough for 2 * 6pos switches. PG_DECLARE_ARRAY(adjustmentRange_t, MAX_ADJUSTMENT_RANGE_COUNT, adjustmentRanges); From b9c221cc5015c6f5d138c1ff93307c2251a2714e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Tue, 28 Jul 2020 22:35:27 +0100 Subject: [PATCH 113/248] [SPEEDYBEEF7] Add support for disabling BT via PINIO USER1 box will disable BT when it's active. If the user doesn't configure the box, BT will always be enabled. --- src/main/target/SPEEDYBEEF7/config.c | 29 +++++----------------------- src/main/target/SPEEDYBEEF7/target.h | 8 +++++++- 2 files changed, 12 insertions(+), 25 deletions(-) diff --git a/src/main/target/SPEEDYBEEF7/config.c b/src/main/target/SPEEDYBEEF7/config.c index f5bc752e356..a41fee54862 100644 --- a/src/main/target/SPEEDYBEEF7/config.c +++ b/src/main/target/SPEEDYBEEF7/config.c @@ -18,38 +18,19 @@ #include #include -#include +#include "platform.h" -#include "common/axis.h" - -#include "config/config_master.h" -#include "config/feature.h" - -#include "drivers/sensor.h" -#include "drivers/pwm_esc_detect.h" -#include "drivers/pwm_output.h" -#include "drivers/serial.h" - -#include "fc/rc_controls.h" - -#include "flight/failsafe.h" -#include "flight/mixer.h" -#include "flight/pid.h" - -#include "rx/rx.h" +#include "fc/fc_msp_box.h" +#include "io/piniobox.h" #include "io/serial.h" -#include "sensors/battery.h" -#include "sensors/sensors.h" - -#include "telemetry/telemetry.h" - - #define BLUETOOTH_MSP_BAUDRATE BAUD_19200 void targetConfiguration(void) { serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART3)].functionMask = FUNCTION_MSP; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART3)].msp_baudrateIndex = BLUETOOTH_MSP_BAUDRATE; + + pinioBoxConfigMutable()->permanentId[0] = BOX_PERMANENT_ID_USER1; } diff --git a/src/main/target/SPEEDYBEEF7/target.h b/src/main/target/SPEEDYBEEF7/target.h index ea338680ee4..80f33f50352 100644 --- a/src/main/target/SPEEDYBEEF7/target.h +++ b/src/main/target/SPEEDYBEEF7/target.h @@ -58,7 +58,7 @@ #define USE_EXTI #define USE_IMU_ICM20689 -#define IMU_ICM20689_ALIGN CW180_DEG +#define IMU_ICM20689_ALIGN CW0_DEG #define GYRO_INT_EXTI PC4 #define ICM20689_CS_PIN PA4 @@ -133,6 +133,12 @@ #define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 #define RSSI_ADC_CHANNEL ADC_CHN_3 +// PINIO to disable BT +#define USE_PINIO +#define USE_PINIOBOX +#define PINIO1_PIN PA15 +#define PINIO1_FLAGS PINIO_FLAGS_INVERTED + // FC Default Config #define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY | FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX) #define USE_DSHOT From fd7e382eda5aab4b9ec84905064f909ca03139d5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 3 Aug 2020 08:38:53 +0100 Subject: [PATCH 114/248] [TARGETS] Add SPEEDYBEEF7 to release targets --- make/release.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/make/release.mk b/make/release.mk index a8806f99a73..792d2dbc699 100644 --- a/make/release.mk +++ b/make/release.mk @@ -21,7 +21,7 @@ RELEASE_TARGETS += MATEKF765 RELEASE_TARGETS += FOXEERF405 FOXEERF722DUAL FOXEERF722V2 -RELEASE_TARGETS += SPEEDYBEEF4 FRSKYF3 FRSKYF4 +RELEASE_TARGETS += SPEEDYBEEF4 SPEEDYBEEF7 FRSKYF3 FRSKYF4 RELEASE_TARGETS += NOX WINGFC From a53b1c061947b2624e58df5e29847163b252f89c Mon Sep 17 00:00:00 2001 From: Andi Kanzler Date: Sat, 8 Aug 2020 22:42:03 +0200 Subject: [PATCH 115/248] Add FF to inflight adjustments --- docs/Inflight Adjustments.md | 58 +++++++++++++++++----------------- src/main/fc/rc_adjustments.c | 24 +++++++------- src/main/fc/rc_adjustments.h | 8 ++--- src/main/flight/pid.c | 9 ++++++ src/main/flight/pid.h | 1 + src/main/flight/pid_autotune.c | 6 ++-- src/main/io/osd.c | 8 ++--- 7 files changed, 62 insertions(+), 52 deletions(-) diff --git a/docs/Inflight Adjustments.md b/docs/Inflight Adjustments.md index 7182d9dc385..fee40469544 100644 --- a/docs/Inflight Adjustments.md +++ b/docs/Inflight Adjustments.md @@ -113,45 +113,45 @@ this reason ensure that you define enough ranges to cover the range channel's us | 8 | PITCH_ROLL_D | | 9 | YAW_P | | 10 | YAW_I | -| 11 | YAW_D | +| 11 | YAW_D_FF | | 12 | RATE_PROFILE | Switch between 3 rate profiles using a 3 position switch. | | 13 | PITCH_RATE | | 14 | ROLL_RATE | | 15 | PITCH_P | | 16 | PITCH_I | -| 17 | PITCH_D | +| 17 | PITCH_D_FF | | 18 | ROLL_P | | 19 | ROLL_I | -| 20 | RC_YAW_EXPO | -| 21 | MANUAL_RC_EXPO | -| 22 | MANUAL_RC_YAW_EXPO | -| 23 | MANUAL_PITCH_ROLL_RATE | -| 24 | MANUAL_ROLL_RATE | -| 25 | MANUAL_PITCH_RATE | -| 26 | MANUAL_YAW_RATE | -| 27 | NAV_FW_CRUISE_THROTTLE | -| 28 | NAV_FW_PITCH2THR | -| 29 | ROLL_BOARD_ALIGNMENT | -| 30 | PITCH_BOARD_ALIGNMENT | -| 31 | LEVEL_P | -| 32 | LEVEL_I | -| 33 | LEVEL_D | -| 34 | POS_XY_P | -| 35 | POS_XY_I | -| 36 | POS_XY_D | -| 37 | POS_Z_P | -| 38 | POS_Z_I | -| 39 | POS_Z_D | -| 40 | HEADING_P | -| 41 | VEL_XY_P | -| 42 | VEL_XY_I | -| 43 | VEL_XY_D | -| 44 | VEL_Z_P | +| 20 | ROLL_D_FF | +| 21 | RC_YAW_EXPO | +| 22 | MANUAL_RC_EXPO | +| 23 | MANUAL_RC_YAW_EXPO | +| 24 | MANUAL_PITCH_ROLL_RATE | +| 25 | MANUAL_ROLL_RATE | +| 26 | MANUAL_PITCH_RATE | +| 27 | MANUAL_YAW_RATE | +| 28 | NAV_FW_CRUISE_THROTTLE | +| 29 | NAV_FW_PITCH2THR | +| 30 | ROLL_BOARD_ALIGNMENT | +| 31 | PITCH_BOARD_ALIGNMENT | +| 32 | LEVEL_P | +| 33 | LEVEL_I | +| 34 | LEVEL_D | +| 35 | POS_XY_P | +| 36 | POS_XY_I | +| 37 | POS_XY_D | +| 38 | POS_Z_P | +| 39 | POS_Z_I | +| 40 | POS_Z_D | +| 41 | HEADING_P | +| 42 | VEL_XY_P | +| 43 | VEL_XY_I | +| 44 | VEL_XY_D | | 45 | VEL_Z_P | | 46 | VEL_Z_I | | 47 | VEL_Z_D | | 48 | FW_MIN_THROTTLE_DOWN_PITCH_ANGLE | -| 49 | PROFILE | Switch between 3 rate profiles using a 3 position switch. | +| 49 | ADJUSTMENT_VTX_POWER_LEVEL | ## Examples @@ -263,4 +263,4 @@ The following examples shows __incorrect__ configurations - the entire usable ra In the following example, the incorrect configuraton (above) has been corrected by adding a range that makes 'No changes'. -![Configurator example 7](Screenshots/adjustments-incorrect-config-2-corrected.png) +![Configurator example 7](Screenshots/adjustments-incorrect-config-2-corrected.png) \ No newline at end of file diff --git a/src/main/fc/rc_adjustments.c b/src/main/fc/rc_adjustments.c index bf07c3d6f34..182653a5063 100644 --- a/src/main/fc/rc_adjustments.c +++ b/src/main/fc/rc_adjustments.c @@ -101,7 +101,7 @@ static const adjustmentConfig_t defaultAdjustmentConfigs[ADJUSTMENT_FUNCTION_COU .mode = ADJUSTMENT_MODE_STEP, .data = { .stepConfig = { .step = 1 }} }, { - .adjustmentFunction = ADJUSTMENT_PITCH_ROLL_D, + .adjustmentFunction = ADJUSTMENT_PITCH_ROLL_D_FF, .mode = ADJUSTMENT_MODE_STEP, .data = { .stepConfig = { .step = 1 }} }, { @@ -113,7 +113,7 @@ static const adjustmentConfig_t defaultAdjustmentConfigs[ADJUSTMENT_FUNCTION_COU .mode = ADJUSTMENT_MODE_STEP, .data = { .stepConfig = { .step = 1 }} }, { - .adjustmentFunction = ADJUSTMENT_YAW_D, + .adjustmentFunction = ADJUSTMENT_YAW_D_FF, .mode = ADJUSTMENT_MODE_STEP, .data = { .stepConfig = { .step = 1 }} }, { @@ -137,7 +137,7 @@ static const adjustmentConfig_t defaultAdjustmentConfigs[ADJUSTMENT_FUNCTION_COU .mode = ADJUSTMENT_MODE_STEP, .data = { .stepConfig = { .step = 1 }} }, { - .adjustmentFunction = ADJUSTMENT_PITCH_D, + .adjustmentFunction = ADJUSTMENT_PITCH_D_FF, .mode = ADJUSTMENT_MODE_STEP, .data = { .stepConfig = { .step = 1 }} }, { @@ -149,7 +149,7 @@ static const adjustmentConfig_t defaultAdjustmentConfigs[ADJUSTMENT_FUNCTION_COU .mode = ADJUSTMENT_MODE_STEP, .data = { .stepConfig = { .step = 1 }} }, { - .adjustmentFunction = ADJUSTMENT_ROLL_D, + .adjustmentFunction = ADJUSTMENT_ROLL_D_FF, .mode = ADJUSTMENT_MODE_STEP, .data = { .stepConfig = { .step = 1 }} }, { @@ -441,18 +441,18 @@ static void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t applyAdjustmentPID(ADJUSTMENT_ROLL_I, &pidBankMutable()->pid[PID_ROLL].I, delta); schedulePidGainsUpdate(); break; - case ADJUSTMENT_PITCH_ROLL_D: - case ADJUSTMENT_PITCH_D: - applyAdjustmentPID(ADJUSTMENT_PITCH_D, &pidBankMutable()->pid[PID_PITCH].D, delta); - if (adjustmentFunction == ADJUSTMENT_PITCH_D) { + case ADJUSTMENT_PITCH_ROLL_D_FF: + case ADJUSTMENT_PITCH_D_FF: + applyAdjustmentPID(ADJUSTMENT_PITCH_D_FF, getD_FFRefByBank(pidBankMutable(), PID_PITCH), delta); + if (adjustmentFunction == ADJUSTMENT_PITCH_D_FF) { schedulePidGainsUpdate(); break; } // follow though for combined ADJUSTMENT_PITCH_ROLL_D FALLTHROUGH; - case ADJUSTMENT_ROLL_D: - applyAdjustmentPID(ADJUSTMENT_ROLL_D, &pidBankMutable()->pid[PID_ROLL].D, delta); + case ADJUSTMENT_ROLL_D_FF: + applyAdjustmentPID(ADJUSTMENT_ROLL_D_FF, getD_FFRefByBank(pidBankMutable(), PID_ROLL), delta); schedulePidGainsUpdate(); break; case ADJUSTMENT_YAW_P: @@ -463,8 +463,8 @@ static void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t applyAdjustmentPID(ADJUSTMENT_YAW_I, &pidBankMutable()->pid[PID_YAW].I, delta); schedulePidGainsUpdate(); break; - case ADJUSTMENT_YAW_D: - applyAdjustmentPID(ADJUSTMENT_YAW_D, &pidBankMutable()->pid[PID_YAW].D, delta); + case ADJUSTMENT_YAW_D_FF: + applyAdjustmentPID(ADJUSTMENT_YAW_D_FF, getD_FFRefByBank(pidBankMutable(), PID_YAW), delta); schedulePidGainsUpdate(); break; case ADJUSTMENT_NAV_FW_CRUISE_THR: diff --git a/src/main/fc/rc_adjustments.h b/src/main/fc/rc_adjustments.h index c629086c13a..b51cf390d60 100644 --- a/src/main/fc/rc_adjustments.h +++ b/src/main/fc/rc_adjustments.h @@ -33,19 +33,19 @@ typedef enum { ADJUSTMENT_YAW_RATE = 5, ADJUSTMENT_PITCH_ROLL_P = 6, ADJUSTMENT_PITCH_ROLL_I = 7, - ADJUSTMENT_PITCH_ROLL_D = 8, + ADJUSTMENT_PITCH_ROLL_D_FF = 8, ADJUSTMENT_YAW_P = 9, ADJUSTMENT_YAW_I = 10, - ADJUSTMENT_YAW_D = 11, + ADJUSTMENT_YAW_D_FF = 11, ADJUSTMENT_RATE_PROFILE = 12, // Unused, placeholder for compatibility ADJUSTMENT_PITCH_RATE = 13, ADJUSTMENT_ROLL_RATE = 14, ADJUSTMENT_PITCH_P = 15, ADJUSTMENT_PITCH_I = 16, - ADJUSTMENT_PITCH_D = 17, + ADJUSTMENT_PITCH_D_FF = 17, ADJUSTMENT_ROLL_P = 18, ADJUSTMENT_ROLL_I = 19, - ADJUSTMENT_ROLL_D = 20, + ADJUSTMENT_ROLL_D_FF = 20, ADJUSTMENT_RC_YAW_EXPO = 21, ADJUSTMENT_MANUAL_RC_EXPO = 22, ADJUSTMENT_MANUAL_RC_YAW_EXPO = 23, diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index c76b36cfec2..f58ab3b7dec 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -1114,3 +1114,12 @@ const pidBank_t * pidBank(void) { pidBank_t * pidBankMutable(void) { return usedPidControllerType == PID_TYPE_PIFF ? &pidProfileMutable()->bank_fw : &pidProfileMutable()->bank_mc; } + +uint8_t * getD_FFRefByBank(pidBank_t *pidBank, pidIndex_e pidIndex) +{ + if (pidIndexGetType(pidIndex) == PID_TYPE_PIFF) { + return &pidBank->pid[pidIndex].FF; + } else { + return &pidBank->pid[pidIndex].D; + } +} diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index c9849800afd..c3251909238 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -198,3 +198,4 @@ void autotuneUpdateState(void); void autotuneFixedWingUpdate(const flight_dynamics_index_t axis, float desiredRateDps, float reachedRateDps, float pidOutput); pidType_e pidIndexGetType(pidIndex_e pidIndex); +uint8_t * getD_FFRefByBank(pidBank_t *pidBank, pidIndex_e pidIndex); diff --git a/src/main/flight/pid_autotune.c b/src/main/flight/pid_autotune.c index e66bf0a939e..9db1f15284c 100755 --- a/src/main/flight/pid_autotune.c +++ b/src/main/flight/pid_autotune.c @@ -230,15 +230,15 @@ void autotuneFixedWingUpdate(const flight_dynamics_index_t axis, float desiredRa switch (axis) { case FD_ROLL: - blackboxLogAutotuneEvent(ADJUSTMENT_ROLL_D, tuneCurrent[axis].gainFF); + blackboxLogAutotuneEvent(ADJUSTMENT_ROLL_D_FF, tuneCurrent[axis].gainFF); break; case FD_PITCH: - blackboxLogAutotuneEvent(ADJUSTMENT_PITCH_D, tuneCurrent[axis].gainFF); + blackboxLogAutotuneEvent(ADJUSTMENT_PITCH_D_FF, tuneCurrent[axis].gainFF); break; case FD_YAW: - blackboxLogAutotuneEvent(ADJUSTMENT_YAW_D, tuneCurrent[axis].gainFF); + blackboxLogAutotuneEvent(ADJUSTMENT_YAW_D_FF, tuneCurrent[axis].gainFF); break; } } diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 29bdaedd902..dccfb514f17 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1181,7 +1181,7 @@ static void osdDisplayPIDValues(uint8_t elemPosX, uint8_t elemPosY, const char * elemAttr = TEXT_ATTRIBUTES_NONE; tfp_sprintf(buff, "%3d", pidType == PID_TYPE_PIFF ? pid->FF : pid->D); - if ((isAdjustmentFunctionSelected(adjFuncD)) || (((adjFuncD == ADJUSTMENT_ROLL_D) || (adjFuncD == ADJUSTMENT_PITCH_D)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_D)))) + if ((isAdjustmentFunctionSelected(adjFuncD)) || (((adjFuncD == ADJUSTMENT_ROLL_D_FF) || (adjFuncD == ADJUSTMENT_PITCH_D_FF)) && (isAdjustmentFunctionSelected(ADJUSTMENT_PITCH_ROLL_D_FF)))) TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); displayWriteWithAttr(osdDisplayPort, elemPosX + 12, elemPosY, buff, elemAttr); } @@ -1777,15 +1777,15 @@ static bool osdDrawSingleElement(uint8_t item) #endif case OSD_ROLL_PIDS: - osdDisplayPIDValues(elemPosX, elemPosY, "ROL", PID_ROLL, ADJUSTMENT_ROLL_P, ADJUSTMENT_ROLL_I, ADJUSTMENT_ROLL_D); + osdDisplayPIDValues(elemPosX, elemPosY, "ROL", PID_ROLL, ADJUSTMENT_ROLL_P, ADJUSTMENT_ROLL_I, ADJUSTMENT_ROLL_D_FF); return true; case OSD_PITCH_PIDS: - osdDisplayPIDValues(elemPosX, elemPosY, "PIT", PID_PITCH, ADJUSTMENT_PITCH_P, ADJUSTMENT_PITCH_I, ADJUSTMENT_PITCH_D); + osdDisplayPIDValues(elemPosX, elemPosY, "PIT", PID_PITCH, ADJUSTMENT_PITCH_P, ADJUSTMENT_PITCH_I, ADJUSTMENT_PITCH_D_FF); return true; case OSD_YAW_PIDS: - osdDisplayPIDValues(elemPosX, elemPosY, "YAW", PID_YAW, ADJUSTMENT_YAW_P, ADJUSTMENT_YAW_I, ADJUSTMENT_YAW_D); + osdDisplayPIDValues(elemPosX, elemPosY, "YAW", PID_YAW, ADJUSTMENT_YAW_P, ADJUSTMENT_YAW_I, ADJUSTMENT_YAW_D_FF); return true; case OSD_LEVEL_PIDS: From 8e6ed88c3596162bea73647d1983baa25758e74e Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 9 Aug 2020 16:55:31 +0200 Subject: [PATCH 116/248] Set OneShgot125 as a default ESC protocol --- src/main/flight/mixer.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 20fa78d30b6..41cf51b35ee 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -93,7 +93,7 @@ PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig, #define DEFAULT_PWM_PROTOCOL PWM_TYPE_BRUSHED #define DEFAULT_PWM_RATE 16000 #else -#define DEFAULT_PWM_PROTOCOL PWM_TYPE_STANDARD +#define DEFAULT_PWM_PROTOCOL PWM_TYPE_ONESHOT125 #define DEFAULT_PWM_RATE 400 #endif From 8d61f4f6df6ff1406b7a7496fc888c766f579d56 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 9 Aug 2020 16:56:02 +0200 Subject: [PATCH 117/248] PG version bump --- src/main/flight/mixer.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 41cf51b35ee..a3e6aebd598 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -99,7 +99,7 @@ PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig, #define DEFAULT_MAX_THROTTLE 1850 -PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 5); +PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 6); PG_RESET_TEMPLATE(motorConfig_t, motorConfig, .motorPwmProtocol = DEFAULT_PWM_PROTOCOL, From 7083b122cb6e1d990f927e4cc43afef9b01a1bf3 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 9 Aug 2020 17:37:21 +0200 Subject: [PATCH 118/248] Allow throttle_idle to be 0 for better 3D compatibility --- src/main/fc/settings.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index b673ffa204f..083f5398fa3 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -647,7 +647,7 @@ groups: description: "The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle." default_value: "15" field: throttleIdle - min: 4 + min: 0 max: 30 - name: motor_poles field: motorPoleCount From 8c38a9284a7cb6a4f9e9d2d798e8cf5d226ae014 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Tue, 11 Aug 2020 09:34:41 +0200 Subject: [PATCH 119/248] Fix the meaning of the `serialrx_inverted` setting for F.Port (#5454) `serialrx_inverted` is supposed to be set to OFF for the normal expected polarity of the signal for the selected protocol. Before this change it needed to be set to ON when a F.Port receiver was connected directly to the FC without an inverter or through the inverted S.Port wire present on some receivers. This change uniformizes the meaning of this setting with its meaning for the protocols others than F.Port --- src/main/rx/fport.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/rx/fport.c b/src/main/rx/fport.c index 4b607373c45..3e02b5c47f8 100644 --- a/src/main/rx/fport.c +++ b/src/main/rx/fport.c @@ -394,7 +394,7 @@ bool fportRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) NULL, FPORT_BAUDRATE, MODE_RXTX, - FPORT_PORT_OPTIONS | (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) + FPORT_PORT_OPTIONS | (rxConfig->serialrx_inverted ? 0 : SERIAL_INVERTED) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) ); if (fportPort) { From a319cd609a90c9aec51512895856a0b440dadb7f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 10 Aug 2020 18:57:30 +0100 Subject: [PATCH 120/248] [RX] Make halfDuplex (exposed as serialrx_halfduplex) a tristate This allows us to set the default value to AUTO, so each protocol can select its default "duplexity". Then the explicit ON and OFF values can be used to override the default value for the protocol. Regenerate Settings.md to update the serialrx_halfduplex documentation. This also regenerates some unrelated settings that were out of date. Update Rx.md accordingly. --- docs/Rx.md | 15 ++++++- docs/Settings.md | 47 +++++++++++++++++++--- src/main/common/tristate.h | 56 +++++++++++++++++++++++++++ src/main/fc/settings.yaml | 9 +++-- src/main/rx/crsf.c | 2 +- src/main/rx/fport.c | 4 +- src/main/rx/ibus.c | 2 +- src/main/rx/jetiexbus.c | 2 +- src/main/rx/rx.c | 2 +- src/main/rx/rx.h | 4 +- src/main/rx/sbus.c | 4 +- src/main/rx/spektrum.c | 2 +- src/main/rx/sumd.c | 2 +- src/main/rx/xbus.c | 2 +- src/main/target/FF_FORTINIF4/config.c | 2 +- src/main/target/FF_PIKOF4/config.c | 2 +- 16 files changed, 135 insertions(+), 22 deletions(-) create mode 100644 src/main/common/tristate.h diff --git a/docs/Rx.md b/docs/Rx.md index be8d896a327..569b9e3112d 100644 --- a/docs/Rx.md +++ b/docs/Rx.md @@ -95,9 +95,20 @@ Just connect the S.Port wire from the receiver to the TX pad of a free UART on y #### Configuration +For INAV 2.6 and newer versions, the default configuration should just work. However, if you're +upgrading from a previous version you might need to set the following settings to their +default values: + +``` +set serialrx_inverted = OFF +set serialrx_halfduplex = AUTO +``` + +For INAV versions prior to 2.6, you need to change the following settings: + ``` -set serialrx_inverted = true -set serialrx_halfduplex = true +set serialrx_inverted = ON +set serialrx_halfduplex = ON ``` ### XBUS diff --git a/docs/Settings.md b/docs/Settings.md index 8e3ca620fdc..3ec4d6442a6 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -33,6 +33,7 @@ | antigravity_accelerator | 1 | | | antigravity_cutoff_lpf_hz | 15 | Antigravity cutoff frequenct for Throtte filter. Antigravity is based on the difference between actual and filtered throttle input. The bigger is the difference, the bigger Antigravity gain | | antigravity_gain | 1 | Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements | +| applied_defaults | 0 | Internal (configurator) hint. Should not be changed manually | | baro_cal_tolerance | 150 | Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]. | | baro_hardware | AUTO | Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info | | baro_median_filter | ON | 3-point median filtering for barometer readouts. No reason to change this setting | @@ -52,6 +53,7 @@ | current_meter_scale | 400 | This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt. | | current_meter_type | ADC | ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position. | | deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. | +| debug_mode | NONE | Defines debug values exposed in debug variables (developer / debugging setting) | | disarm_kill_switch | ON | Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel. | | display_force_sw_blink | OFF | OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON | | dterm_lpf2_hz | 0 | Cutoff frequency for stage 2 D-term low pass filter | @@ -135,6 +137,7 @@ | imu_dcm_ki_mag | 0 | Inertial Measurement Unit KI Gain for compass measurements | | imu_dcm_kp | 2500 | Inertial Measurement Unit KP Gain for accelerometer measurements | | imu_dcm_kp_mag | 10000 | Inertial Measurement Unit KP Gain for compass measurements | +| inav_allow_dead_reckoning | OFF | Defines if inav will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation | | inav_auto_mag_decl | ON | Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored. | | inav_baro_epv | 100.000 | Uncertainty value for barometric sensor [cm] | | inav_gravity_cal_tolerance | 5 | Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value. | @@ -153,6 +156,8 @@ | inav_w_z_res_v | 0.500 | Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost | | iterm_windup | 50 | Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter) | | ledstrip_visual_beeper | OFF | | +| log_level | `ERROR` | Defines serial debugging log level. See `docs/development/serial_printf_debugging.md` for usage. | +| log_topics | 0 | Defines serial debugging log topic. See `docs/development/serial_printf_debugging.md` for usage. | | looptime | 1000 | This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible. | | ltm_update_rate | NORMAL | Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details. | | mag_calibration_time | 30 | Adjust how long time the Calibration of mag will last. | @@ -199,6 +204,7 @@ | motor_direction_inverted | OFF | Use if you need to inverse yaw motor direction. | | motor_pwm_protocol | STANDARD | Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED | | motor_pwm_rate | 400 | Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000. | +| msp_override_channels | 0 | Mask of RX channels that may be overridden by MSP `SET_RAW_RC`. Note that this requires custom firmware with `USE_RX_MSP` and `USE_MSP_RC_OVERRIDE` compile options and the `MSP RC Override` flight mode. | | name | Empty string | Craft name | | nav_auto_climb_rate | 500 | Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s] | | nav_auto_speed | 300 | Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only] | @@ -247,7 +253,7 @@ | nav_landing_speed | 200 | Vertical descent velocity during the RTH landing phase. [cm/s] | | nav_manual_climb_rate | 200 | Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] | | nav_manual_speed | 500 | Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only] | -| nav_mc_auto_disarm_delay | 2000 | | +| nav_mc_auto_disarm_delay | 2000 | Delay before multi-rotor disarms when `nav_disarm_on_landing` is set (m/s) | | nav_mc_bank_angle | 30 | Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude | | nav_mc_braking_bank_angle | 40 | max angle that MR is allowed to bank in BOOST mode | | nav_mc_braking_boost_disengage_speed | 100 | BOOST will be disabled when speed goes below this value | @@ -264,6 +270,9 @@ | nav_mc_pos_xy_p | 65 | Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity | | nav_mc_pos_z_p | 50 | P gain of altitude PID controller (Multirotor) | | nav_mc_vel_xy_d | 100 | D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target. | +| nav_mc_vel_xy_dterm_attenuation | 90 | Maximum D-term attenution percentage for horizontal velocity PID controller (Multirotor). It allows to smooth the PosHold CRUISE, WP and RTH when Multirotor is traveling at full speed. Dterm is not attenuated at low speeds, breaking and accelerating. | +| nav_mc_vel_xy_dterm_attenuation_end | 60 | A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation reaches maximum | +| nav_mc_vel_xy_dterm_attenuation_start | 10" | A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation begins | | nav_mc_vel_xy_i | 15 | I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot | | nav_mc_vel_xy_p | 40 | P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause "nervous" behavior and oscillations | | nav_mc_vel_z_d | 10 | D gain of velocity PID controller | @@ -279,35 +288,55 @@ | nav_rth_climb_first | ON | If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way. | | nav_rth_climb_ignore_emerg | OFF | If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status. | | nav_rth_home_altitude | 0 | Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm] | -| nav_rth_home_offset_direction | 0 | Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) | -| nav_rth_home_offset_distance | 0 | Distance offset from GPS established home to "safe" position used for RTH (cm, 0 disables) | | nav_rth_tail_first | OFF | If set to ON drone will return tail-first. Obviously meaningless for airplanes. | | nav_use_fw_yaw_control | OFF | Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats | | nav_use_midthr_for_althold | OFF | If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude | | nav_user_control_mode | ATTI | Defines how Pitch/Roll input from RC receiver affects flight in POSHOLD mode: ATTI - pitch/roll controls attitude like in ANGLE mode; CRUISE - pitch/roll controls velocity in forward and right direction. | | nav_wp_radius | 100 | Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius | | nav_wp_safe_distance | 10000 | First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check. | +| opflow_hardware | | Selection of OPFLOW hardware. | +| osd_ahi_bordered | OFF | Shows a border/corners around the AHI region (pixel OSD only) | +| osd_ahi_height | 162 | AHI height in pixels (pixel OSD only) | | osd_ahi_style | DEFAULT | Sets OSD Artificial Horizon style "DEFAULT" or "LINE" for the FrSky Graphical OSD. | +| osd_ahi_vertical_offset | 0 | AHI vertical offset from center (pixel OSD only) | +| osd_ahi_width | 132 | AHI width in pixels (pixel OSD only) | | osd_alt_alarm | 100 | Value above which to make the OSD relative altitude indicator blink (meters) | | osd_artificial_horizon_max_pitch | 20 | Max pitch, in degrees, for OSD artificial horizon | | osd_baro_temp_alarm_max | 600 | Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade) | | osd_baro_temp_alarm_min | -200 | Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade) | +| osd_camera_fov_h | 135 | Horizontal field of view for the camera in degres | +| osd_camera_fov_v | 85 | Vertical field of view for the camera in degres | +| osd_camera_uptilt | 0 | Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal | +| osd_crosshairs_style | DEFAULT | To set the visual type for the crosshair | | osd_current_alarm | 0 | Value above which the OSD current consumption element will start blinking. Measured in full Amperes. | | osd_dist_alarm | 1000 | Value above which to make the OSD distance from home indicator blink (meters) | | osd_esc_temp_alarm_max | 900 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | | osd_esc_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | | osd_estimations_wind_compensation | ON | Use wind estimation for remaining flight time/distance estimation | | osd_failsafe_switch_layout | OFF | If enabled the OSD automatically switches to the first layout during failsafe | +| osd_force_grid | OFF | Force OSD to work in grid mode even if the OSD device supports pixel level access (mainly used for development) | | osd_gforce_alarm | 5 | Value above which the OSD g force indicator will blink (g) | | osd_gforce_axis_alarm_max | 5 | Value above which the OSD axis g force indicators will blink (g) | | osd_gforce_axis_alarm_min | -5 | Value under which the OSD axis g force indicators will blink (g) | -| osd_hud_wp_disp | OFF | Controls display of the next waypoints in the HUD. | +| osd_horizon_offset | 0 | To vertically adjust the whole OSD and AHI and scrolling bars | +| osd_hud_homepoint | 0 | To 3D-display the home point location in the hud | +| osd_hud_homing | 0 | To display little arrows around the crossair showing where the home point is in the hud | +| osd_hud_margin_h | 3 | Left and right margins for the hud area | +| osd_hud_margin_v | 3 | Top and bottom margins for the hud area | +| osd_hud_radar_disp | 0 | Maximum count of nearby aircrafts or points of interest to display in the hud, as sent from an ESP32 LoRa module. Set to 0 to disable (show nothing). The nearby aircrafts will appear as markers A, B, C, etc | +| osd_hud_radar_nearest | 0 | To display an extra bar of informations at the bottom of the hud area for the closest radar aircraft found, if closest than the set value, in meters. Shows relative altitude (meters or feet, with an up or down arrow to indicate if above or below), speed (in m/s or f/s), and absolute heading (in °, 0 is north, 90 is east, 180 is south, 270 is west). Set to 0 (zero) to disable. | +| osd_hud_radar_range_max | 4000" | In meters, radar aircrafts further away than this will not be displayed in the hud | +| osd_hud_radar_range_min | 3 | In meters, radar aircrafts closer than this will not be displayed in the hud | +| osd_hud_wp_disp | 0 | How many navigation waypoints are displayed, set to 0 (zero) to disable. As sample, if set to 2, and you just passed the 3rd waypoint of the mission, you'll see markers for the 4th waypoint (marked 1) and the 5th waypoint (marked 2) | | osd_imu_temp_alarm_max | 600 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | | osd_imu_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | +| osd_left_sidebar_scroll_step | 0 | How many units each sidebar step represents. 0 means the default value for the scroll type. | | osd_main_voltage_decimals | 1 | Number of decimals for the battery voltages displayed in the OSD [1-2]. | | osd_neg_alt_alarm | 5 | Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters) | +| osd_right_sidebar_scroll_step | 0 | Same as left_sidebar_scroll_step, but for the right sidebar | | osd_row_shiftdown | 0 | Number of rows to shift the OSD display (increase if top rows are cut off) | | osd_rssi_alarm | 20 | Value bellow which to make the OSD RSSI indicator blink | +| osd_sidebar_horizontal_offset | 0 | Sidebar horizontal offset from default position. Positive values move the sidebars closer to the edges. | | osd_stats_energy_unit | MAH | Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour) | | osd_temp_label_align | LEFT | Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT` | | osd_time_alarm | 10 | Value above which to make the OSD flight time indicator blink (minutes) | @@ -317,8 +346,10 @@ | pidsum_limit | 500 | A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | | pidsum_limit_yaw | 400 | A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | | pitch_rate | 20 | Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. | +| pitot_hardware | NONE | Selection of pitot hardware. | | platform_type | "MULTIROTOR" | Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented | | pos_hold_deadband | 20 | Stick deadband in [r/c points], applied after r/c deadband and expo | +| rangefinder_hardware | NONE | Selection of rangefinder hardware. | | rangefinder_median_filter | OFF | 3-point median filtering for rangefinder readouts | | rate_accel_limit_roll_pitch | 0 | Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting. | | rate_accel_limit_yaw | 10000 | Limits acceleration of YAW rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 180 dps^2). When set correctly, it greatly improves stopping performance and general stability during yaw turns. Value of 0 disables limiting. | @@ -326,6 +357,7 @@ | rc_filter_frequency | 50 | RC data biquad filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay. Practical values are 20-50. Set to zero to disable entirely and use unsmoothed RC stick values | | rc_yaw_expo | 20 | Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`) | | reboot_character | 82 | Special character used to trigger reboot | +| receiver_type | `TARGET dependent` | Selection of receiver (RX) type. Additional configuration of a `serialrx_provider` and a UART will be needed for `SERIAL` | | report_cell_voltage | OFF | S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON | | roll_rate | 20 | Defines rotation rate on ROLL axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. | | rpm_gyro_filter_enabled | `OFF` | Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV | @@ -341,13 +373,17 @@ | rx_max_usec | 2115 | Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of mid_rc. | | rx_min_usec | 885 | Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc. | | sdcard_detect_inverted | `TARGET dependent` | This setting drives the way SD card is detected in card slot. On some targets (AnyFC F7 clone) different card slot was used and depending of hardware revision ON or OFF setting might be required. If card is not detected, change this value. | -| serialrx_halfduplex | OFF | Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire | +| serialrx_halfduplex | AUTO | Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire | | serialrx_inverted | OFF | Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY). | | serialrx_provider | SPEK1024 | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. | | servo_center_pulse | 1500 | Servo midpoint | | servo_lpf_hz | 20 | Selects the servo PWM output cutoff frequency. Value is in [Hz] | | servo_protocol | PWM | An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SERVO_DRIVER` (I2C PCA9685 peripheral), `SBUS` (S.Bus protocol output via a configured serial port) | | servo_pwm_rate | 50 | Output frequency (in Hz) servo pins. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz. | +| setpoint_kalman_enabled | OFF | Enable Kalman filter on the PID controller setpoint | +| setpoint_kalman_q | 100 | Quality factor of the setpoint Kalman filter. Higher values means less filtering and lower phase delay. On 3-7 inch multirotors can be usually increased to 200-300 or even higher of clean builds | +| setpoint_kalman_sharpness | 100 | Dynamic factor for the setpoint Kalman filter. In general, the higher the value, the more dynamic Kalman filter gets | +| setpoint_kalman_w | 4 | Window size for the setpoint Kalman filter. Wider the window, more samples are used to compute variance. In general, wider window results in smoother filter response | | sim_ground_station_number | Empty string | Number of phone that is used to communicate with SIM module. Messages / calls from other numbers are ignored. If undefined, can be set by calling or sending a message to the module. | | sim_low_altitude | 0 | Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`. | | sim_pin | Empty string | PIN code for the SIM module | @@ -385,6 +421,7 @@ | vtx_channel | 1 | Channel to use within the configured `vtx_band`. Valid values are [1, 8]. | | vtx_halfduplex | ON | Use half duplex UART to communicate with the VTX, using only a TX pin in the FC. | | vtx_low_power_disarm | OFF | When the craft is disarmed, set the VTX to its lowest power. `ON` will set the power to its minimum value on startup, increase it to `vtx_power` when arming and change it back to its lowest setting after disarming. `UNTIL_FIRST_ARM` will start with minimum power, but once the craft is armed it will increase to `vtx_power` and it will never decrease until the craft is power cycled. | +| vtx_max_power_override | 0 | Some VTXes may report max power incorrectly (i.e. 200mW for a 600mW VTX). Use this to override max supported power. 0 to disable and use whatever VTX reports as its capabilities | | vtx_power | 1 | VTX RF power level to use. The exact number of mw depends on the VTX hardware. | | yaw_deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. | | yaw_lpf_hz | 30 | Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below) | diff --git a/src/main/common/tristate.h b/src/main/common/tristate.h new file mode 100644 index 00000000000..4215814e865 --- /dev/null +++ b/src/main/common/tristate.h @@ -0,0 +1,56 @@ +/* + * This file is part of iNav. + * + * iNav is free software. You can redistribute this software + * and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * iNav is distributed in the hope that they will be + * useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +#include + +// tristate_e represents something that can take a default AUTO +// value and two explicit ON and OFF values. To ease the transition +// from boolean settings (0 = OFF, 1 = ON), the 1 value has +// been picked as ON while OFF is represented by 2. AUTO is represented +// by 0. +typedef enum { + TRISTATE_AUTO = 0, + TRISTATE_ON = 1, + TRISTATE_OFF = 2, +} tristate_e; + +// tristateWithDefaultOnIsActive returns false is tristate is TRISTATE_OFF +// and true otherwise. +static inline bool tristateWithDefaultOnIsActive(tristate_e tristate) +{ + return tristate != TRISTATE_OFF; +} + +// tristateWithDefaultOffIsActive returns true is tristate is TRISTATE_ON +// and false otherwise. +static inline bool tristateWithDefaultOffIsActive(tristate_e tristate) +{ + return tristate == TRISTATE_ON; +} + +// tristateWithDefaultIsActive() calls tristateWithDefaultOnIsActive() when +// def is true, and tristateWithDefaultOffIsActive() otherwise. +// See tristateWithDefaultOnIsActive() and tristateWithDefaultOffIsActive() +static inline bool tristateWithDefaultIsActive(tristate_e tristate, bool def) +{ + return def ? tristateWithDefaultOnIsActive(tristate) : tristateWithDefaultOffIsActive(tristate); +} \ No newline at end of file diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 083f5398fa3..e1086d6bf0d 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -141,6 +141,9 @@ tables: - name: osd_ahi_style values: ["DEFAULT", "LINE"] enum: osd_ahi_style_e + - name: tristate + enum: tristate_e + values: ["AUTO", "ON", "OFF"] groups: - name: PG_GYRO_CONFIG @@ -557,10 +560,10 @@ groups: min: PWM_PULSE_MIN max: PWM_PULSE_MAX - name: serialrx_halfduplex - description: "Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire" - default_value: "OFF" + description: "Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire." + default_value: "AUTO" field: halfDuplex - type: bool + table: tristate - name: msp_override_channels description: "Mask of RX channels that may be overridden by MSP `SET_RAW_RC`. Note that this requires custom firmware with `USE_RX_MSP` and `USE_MSP_RC_OVERRIDE` compile options and the `MSP RC Override` flight mode." default_value: "0" diff --git a/src/main/rx/crsf.c b/src/main/rx/crsf.c index 6a0ad8d3f5a..a4fd468661b 100755 --- a/src/main/rx/crsf.c +++ b/src/main/rx/crsf.c @@ -305,7 +305,7 @@ bool crsfRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) NULL, CRSF_BAUDRATE, CRSF_PORT_MODE, - CRSF_PORT_OPTIONS | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) + CRSF_PORT_OPTIONS | (tristateWithDefaultOffIsActive(rxConfig->halfDuplex) ? SERIAL_BIDIR : 0) ); return serialPort != NULL; diff --git a/src/main/rx/fport.c b/src/main/rx/fport.c index 3e02b5c47f8..4f68bee1177 100644 --- a/src/main/rx/fport.c +++ b/src/main/rx/fport.c @@ -394,7 +394,9 @@ bool fportRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) NULL, FPORT_BAUDRATE, MODE_RXTX, - FPORT_PORT_OPTIONS | (rxConfig->serialrx_inverted ? 0 : SERIAL_INVERTED) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) + FPORT_PORT_OPTIONS | + (rxConfig->serialrx_inverted ? 0 : SERIAL_INVERTED) | + (tristateWithDefaultOnIsActive(rxConfig->halfDuplex) ? SERIAL_BIDIR : 0) ); if (fportPort) { diff --git a/src/main/rx/ibus.c b/src/main/rx/ibus.c index 474d563e298..b6c502b5265 100755 --- a/src/main/rx/ibus.c +++ b/src/main/rx/ibus.c @@ -241,7 +241,7 @@ bool ibusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) NULL, IBUS_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, - SERIAL_NOT_INVERTED | (rxConfig->halfDuplex || portShared ? SERIAL_BIDIR : 0) + SERIAL_NOT_INVERTED | ((tristateWithDefaultOffIsActive(rxConfig->halfDuplex) || portShared) ? SERIAL_BIDIR : 0) ); #if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_IBUS) diff --git a/src/main/rx/jetiexbus.c b/src/main/rx/jetiexbus.c index 7f82457ad35..14424ff952c 100644 --- a/src/main/rx/jetiexbus.c +++ b/src/main/rx/jetiexbus.c @@ -607,7 +607,7 @@ bool jetiExBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfi NULL, JETIEXBUS_BAUDRATE, MODE_RXTX, - JETIEXBUS_OPTIONS | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) + JETIEXBUS_OPTIONS | (tristateWithDefaultOffIsActive(rxConfig->halfDuplex) ? SERIAL_BIDIR : 0) ); serialSetMode(jetiExBusPort, MODE_RX); diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 5ed140f5dda..8063cf08304 100755 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -121,7 +121,7 @@ PG_REGISTER_WITH_RESET_TEMPLATE(rxConfig_t, rxConfig, PG_RX_CONFIG, 9); PG_RESET_TEMPLATE(rxConfig_t, rxConfig, .receiverType = DEFAULT_RX_TYPE, .rcmap = {0, 1, 3, 2}, // Default to AETR map - .halfDuplex = 0, + .halfDuplex = TRISTATE_AUTO, .serialrx_provider = SERIALRX_PROVIDER, .rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL, .spektrum_sat_bind = 0, diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index 4444cb847ab..4a64a730896 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -21,6 +21,8 @@ #include #include "common/time.h" +#include "common/tristate.h" + #include "config/parameter_group.h" #define STICK_CHANNEL_COUNT 4 @@ -108,7 +110,7 @@ typedef struct rxConfig_s { uint8_t rcmap[MAX_MAPPABLE_RX_INPUTS]; // mapping of radio channels to internal RPYTA+ order uint8_t serialrx_provider; // Type of UART-based receiver (rxSerialReceiverType_e enum). Only used if receiverType is RX_TYPE_SERIAL uint8_t serialrx_inverted; // Flip the default inversion of the protocol - e.g. sbus (Futaba, FrSKY) is inverted if this is false, uninverted if it's true. Support for uninverted OpenLRS (and modified FrSKY) receivers. - uint8_t halfDuplex; // allow rx to operate in half duplex mode on F4, ignored for F1 and F3. + uint8_t halfDuplex; // allow rx to operate in half duplex mode. From tristate_e. uint8_t rx_spi_protocol; // type of SPI receiver protocol (rx_spi_protocol_e enum). Only used if receiverType is RX_TYPE_SPI uint32_t rx_spi_id; uint8_t rx_spi_rf_channel_count; diff --git a/src/main/rx/sbus.c b/src/main/rx/sbus.c index a41e264c2a7..a206e0d41f9 100644 --- a/src/main/rx/sbus.c +++ b/src/main/rx/sbus.c @@ -195,7 +195,9 @@ static bool sbusInitEx(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeC &sbusFrameData, sbusBaudRate, portShared ? MODE_RXTX : MODE_RX, - SBUS_PORT_OPTIONS | (rxConfig->serialrx_inverted ? 0 : SERIAL_INVERTED) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) + SBUS_PORT_OPTIONS | + (rxConfig->serialrx_inverted ? 0 : SERIAL_INVERTED) | + (tristateWithDefaultOffIsActive(rxConfig->halfDuplex) ? SERIAL_BIDIR : 0) ); #ifdef USE_TELEMETRY diff --git a/src/main/rx/spektrum.c b/src/main/rx/spektrum.c index 34c641c3fcb..42b46c7b3be 100644 --- a/src/main/rx/spektrum.c +++ b/src/main/rx/spektrum.c @@ -294,7 +294,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig NULL, SPEKTRUM_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, - SERIAL_NOT_INVERTED | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) + SERIAL_NOT_INVERTED | (tristateWithDefaultOffIsActive(rxConfig->halfDuplex) ? SERIAL_BIDIR : 0) ); #ifdef USE_TELEMETRY diff --git a/src/main/rx/sumd.c b/src/main/rx/sumd.c index 814e8563d59..1e89705e374 100644 --- a/src/main/rx/sumd.c +++ b/src/main/rx/sumd.c @@ -189,7 +189,7 @@ bool sumdInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) NULL, SUMD_BAUDRATE, portShared ? MODE_RXTX : MODE_RX, - SERIAL_NOT_INVERTED | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) + SERIAL_NOT_INVERTED | (tristateWithDefaultOffIsActive(rxConfig->halfDuplex) ? SERIAL_BIDIR : 0) ); #ifdef USE_TELEMETRY diff --git a/src/main/rx/xbus.c b/src/main/rx/xbus.c index 82cd3618961..9357b872487 100644 --- a/src/main/rx/xbus.c +++ b/src/main/rx/xbus.c @@ -334,7 +334,7 @@ bool xBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) NULL, baudRate, portShared ? MODE_RXTX : MODE_RX, - SERIAL_NOT_INVERTED | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) + SERIAL_NOT_INVERTED | (tristateWithDefaultOffIsActive(rxConfig->halfDuplex) ? SERIAL_BIDIR : 0) ); #ifdef USE_TELEMETRY diff --git a/src/main/target/FF_FORTINIF4/config.c b/src/main/target/FF_FORTINIF4/config.c index 6acec9f9b4b..67d129e23ce 100644 --- a/src/main/target/FF_FORTINIF4/config.c +++ b/src/main/target/FF_FORTINIF4/config.c @@ -31,5 +31,5 @@ void targetConfiguration(void) featureSet(FEATURE_OSD); } - rxConfigMutable()->halfDuplex = false; + rxConfigMutable()->halfDuplex = TRISTATE_OFF; } diff --git a/src/main/target/FF_PIKOF4/config.c b/src/main/target/FF_PIKOF4/config.c index 5d7d0df06ec..905eb58011a 100644 --- a/src/main/target/FF_PIKOF4/config.c +++ b/src/main/target/FF_PIKOF4/config.c @@ -27,6 +27,6 @@ void targetConfiguration(void) { - rxConfigMutable()->halfDuplex = false; + rxConfigMutable()->halfDuplex = TRISTATE_OFF; batteryMetersConfigMutable()->current.scale = CURRENTSCALE; } From bf365134f7e6bf1f9be09c239859f81ba23fb567 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Thu, 23 Jul 2020 22:52:11 +0200 Subject: [PATCH 121/248] Add F.Port2 support --- make/source.mk | 1 + src/main/fc/settings.yaml | 2 +- src/main/rx/fport2.c | 672 ++++++++++++++++++++++++++++++++++++++ src/main/rx/fport2.h | 27 ++ src/main/rx/rx.c | 6 + src/main/rx/rx.h | 1 + src/main/target/common.h | 2 + 7 files changed, 710 insertions(+), 1 deletion(-) create mode 100644 src/main/rx/fport2.c create mode 100644 src/main/rx/fport2.h diff --git a/make/source.mk b/make/source.mk index d952118e3dc..e9e3a33e5be 100644 --- a/make/source.mk +++ b/make/source.mk @@ -129,6 +129,7 @@ MAIN_SRC = \ rx/crsf.c \ rx/eleres.c \ rx/fport.c \ + rx/fport2.c \ rx/ibus.c \ rx/jetiexbus.c \ rx/msp.c \ diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index e1086d6bf0d..fe42a114e1c 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -25,7 +25,7 @@ tables: values: ["NONE", "PPM", "SERIAL", "MSP", "SPI", "UIB"] enum: rxReceiverType_e - name: serial_rx - values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "SUMH", "XB-B", "XB-B-RJ01", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "FPORT2", "SBUS_FAST"] + values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "SUMH", "XB-B", "XB-B-RJ01", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "SBUS_FAST", "FPORT2"] - name: rx_spi_protocol values: ["V202_250K", "V202_1M", "SYMA_X", "SYMA_X5C", "CX10", "CX10A", "H8_3D", "INAV", "ELERES"] enum: rx_spi_protocol_e diff --git a/src/main/rx/fport2.c b/src/main/rx/fport2.c new file mode 100644 index 00000000000..f2382d1d123 --- /dev/null +++ b/src/main/rx/fport2.c @@ -0,0 +1,672 @@ +/* + * This file is part of iNav. + * + * iNav are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * iNav is distributed in the hope that it + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#include +#include +#include +#include + +#include "platform.h" + +#ifdef USE_SERIALRX_FPORT2 + +#include "build/debug.h" + +#include "common/log.h" +#include "common/maths.h" +#include "common/utils.h" + +#include "drivers/time.h" + +#ifdef MSP_FIRMWARE_UPDATE +#include "fc/firmware_update.h" +#endif + +#include "io/serial.h" +#include "io/smartport_master.h" + +#ifdef USE_TELEMETRY +#include "telemetry/telemetry.h" +#include "telemetry/smartport.h" +#endif + +#include "rx/frsky_crc.h" +#include "rx/rx.h" +#include "rx/sbus_channels.h" +#include "rx/fport2.h" + + +#define FPORT2_MAX_TELEMETRY_RESPONSE_DELAY_US 3000 +#define FPORT2_MIN_TELEMETRY_RESPONSE_DELAY_US 500 +#define FPORT2_MIN_OTA_RESPONSE_DELAY_US 50 +#define FPORT2_MAX_TELEMETRY_AGE_MS 500 +#define FPORT2_FC_COMMON_ID 0x1B +#define FPORT2_FC_MSP_ID 0x0D +#define FPORT2_BAUDRATE 115200 +#define FPORT2_PORT_OPTIONS (SERIAL_STOPBITS_1 | SERIAL_PARITY_NO) +#define FPORT2_RX_TIMEOUT 120 // µs +#define FPORT2_CONTROL_FRAME_LENGTH 24 +#define FPORT2_OTA_DATA_FRAME_LENGTH 32 +#define FPORT2_DOWNLINK_FRAME_LENGTH 8 +#define FPORT2_UPLINK_FRAME_LENGTH 8 +#define FPORT2_TELEMETRY_MAX_CONSECUTIVE_TELEMETRY_FRAMES 2 +#define FPORT2_OTA_DATA_FRAME_BYTES 32 + +enum { + DEBUG_FPORT2_FRAME_INTERVAL = 0, + DEBUG_FPORT2_FRAME_ERRORS, + DEBUG_FPORT2_FRAME_LAST_ERROR, + DEBUG_FPORT2_TELEMETRY_INTERVAL, + DEBUG_FPORT2_MAX_BUFFER_USAGE, + DEBUG_FPORT2_OTA_FRAME_RESPONSE_TIME, + DEBUG_FPORT2_OTA_RECEIVED_BYTES, +}; + +enum { + DEBUG_FPORT2_NO_ERROR = 0, + DEBUG_FPORT2_ERROR_TIMEOUT, + DEBUG_FPORT2_ERROR_OVERSIZE, + DEBUG_FPORT2_ERROR_SIZE, + DEBUG_FPORT2_ERROR_CHECKSUM, + DEBUG_FPORT2_ERROR_PHYID_CRC, + DEBUG_FPORT2_ERROR_TYPE, + DEBUG_FPORT2_ERROR_TYPE_SIZE, + DEBUG_FPORT2_ERROR_OTA_BAD_ADDRESS, +}; + +typedef enum { + CFT_RC = 0xFF, + CFT_OTA_START = 0xF0, + CFT_OTA_DATA = 0xF1, + CFT_OTA_STOP = 0xF2 +} fport2_control_frame_type_e; + +typedef enum { + FT_CONTROL, + FT_DOWNLINK +} frame_type_e; + +typedef enum { + FS_CONTROL_FRAME_START, + FS_CONTROL_FRAME_TYPE, + FS_CONTROL_FRAME_DATA, + FS_DOWNLINK_FRAME_START, + FS_DOWNLINK_FRAME_DATA +} frame_state_e; + +enum { + FPORT2_FRAME_ID_NULL = 0x00, + FPORT2_FRAME_ID_DATA = 0x10, + FPORT2_FRAME_ID_READ = 0x30, + FPORT2_FRAME_ID_WRITE = 0x31, + FPORT2_FRAME_ID_RESPONSE = 0x32, + FPORT2_FRAME_ID_OTA_START = 0xF0, + FPORT2_FRAME_ID_OTA_DATA = 0xF1, + FPORT2_FRAME_ID_OTA_STOP = 0xF2 +}; + +typedef struct { + sbusChannels_t channels; + uint8_t rssi; +} rcData_t; + +typedef struct { + uint8_t phyID; + /*uint8_t phyID : 5;*/ + /*uint8_t phyXOR : 3;*/ + smartPortPayload_t telemetryData; +} PACKED fportDownlinkData_t; + +typedef struct { + uint8_t type; + union { + rcData_t rc; + uint8_t ota[FPORT2_OTA_DATA_FRAME_BYTES]; + }; +} PACKED fportControlFrame_t; + +typedef struct { + uint8_t type; + union { + fportControlFrame_t control; + fportDownlinkData_t downlink; + }; +} fportFrame_t; + +// RX frames ring buffer +#define NUM_RX_BUFFERS 15 + +typedef struct fportBuffer_s { + uint8_t data[sizeof(fportFrame_t)+1]; // +1 for CRC + uint8_t length; +} fportBuffer_t; + +typedef struct { + uint32_t size; + uint8_t crc; +} PACKED firmwareUpdateHeader_t; + +static volatile fportBuffer_t rxBuffer[NUM_RX_BUFFERS]; +static volatile uint8_t rxBufferWriteIndex = 0; +static volatile uint8_t rxBufferReadIndex = 0; + +static serialPort_t *fportPort; + +#ifdef USE_TELEMETRY_SMARTPORT +static smartPortPayload_t *mspPayload = NULL; +static bool telemetryEnabled = false; +static volatile timeUs_t lastTelemetryFrameReceivedUs; +static volatile bool clearToSend = false; +static volatile bool sendNullFrame = false; +static uint8_t downlinkPhyID; +static const smartPortPayload_t emptySmartPortFrame = { .frameId = 0, .valueId = 0, .data = 0 }; +static smartPortPayload_t *otaResponsePayload = NULL; +static bool otaMode = false; +static bool otaDataNeedsProcessing = false; +static uint32_t otaDataAddress; +static uint8_t otaDataBuffer[FPORT2_OTA_DATA_FRAME_BYTES]; +static timeUs_t otaFrameEndTimestamp = 0; +static bool firmwareUpdateError = false; +#ifdef MSP_FIRMWARE_UPDATE +static uint8_t firmwareUpdateCRC; +static timeUs_t readyToUpdateFirmwareTimestamp = 0; +#endif +#endif + +static volatile uint16_t frameErrors = 0; + +static void reportFrameError(uint8_t errorReason) { + + frameErrors++; + + DEBUG_SET(DEBUG_FPORT, DEBUG_FPORT2_FRAME_ERRORS, frameErrors); + DEBUG_SET(DEBUG_FPORT, DEBUG_FPORT2_FRAME_LAST_ERROR, errorReason); +} + +static uint8_t bufferCount(void) +{ + if (rxBufferReadIndex > rxBufferWriteIndex) { + return NUM_RX_BUFFERS - rxBufferReadIndex + rxBufferWriteIndex; + } else { + return rxBufferWriteIndex - rxBufferReadIndex; + } +} + +static void clearWriteBuffer(void) +{ + rxBuffer[rxBufferWriteIndex].length = 0; +} + +static bool nextWriteBuffer(void) +{ + const uint8_t nextWriteIndex = (rxBufferWriteIndex + 1) % NUM_RX_BUFFERS; + if (nextWriteIndex != rxBufferReadIndex) { + rxBufferWriteIndex = nextWriteIndex; + clearWriteBuffer(); + return true; + } else { + clearWriteBuffer(); + return false; + } +} + +static uint8_t writeBuffer(uint8_t byte) +{ + volatile uint8_t * const buffer = rxBuffer[rxBufferWriteIndex].data; + volatile uint8_t * const buflen = &rxBuffer[rxBufferWriteIndex].length; + buffer[*buflen] = byte; + *buflen += 1; + return *buflen; +} + +// UART RX ISR +static void fportDataReceive(uint16_t byte, void *callback_data) +{ + UNUSED(callback_data); + + static volatile frame_state_e state = FS_CONTROL_FRAME_START; + static volatile timeUs_t lastRxByteTimestamp = 0; + const timeUs_t currentTimeUs = micros(); + const timeUs_t timeSincePreviousRxByte = lastRxByteTimestamp ? currentTimeUs - lastRxByteTimestamp : 0; + static unsigned controlFrameSize; + + lastRxByteTimestamp = currentTimeUs; +#if defined(USE_TELEMETRY_SMARTPORT) + clearToSend = false; +#endif + + if ((state != FS_CONTROL_FRAME_START) && (timeSincePreviousRxByte > FPORT2_RX_TIMEOUT)) { + state = FS_CONTROL_FRAME_START; + } + + switch (state) { + + case FS_CONTROL_FRAME_START: + if ((byte == FPORT2_CONTROL_FRAME_LENGTH) || (byte == FPORT2_OTA_DATA_FRAME_LENGTH)) { + clearWriteBuffer(); + writeBuffer(FT_CONTROL); + state = FS_CONTROL_FRAME_TYPE; + } + break; + + case FS_CONTROL_FRAME_TYPE: + if ((byte == CFT_RC) || ((byte >= CFT_OTA_START) && (byte <= CFT_OTA_STOP))) { + unsigned controlFrameType = byte; + writeBuffer(controlFrameType); + controlFrameSize = (controlFrameType == CFT_OTA_DATA ? FPORT2_OTA_DATA_FRAME_LENGTH : FPORT2_CONTROL_FRAME_LENGTH) + 2; // +2 = General frame type + CRC + state = FS_CONTROL_FRAME_DATA; + } else { + state = FS_CONTROL_FRAME_START; + } + break; + + case FS_CONTROL_FRAME_DATA: { + if (writeBuffer(byte) > controlFrameSize) { + nextWriteBuffer(); + state = FS_DOWNLINK_FRAME_START; + } + break; + } + + case FS_DOWNLINK_FRAME_START: + if (byte == FPORT2_DOWNLINK_FRAME_LENGTH) { + writeBuffer(FT_DOWNLINK); + state = FS_DOWNLINK_FRAME_DATA; + } else { + state = FS_CONTROL_FRAME_START; + } + break; + + case FS_DOWNLINK_FRAME_DATA: + if (writeBuffer(byte) > (FPORT2_DOWNLINK_FRAME_LENGTH + 1)) { +#if defined(USE_TELEMETRY_SMARTPORT) + if ((rxBuffer[rxBufferWriteIndex].data[2] >= FPORT2_FRAME_ID_OTA_START) && (rxBuffer[rxBufferWriteIndex].data[2] <= FPORT2_FRAME_ID_OTA_STOP)) { + otaFrameEndTimestamp = currentTimeUs; + } + lastTelemetryFrameReceivedUs = currentTimeUs; +#endif + nextWriteBuffer(); + state = FS_CONTROL_FRAME_START; + } + break; + + default: + state = FS_CONTROL_FRAME_START; + break; + + } + + DEBUG_SET(DEBUG_FPORT, DEBUG_FPORT2_MAX_BUFFER_USAGE, MAX(bufferCount(), debug[DEBUG_FPORT2_MAX_BUFFER_USAGE])); + +} + +#if defined(USE_TELEMETRY_SMARTPORT) +static void writeUplinkFramePhyID(uint8_t phyID, const smartPortPayload_t *payload) +{ + serialWrite(fportPort, FPORT2_UPLINK_FRAME_LENGTH); + serialWrite(fportPort, phyID); + + uint16_t checksum = 0; + frskyCheckSumStep(&checksum, phyID); + uint8_t *data = (uint8_t *)payload; + for (unsigned i = 0; i < sizeof(smartPortPayload_t); ++i, ++data) { + serialWrite(fportPort, *data); + frskyCheckSumStep(&checksum, *data); + } + frskyCheckSumFini(&checksum); + serialWrite(fportPort, checksum); +} + +static void writeUplinkFrame(const smartPortPayload_t *payload) +{ + writeUplinkFramePhyID(FPORT2_FC_COMMON_ID, payload); +} +#endif + +static uint8_t frameStatus(rxRuntimeConfig_t *rxRuntimeConfig) +{ +#ifdef USE_TELEMETRY_SMARTPORT + static smartPortPayload_t payloadBuffer; + static bool hasTelemetryRequest = false; + static uint32_t otaPrevDataAddress; + static bool otaJustStarted = false; + static bool otaGotData = false; +#endif + static timeUs_t frameReceivedTimestamp = 0; + + uint8_t result = RX_FRAME_PENDING; + timeUs_t currentTimeUs = micros(); + + if (rxBufferReadIndex != rxBufferWriteIndex) { + + volatile uint8_t *buffer = rxBuffer[rxBufferReadIndex].data; + uint8_t buflen = rxBuffer[rxBufferReadIndex].length; + + fportFrame_t *frame = (fportFrame_t *)buffer; + + if (!frskyCheckSumIsGood((uint8_t *)buffer + 1, buflen - 1)) { + reportFrameError(DEBUG_FPORT2_ERROR_CHECKSUM); + } else { + + switch (frame->type) { + + case FT_CONTROL: + switch (frame->control.type) { + + case CFT_RC: + result = sbusChannelsDecode(rxRuntimeConfig, &frame->control.rc.channels); + lqTrackerSet(rxRuntimeConfig->lqTracker, scaleRange(frame->control.rc.rssi, 0, 100, 0, RSSI_MAX_VALUE)); + frameReceivedTimestamp = currentTimeUs; +#if defined(USE_TELEMETRY_SMARTPORT) + otaMode = false; +#endif + break; + +#if defined(USE_TELEMETRY_SMARTPORT) + case CFT_OTA_START: + otaMode = true; + break; + + case CFT_OTA_DATA: + if (otaMode) { + memcpy(otaDataBuffer, frame->control.ota, sizeof(otaDataBuffer)); + otaGotData = true; + } else { + reportFrameError(DEBUG_FPORT2_ERROR_TYPE); + } + break; + + case CFT_OTA_STOP: + if (!otaMode) { + reportFrameError(DEBUG_FPORT2_ERROR_TYPE); + } + break; +#endif + + default: + reportFrameError(DEBUG_FPORT2_ERROR_TYPE); + break; + + } + break; + + case FT_DOWNLINK: +#if defined(USE_TELEMETRY_SMARTPORT) + if (!telemetryEnabled) { + break; + } + + downlinkPhyID = frame->downlink.phyID; + uint8_t frameId = frame->downlink.telemetryData.frameId; + + switch (frameId) { + + case FPORT2_FRAME_ID_NULL: + hasTelemetryRequest = true; + sendNullFrame = true; + break; + + case FPORT2_FRAME_ID_DATA: + hasTelemetryRequest = true; + break; + + case FPORT2_FRAME_ID_OTA_START: + case FPORT2_FRAME_ID_OTA_DATA: + case FPORT2_FRAME_ID_OTA_STOP: + switch (frameId) { + case FPORT2_FRAME_ID_OTA_START: + if (otaMode) { + otaJustStarted = true; + otaPrevDataAddress = 0; + hasTelemetryRequest = true; + otaDataNeedsProcessing = false; + firmwareUpdateError = false; + } else { + reportFrameError(DEBUG_FPORT2_ERROR_TYPE); + } + break; + + case FPORT2_FRAME_ID_OTA_DATA: + if (otaMode) { + otaDataAddress = frame->downlink.telemetryData.data; + if (otaGotData && (otaDataAddress == (otaJustStarted ? 0 : otaPrevDataAddress + FPORT2_OTA_DATA_FRAME_BYTES))) { // check that we got a control frame with data and check address + otaPrevDataAddress = otaDataAddress; + otaGotData = false; + otaDataNeedsProcessing = true; + DEBUG_SET(DEBUG_FPORT, DEBUG_FPORT2_OTA_RECEIVED_BYTES, debug[DEBUG_FPORT2_OTA_RECEIVED_BYTES] + FPORT2_OTA_DATA_FRAME_BYTES); + } + hasTelemetryRequest = true; + otaJustStarted = false; + } else { + reportFrameError(DEBUG_FPORT2_ERROR_TYPE); + } + break; + + case FPORT2_FRAME_ID_OTA_STOP: + if (otaMode) { + hasTelemetryRequest = true; + } else { + reportFrameError(DEBUG_FPORT2_ERROR_TYPE); + } + break; + } + if (hasTelemetryRequest) { + memcpy(&payloadBuffer, &frame->downlink.telemetryData, sizeof(payloadBuffer)); + otaResponsePayload = &payloadBuffer; + } + break; + + default: + if ((frameId == FPORT2_FRAME_ID_READ) && (downlinkPhyID == FPORT2_FC_MSP_ID)) { + memcpy(&payloadBuffer, &frame->downlink.telemetryData, sizeof(payloadBuffer)); + mspPayload = &payloadBuffer; + hasTelemetryRequest = true; + } else if (downlinkPhyID != FPORT2_FC_COMMON_ID) { +#if defined(USE_SMARTPORT_MASTER) + int8_t smartportPhyID = smartportMasterStripPhyIDCheckBits(downlinkPhyID); + if (smartportPhyID != -1) { + smartportMasterForward(smartportPhyID, &frame->downlink.telemetryData); + hasTelemetryRequest = true; + } +#endif + } + break; + + } +#endif + break; + + default: + reportFrameError(DEBUG_FPORT2_ERROR_TYPE); + break; + + } + + } + + rxBufferReadIndex = (rxBufferReadIndex + 1) % NUM_RX_BUFFERS; + } + +#if defined(USE_TELEMETRY_SMARTPORT) + if (((mspPayload || hasTelemetryRequest) && cmpTimeUs(currentTimeUs, lastTelemetryFrameReceivedUs) >= FPORT2_MIN_TELEMETRY_RESPONSE_DELAY_US) + || (otaResponsePayload && cmpTimeUs(currentTimeUs, lastTelemetryFrameReceivedUs) >= FPORT2_MIN_OTA_RESPONSE_DELAY_US)) { + hasTelemetryRequest = false; + clearToSend = true; + result |= RX_FRAME_PROCESSING_REQUIRED; + } +#endif + + if (frameReceivedTimestamp && (cmpTimeUs(currentTimeUs, frameReceivedTimestamp) > FPORT2_MAX_TELEMETRY_AGE_MS * 1000)) { + lqTrackerSet(rxRuntimeConfig->lqTracker, 0); + frameReceivedTimestamp = 0; + } + +#ifdef MSP_FIRMWARE_UPDATE + if (readyToUpdateFirmwareTimestamp && (cmpTimeUs(currentTimeUs, readyToUpdateFirmwareTimestamp) > 2000000)) { + readyToUpdateFirmwareTimestamp = 0; + firmwareUpdateExec(firmwareUpdateCRC); + } +#endif + + return result; +} + +static bool processFrame(const rxRuntimeConfig_t *rxRuntimeConfig) +{ + UNUSED(rxRuntimeConfig); + +#if defined(USE_TELEMETRY_SMARTPORT) + static timeUs_t lastTelemetryFrameSentUs; + + timeUs_t currentTimeUs = micros(); + if (cmpTimeUs(currentTimeUs, lastTelemetryFrameReceivedUs) > FPORT2_MAX_TELEMETRY_RESPONSE_DELAY_US) { + clearToSend = false; + } + + if (clearToSend) { + if (otaResponsePayload) { + switch (otaResponsePayload->frameId) { + + case FPORT2_FRAME_ID_OTA_DATA: { + if (otaDataNeedsProcessing && !firmwareUpdateError) { // We have got fresh data +#ifdef MSP_FIRMWARE_UPDATE + static uint32_t firmwareUpdateSize; + uint32_t receivedSize = otaDataAddress - FPORT2_OTA_DATA_FRAME_BYTES; + if (otaDataAddress == 0) { + static firmwareUpdateHeader_t *header = (firmwareUpdateHeader_t *)otaDataBuffer; + firmwareUpdateSize = header->size; + firmwareUpdateCRC = header->crc; + firmwareUpdateError = !firmwareUpdatePrepare(firmwareUpdateSize); + } else if (receivedSize < firmwareUpdateSize) { + uint8_t firmwareDataSize = MIN((uint8_t)FPORT2_OTA_DATA_FRAME_BYTES, firmwareUpdateSize - receivedSize); + firmwareUpdateError = !firmwareUpdateStore(otaDataBuffer, firmwareDataSize); + } +#else + firmwareUpdateError = true; +#endif + } + otaDataNeedsProcessing = false; + break; + } + + case FPORT2_FRAME_ID_OTA_STOP: + otaMode = false; +#ifdef MSP_FIRMWARE_UPDATE + readyToUpdateFirmwareTimestamp = currentTimeUs; +#endif + break; + + } + + timeUs_t otaResponseTime = cmpTimeUs(micros(), otaFrameEndTimestamp); + if (!firmwareUpdateError && (otaResponseTime < 400)) { // We can answer in time (firmwareUpdateStore can take time because it might need to erase flash) + writeUplinkFramePhyID(downlinkPhyID, otaResponsePayload); + DEBUG_SET(DEBUG_FPORT, DEBUG_FPORT2_OTA_FRAME_RESPONSE_TIME, otaResponseTime); + } + + otaResponsePayload = NULL; + clearToSend = false; + + } else if ((downlinkPhyID == FPORT2_FC_COMMON_ID) || (downlinkPhyID == FPORT2_FC_MSP_ID)) { + if ((downlinkPhyID == FPORT2_FC_MSP_ID) && !mspPayload) { + clearToSend = false; + } else if (!sendNullFrame) { + processSmartPortTelemetry(mspPayload, &clearToSend, NULL); + mspPayload = NULL; + } + + } else { +#if defined(USE_SMARTPORT_MASTER) + int8_t smartportPhyID = smartportMasterStripPhyIDCheckBits(downlinkPhyID); + + if (smartportPhyID != -1) { + if (sendNullFrame) { + if (!smartportMasterPhyIDIsActive(smartportPhyID)) { // send null frame only if the sensor is active + clearToSend = false; + } + } else { + smartPortPayload_t forwardPayload; + if (smartportMasterNextForwardResponse(smartportPhyID, &forwardPayload) || smartportMasterGetSensorPayload(smartportPhyID, &forwardPayload)) { + writeUplinkFramePhyID(downlinkPhyID, &forwardPayload); + } + clearToSend = false; // either we answered or the sensor is not active, do not send null frame + } + } else { + clearToSend = false; + } +#else + clearToSend = false; +#endif + } + + if (clearToSend) { + writeUplinkFramePhyID(downlinkPhyID, &emptySmartPortFrame); + clearToSend = false; + } + + sendNullFrame = false; + + DEBUG_SET(DEBUG_FPORT, DEBUG_FPORT2_TELEMETRY_INTERVAL, currentTimeUs - lastTelemetryFrameSentUs); + lastTelemetryFrameSentUs = currentTimeUs; + + } +#endif + + return true; +} + + +bool fport2RxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig) +{ + static uint16_t sbusChannelData[SBUS_MAX_CHANNEL]; + rxRuntimeConfig->channelData = sbusChannelData; + sbusChannelsInit(rxRuntimeConfig); + + rxRuntimeConfig->channelCount = SBUS_MAX_CHANNEL; + rxRuntimeConfig->rxRefreshRate = 11000; + + rxRuntimeConfig->rcFrameStatusFn = frameStatus; + rxRuntimeConfig->rcProcessFrameFn = processFrame; + + const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL); + if (!portConfig) { + return false; + } + + fportPort = openSerialPort(portConfig->identifier, + FUNCTION_RX_SERIAL, + fportDataReceive, + NULL, + FPORT2_BAUDRATE, + MODE_RXTX, + FPORT2_PORT_OPTIONS | (rxConfig->serialrx_inverted ? 0 : SERIAL_INVERTED) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) + ); + + if (fportPort) { +#if defined(USE_TELEMETRY_SMARTPORT) + telemetryEnabled = initSmartPortTelemetryExternal(writeUplinkFrame); +#endif + + } + + return fportPort != NULL; +} + +#endif diff --git a/src/main/rx/fport2.h b/src/main/rx/fport2.h new file mode 100644 index 00000000000..589b51b8af7 --- /dev/null +++ b/src/main/rx/fport2.h @@ -0,0 +1,27 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software under the terms of the + * GNU General Public License as published by the Free Software + * Foundation, either version 3 of the License, or (at your option) + * any later version. + * + * Cleanflight and Betaflight are distributed in the hope that they + * will be useful, but WITHOUT ANY WARRANTY; without even the implied + * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this software. + * + * If not, see . + */ + +#pragma once + +#ifdef USE_SERIALRX_FPORT2 + +bool fport2RxInit(const rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig); + +#endif diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 8063cf08304..740a6050977 100755 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -54,6 +54,7 @@ #include "rx/ibus.h" #include "rx/jetiexbus.h" #include "rx/fport.h" +#include "rx/fport2.h" #include "rx/msp.h" #include "rx/msp_override.h" #include "rx/pwm.h" @@ -234,6 +235,11 @@ bool serialRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig case SERIALRX_FPORT: enabled = fportRxInit(rxConfig, rxRuntimeConfig); break; +#endif +#ifdef USE_SERIALRX_FPORT2 + case SERIALRX_FPORT2: + enabled = fport2RxInit(rxConfig, rxRuntimeConfig); + break; #endif default: enabled = false; diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index 4a64a730896..89523190e47 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -81,6 +81,7 @@ typedef enum { SERIALRX_CRSF = 9, SERIALRX_FPORT = 10, SERIALRX_SBUS_FAST = 11, + SERIALRX_FPORT2 = 12, } rxSerialReceiverType_e; #define MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT 16 diff --git a/src/main/target/common.h b/src/main/target/common.h index 08876545592..01a79e9b580 100755 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -33,6 +33,7 @@ #define USE_SERIALRX_SBUS // Very common protocol #define USE_SERIALRX_IBUS // Cheap FlySky & Turnigy receivers #define USE_SERIALRX_FPORT +#define USE_SERIALRX_FPORT2 #define COMMON_DEFAULT_FEATURES (FEATURE_TX_PROF_SEL) @@ -113,6 +114,7 @@ #define USE_TELEMETRY_SIM #define USE_FRSKYOSD #define USE_DJI_HD_OSD +#define USE_SMARTPORT_MASTER #define NAV_NON_VOLATILE_WAYPOINT_CLI From 9866553d85396432413820c2d05468b1ec5ac2aa Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Tue, 4 Aug 2020 12:01:03 +0200 Subject: [PATCH 122/248] Disable SPRACINGF3EVO target --- make/release.mk | 2 +- make/targets.mk | 2 +- .../{SPRACINGF3EVO_1SS.mk => SPRACINGF3EVO_1SS.mk_} | 0 src/main/target/SPRACINGF3EVO/{target.mk => target.mk_} | 0 4 files changed, 2 insertions(+), 2 deletions(-) rename src/main/target/SPRACINGF3EVO/{SPRACINGF3EVO_1SS.mk => SPRACINGF3EVO_1SS.mk_} (100%) rename src/main/target/SPRACINGF3EVO/{target.mk => target.mk_} (100%) diff --git a/make/release.mk b/make/release.mk index 792d2dbc699..a57a90f9b43 100644 --- a/make/release.mk +++ b/make/release.mk @@ -8,7 +8,7 @@ RELEASE_TARGETS += BETAFLIGHTF3 BETAFLIGHTF4 RELEASE_TARGETS += FF_F35_LIGHTNING FF_FORTINIF4 RELEASE_TARGETS += KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KAKUTEF7HDV -RELEASE_TARGETS += SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPRACINGF4EVO SPRACINGF7DUAL +RELEASE_TARGETS += SPRACINGF3 SPRACINGF3MINI SPRACINGF4EVO SPRACINGF7DUAL RELEASE_TARGETS += AIRBOTF4 ASGARD32F4 ASGARD32F7 FIREWORKSV2 AIRBOTF7 OMNIBUSF7NANOV7 RELEASE_TARGETS += OMNIBUSF4 OMNIBUSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 DYSF4PRO DYSF4PROV2 diff --git a/make/targets.mk b/make/targets.mk index fcec9980457..7b13c86e239 100644 --- a/make/targets.mk +++ b/make/targets.mk @@ -72,7 +72,7 @@ $(error Unknown target MCU specified.) endif GROUP_1_TARGETS := AIRHEROF3 AIRHEROF3_QUAD LUX_RACE SPARKY REVO SPARKY2 COLIBRI FALCORE FF_F35_LIGHTNING FF_FORTINIF4 FF_PIKOF4 FF_PIKOF4OSD -GROUP_2_TARGETS := SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPRACINGF4EVO CLRACINGF4AIR CLRACINGF4AIRV2 BEEROTORF4 BETAFLIGHTF3 BETAFLIGHTF4 PIKOBLX +GROUP_2_TARGETS := SPRACINGF3 SPRACINGF3MINI SPRACINGF4EVO CLRACINGF4AIR CLRACINGF4AIRV2 BEEROTORF4 BETAFLIGHTF3 BETAFLIGHTF4 PIKOBLX GROUP_3_TARGETS := AIRBOTF4 BLUEJAYF4 OMNIBUSF4 OMNIBUSF4PRO FIREWORKSV2 SPARKY2 MATEKF405 OMNIBUSF7 DYSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 OMNIBUSF7NXT OMNIBUSF7V2 ASGARD32F4 GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ALIENFLIGHTNGF7 PIXRACER YUPIF7 MATEKF405SE MATEKF411 MATEKF722 MATEKF405OSD MATEKF405_SERVOS6 NOX GROUP_5_TARGETS := ASGARD32F7 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF3 FURYF3_SPIFLASH FURYF4OSD diff --git a/src/main/target/SPRACINGF3EVO/SPRACINGF3EVO_1SS.mk b/src/main/target/SPRACINGF3EVO/SPRACINGF3EVO_1SS.mk_ similarity index 100% rename from src/main/target/SPRACINGF3EVO/SPRACINGF3EVO_1SS.mk rename to src/main/target/SPRACINGF3EVO/SPRACINGF3EVO_1SS.mk_ diff --git a/src/main/target/SPRACINGF3EVO/target.mk b/src/main/target/SPRACINGF3EVO/target.mk_ similarity index 100% rename from src/main/target/SPRACINGF3EVO/target.mk rename to src/main/target/SPRACINGF3EVO/target.mk_ From a56a25ae9de13cfec9080aad96d0d0f57208b130 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Tue, 4 Aug 2020 13:04:48 +0200 Subject: [PATCH 123/248] Disable FURYF3 target --- make/release.mk | 2 +- make/targets.mk | 2 +- .../target/FURYF3/{FURYF3_SPIFLASH.mk => FURYF3_SPIFLASH.mk_} | 0 src/main/target/FURYF3/{target.mk => target.mk_} | 0 4 files changed, 2 insertions(+), 2 deletions(-) rename src/main/target/FURYF3/{FURYF3_SPIFLASH.mk => FURYF3_SPIFLASH.mk_} (100%) rename src/main/target/FURYF3/{target.mk => target.mk_} (100%) diff --git a/make/release.mk b/make/release.mk index a57a90f9b43..10ab5a848e5 100644 --- a/make/release.mk +++ b/make/release.mk @@ -1,6 +1,6 @@ RELEASE_TARGETS = AIRHEROF3 AIRHEROF3_QUAD -RELEASE_TARGETS += LUX_RACE FURYF3 FURYF3_SPIFLASH RCEXPLORERF3 RMDO SPARKY KFC32F3_INAV FALCORE MOTOLAB ANYFC BLUEJAYF4 COLIBRI F4BY DALRCF405 DALRCF722DUAL +RELEASE_TARGETS += LUX_RACE RCEXPLORERF3 RMDO SPARKY KFC32F3_INAV FALCORE MOTOLAB ANYFC BLUEJAYF4 COLIBRI F4BY DALRCF405 DALRCF722DUAL RELEASE_TARGETS += QUANTON REVO SPARKY2 PIKOBLX CLRACINGF4AIR CLRACINGF4AIRV2 PIXRACER BEEROTORF4 ANYFCF7 ANYFCF7_EXTERNAL_BARO RELEASE_TARGETS += ALIENFLIGHTNGF7 diff --git a/make/targets.mk b/make/targets.mk index 7b13c86e239..b3d1110965f 100644 --- a/make/targets.mk +++ b/make/targets.mk @@ -75,7 +75,7 @@ GROUP_1_TARGETS := AIRHEROF3 AIRHEROF3_QUAD LUX_RACE SPARKY REVO SPARKY2 COLIBRI GROUP_2_TARGETS := SPRACINGF3 SPRACINGF3MINI SPRACINGF4EVO CLRACINGF4AIR CLRACINGF4AIRV2 BEEROTORF4 BETAFLIGHTF3 BETAFLIGHTF4 PIKOBLX GROUP_3_TARGETS := AIRBOTF4 BLUEJAYF4 OMNIBUSF4 OMNIBUSF4PRO FIREWORKSV2 SPARKY2 MATEKF405 OMNIBUSF7 DYSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 OMNIBUSF7NXT OMNIBUSF7V2 ASGARD32F4 GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ALIENFLIGHTNGF7 PIXRACER YUPIF7 MATEKF405SE MATEKF411 MATEKF722 MATEKF405OSD MATEKF405_SERVOS6 NOX -GROUP_5_TARGETS := ASGARD32F7 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF3 FURYF3_SPIFLASH FURYF4OSD +GROUP_5_TARGETS := ASGARD32F7 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF4OSD GROUP_6_TARGETS := MAMBAF405 OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS AIKONF4 GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KFC32F3_INAV MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO GROUP_8_TARGETS := MATEKF765 MATEKF722PX KAKUTEF7HDV ZEEZF7 FOXEERF722V2 diff --git a/src/main/target/FURYF3/FURYF3_SPIFLASH.mk b/src/main/target/FURYF3/FURYF3_SPIFLASH.mk_ similarity index 100% rename from src/main/target/FURYF3/FURYF3_SPIFLASH.mk rename to src/main/target/FURYF3/FURYF3_SPIFLASH.mk_ diff --git a/src/main/target/FURYF3/target.mk b/src/main/target/FURYF3/target.mk_ similarity index 100% rename from src/main/target/FURYF3/target.mk rename to src/main/target/FURYF3/target.mk_ From 64fa696944f9f0ee0a6ae1568102a253e704b796 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Mon, 8 Jun 2020 10:08:18 +0200 Subject: [PATCH 124/248] Add target for FrSky's R9 Pilot F765 fixed wing flight controller --- src/main/target/R9_PILOT/config.c | 29 ++++ src/main/target/R9_PILOT/target.c | 49 +++++++ src/main/target/R9_PILOT/target.h | 205 +++++++++++++++++++++++++++++ src/main/target/R9_PILOT/target.mk | 15 +++ 4 files changed, 298 insertions(+) create mode 100644 src/main/target/R9_PILOT/config.c create mode 100644 src/main/target/R9_PILOT/target.c create mode 100644 src/main/target/R9_PILOT/target.h create mode 100644 src/main/target/R9_PILOT/target.mk diff --git a/src/main/target/R9_PILOT/config.c b/src/main/target/R9_PILOT/config.c new file mode 100644 index 00000000000..bea124aa9f3 --- /dev/null +++ b/src/main/target/R9_PILOT/config.c @@ -0,0 +1,29 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include + +#include + +#include "io/serial.h" + +void targetConfiguration(void) +{ + serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_TELEMETRY_SMARTPORT_MASTER; + serialConfigMutable()->portConfigs[5].functionMask = FUNCTION_FRSKY_OSD; +} diff --git a/src/main/target/R9_PILOT/target.c b/src/main/target/R9_PILOT/target.c new file mode 100644 index 00000000000..164e4b15cc5 --- /dev/null +++ b/src/main/target/R9_PILOT/target.c @@ -0,0 +1,49 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/pinio.h" +#include "drivers/sensor.h" + +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, MPU6500_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); +BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); + +const timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_SERVO | TIM_USE_FW_MOTOR, 0, 0), + DEF_TIM(TIM1, CH1, PE9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM1, CH2, PE11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM1, CH3, PE13, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM1, CH4, PE14, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM4, CH4, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), + + DEF_TIM(TIM5, CH1, PA0, TIM_USE_BEEPER, 0, 0), // beeper +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/R9_PILOT/target.h b/src/main/target/R9_PILOT/target.h new file mode 100644 index 00000000000..f4ba9ab27b4 --- /dev/null +++ b/src/main/target/R9_PILOT/target.h @@ -0,0 +1,205 @@ +/* + * This file is part of INAV. + * + * INAV is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * INAV is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with INAV. If not, see . + */ + + +#pragma once + +#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS +#define USE_TARGET_CONFIG + +#define TARGET_BOARD_IDENTIFIER "R9P" +#define USBD_PRODUCT_STRING "R9PILOT" + +#define LED0 PA3 +#define LED1 PC5 + +#define BEEPER PA0 +#define BEEPER_INVERTED +#define BEEPER_PWM +#define BEEPER_PWM_FREQUENCY 4000 + +#define USE_SPI + +// *************** SPI1 BARO ********************** + +#define USE_SPI_DEVICE_1 +#define SPI1_NSS_PIN PA4 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_BARO +#define USE_BARO_SPL06 +#define SPL06_SPI_BUS BUS_SPI1 +#define SPL06_CS_PIN SPI1_NSS_PIN + +// *************** SPI2/3 IMUs ******************* + +// IMU box +#define USE_SPI_DEVICE_2 +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +// IMU on-board +#define USE_SPI_DEVICE_3 +#define SPI3_NSS_PIN PA15 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 + +#define USE_TARGET_IMU_HARDWARE_DESCRIPTORS + +#define USE_IMU_MPU6000 +#define USE_IMU_MPU6500 + +#define USE_EXTI +#define USE_MPU_DATA_READY_SIGNAL + +//#define USE_ONBOARD_IMU +//#define USE_BOX_IMU +#define USE_DUAL_GYRO + +//#if defined(USE_ONBOARD_IMU) +#define MPU6500_EXTI_PIN PE8 +#define MPU6500_SPI_BUS BUS_SPI3 +#define MPU6500_CS_PIN SPI3_NSS_PIN +#define IMU_MPU6500_ALIGN CW270_DEG_FLIP // XXX check + +//#elif defined(USE_BOX_IMU) +#define MPU6000_EXTI_PIN NONE +#define MPU6000_SPI_BUS BUS_SPI2 +#define MPU6000_CS_PIN SPI2_NSS_PIN +#define IMU_MPU6000_ALIGN CW270_DEG_FLIP // XXX check + +//#endif // IMU SELECTION + +// *************** SPI4: SDCARD ******************* + +#define USE_SPI_DEVICE_4 +#define SPI4_NSS_PIN PE4 +#define SPI4_SCK_PIN PE2 +#define SPI4_MISO_PIN PE5 +#define SPI4_MOSI_PIN PE6 + +#define USE_SDCARD +#define USE_SDCARD_SPI +#define SDCARD_SPI_BUS BUS_SPI4 +#define SDCARD_CS_PIN SPI4_NSS_PIN +#define SDCARD_DETECT_PIN PE3 +#define SDCARD_DETECT_INVERTED + +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +// *************** I2C ********************* +#define USE_I2C + +#define USE_I2C_DEVICE_3 +#define I2C3_SCL PA8 +#define I2C3_SDA PC9 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C3 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +#define TEMPERATURE_I2C_BUS BUS_I2C3 + +#define PITOT_I2C_BUS BUS_I2C3 + +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS BUS_I2C3 + +// *************** UART ***************************** +#define USE_VCP +#define USB_DETECT_PIN PC4 +#define USE_USB_DETECT + +#define USE_UART1 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 + +#define USE_UART2 +#define UART2_TX_PIN PD5 +#define UART2_RX_PIN PD6 + +#define USE_UART3 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 + +#define USE_UART5 +#define UART5_TX_PIN PB6 +#define UART5_RX_PIN PB5 +#define UART5_AF 1 + +// OSD +#define USE_OSD +#define USE_UART6 +#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 + +// RX connector +#define USE_UART7 +#define UART7_TX_PIN PB4 +#define UART7_RX_PIN PB3 +#define UART7_AF 12 + +#define USE_UART8 +#define UART8_TX_PIN PE1 +#define UART8_RX_PIN PE0 + +#define SERIAL_PORT_COUNT 8 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART8 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 + +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC3 +#define ADC_CHANNEL_3_PIN PC1 +#define ADC_CHANNEL_4_PIN PC0 + +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 +#define VBAT_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 +#define AIRSPEED_ADC_CHANNEL ADC_CHN_4 + +#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) +#define VBAT_SCALE_DEFAULT 1545 +#define CURRENT_METER_SCALE 168 +#define CURRENT_METER_OFFSET 3277 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff + +#define MAX_PWM_OUTPUT_PORTS 12 + +#define USE_DSHOT diff --git a/src/main/target/R9_PILOT/target.mk b/src/main/target/R9_PILOT/target.mk new file mode 100644 index 00000000000..0208f36d3f8 --- /dev/null +++ b/src/main/target/R9_PILOT/target.mk @@ -0,0 +1,15 @@ +F765XG_TARGETS += $(TARGET) +FEATURES += SDCARD VCP + +TARGET_SRC = \ + drivers/accgyro/accgyro_mpu6000.c \ + drivers/accgyro/accgyro_mpu6500.c \ + drivers/barometer/barometer_spl06.c \ + drivers/compass/compass_hmc5883l.c \ + drivers/compass/compass_qmc5883l.c \ + drivers/compass/compass_ist8310.c \ + drivers/compass/compass_ist8308.c \ + drivers/compass/compass_mag3110.c \ + drivers/compass/compass_lis3mdl.c \ + drivers/pitotmeter_adc.c \ + From 154a8ee838634ec84804e8b8969fdd0ec727f435 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Fri, 7 Aug 2020 12:09:33 +0100 Subject: [PATCH 125/248] [R9PILOT] Use SERIAL_PORT_xxx for target configuration --- src/main/target/R9_PILOT/config.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/target/R9_PILOT/config.c b/src/main/target/R9_PILOT/config.c index bea124aa9f3..66642153eaf 100644 --- a/src/main/target/R9_PILOT/config.c +++ b/src/main/target/R9_PILOT/config.c @@ -24,6 +24,6 @@ void targetConfiguration(void) { - serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_TELEMETRY_SMARTPORT_MASTER; - serialConfigMutable()->portConfigs[5].functionMask = FUNCTION_FRSKY_OSD; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_TELEMETRY_SMARTPORT_MASTER; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART5)].functionMask = FUNCTION_FRSKY_OSD; } From 84f3774ef9bbd7c52141cb338e4579550f93c73b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Fri, 7 Aug 2020 12:16:52 +0100 Subject: [PATCH 126/248] [TARGETS] Rename R9_PILOT to FRSKYPILOT --- src/main/target/{R9_PILOT => FRSKYPILOT}/config.c | 0 src/main/target/{R9_PILOT => FRSKYPILOT}/target.c | 0 src/main/target/{R9_PILOT => FRSKYPILOT}/target.h | 4 ++-- src/main/target/{R9_PILOT => FRSKYPILOT}/target.mk | 5 ++--- 4 files changed, 4 insertions(+), 5 deletions(-) rename src/main/target/{R9_PILOT => FRSKYPILOT}/config.c (100%) rename src/main/target/{R9_PILOT => FRSKYPILOT}/target.c (100%) rename src/main/target/{R9_PILOT => FRSKYPILOT}/target.h (98%) rename src/main/target/{R9_PILOT => FRSKYPILOT}/target.mk (84%) diff --git a/src/main/target/R9_PILOT/config.c b/src/main/target/FRSKYPILOT/config.c similarity index 100% rename from src/main/target/R9_PILOT/config.c rename to src/main/target/FRSKYPILOT/config.c diff --git a/src/main/target/R9_PILOT/target.c b/src/main/target/FRSKYPILOT/target.c similarity index 100% rename from src/main/target/R9_PILOT/target.c rename to src/main/target/FRSKYPILOT/target.c diff --git a/src/main/target/R9_PILOT/target.h b/src/main/target/FRSKYPILOT/target.h similarity index 98% rename from src/main/target/R9_PILOT/target.h rename to src/main/target/FRSKYPILOT/target.h index f4ba9ab27b4..a4579a09adf 100644 --- a/src/main/target/R9_PILOT/target.h +++ b/src/main/target/FRSKYPILOT/target.h @@ -21,8 +21,8 @@ #define USE_TARGET_IMU_HARDWARE_DESCRIPTORS #define USE_TARGET_CONFIG -#define TARGET_BOARD_IDENTIFIER "R9P" -#define USBD_PRODUCT_STRING "R9PILOT" +#define TARGET_BOARD_IDENTIFIER "FRP" +#define USBD_PRODUCT_STRING "FrSkyPilot" #define LED0 PA3 #define LED1 PC5 diff --git a/src/main/target/R9_PILOT/target.mk b/src/main/target/FRSKYPILOT/target.mk similarity index 84% rename from src/main/target/R9_PILOT/target.mk rename to src/main/target/FRSKYPILOT/target.mk index 0208f36d3f8..8147748f123 100644 --- a/src/main/target/R9_PILOT/target.mk +++ b/src/main/target/FRSKYPILOT/target.mk @@ -4,12 +4,11 @@ FEATURES += SDCARD VCP TARGET_SRC = \ drivers/accgyro/accgyro_mpu6000.c \ drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_spl06.c \ + drivers/barometer/barometer_spl06.c \ drivers/compass/compass_hmc5883l.c \ drivers/compass/compass_qmc5883l.c \ drivers/compass/compass_ist8310.c \ drivers/compass/compass_ist8308.c \ drivers/compass/compass_mag3110.c \ drivers/compass/compass_lis3mdl.c \ - drivers/pitotmeter_adc.c \ - + drivers/pitotmeter_adc.c From 06c804ad98892092eeb2a0cdb695fbcbc5ce0955 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Fri, 7 Aug 2020 14:04:42 +0100 Subject: [PATCH 127/248] [FRSKYPILOT] Update default IMU orientation for final board design --- src/main/target/FRSKYPILOT/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/FRSKYPILOT/target.h b/src/main/target/FRSKYPILOT/target.h index a4579a09adf..4d5181abf51 100644 --- a/src/main/target/FRSKYPILOT/target.h +++ b/src/main/target/FRSKYPILOT/target.h @@ -79,7 +79,7 @@ #define MPU6500_EXTI_PIN PE8 #define MPU6500_SPI_BUS BUS_SPI3 #define MPU6500_CS_PIN SPI3_NSS_PIN -#define IMU_MPU6500_ALIGN CW270_DEG_FLIP // XXX check +#define IMU_MPU6500_ALIGN CW0_DEG_FLIP //#elif defined(USE_BOX_IMU) #define MPU6000_EXTI_PIN NONE From 40f4320a4420dc27797ad85a9b4758b5e050f5f1 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Mon, 10 Aug 2020 19:36:12 +0200 Subject: [PATCH 128/248] [FRSKYPILOT] Set serialrx_inverted to ON by default --- src/main/target/FRSKYPILOT/config.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/main/target/FRSKYPILOT/config.c b/src/main/target/FRSKYPILOT/config.c index 66642153eaf..2545ff06035 100644 --- a/src/main/target/FRSKYPILOT/config.c +++ b/src/main/target/FRSKYPILOT/config.c @@ -21,9 +21,12 @@ #include #include "io/serial.h" +#include "rx/rx.h" void targetConfiguration(void) { serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_TELEMETRY_SMARTPORT_MASTER; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART5)].functionMask = FUNCTION_FRSKY_OSD; + + rxConfigMutable()->serialrx_inverted = 1; } From 3a1e84882e61755053f3707991a29208b840c48a Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Tue, 11 Aug 2020 18:06:15 +0200 Subject: [PATCH 129/248] [FRSKYPILOT] Add to releases --- make/release.mk | 2 ++ make/targets.mk | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/make/release.mk b/make/release.mk index 10ab5a848e5..46153676805 100644 --- a/make/release.mk +++ b/make/release.mk @@ -37,3 +37,5 @@ RELEASE_TARGETS += AIKONF4 RELEASE_TARGETS += ZEEZF7 HGLRCF722 RELEASE_TARGETS += FLYWOOF7DUAL FLYWOOF411 + +RELEASE_TARGETS += FRSKYPILOT diff --git a/make/targets.mk b/make/targets.mk index b3d1110965f..9133fe9fc5d 100644 --- a/make/targets.mk +++ b/make/targets.mk @@ -78,7 +78,7 @@ GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ALIENFLIGHTNGF7 PIXRACER GROUP_5_TARGETS := ASGARD32F7 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF4OSD GROUP_6_TARGETS := MAMBAF405 OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS AIKONF4 GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KFC32F3_INAV MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO -GROUP_8_TARGETS := MATEKF765 MATEKF722PX KAKUTEF7HDV ZEEZF7 FOXEERF722V2 +GROUP_8_TARGETS := MATEKF765 MATEKF722PX KAKUTEF7HDV ZEEZF7 FOXEERF722V2 FRSKYPILOT GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS) $(GROUP_3_TARGETS) $(GROUP_4_TARGETS) $(GROUP_5_TARGETS) $(GROUP_6_TARGETS) $(GROUP_7_TARGETS) $(GROUP_8_TARGETS), $(VALID_TARGETS)) ## targets-group-1 : build some targets From a9120cbdbf089a1402d6dbdd766557ebffebc0f1 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Tue, 7 Jul 2020 17:58:05 +0200 Subject: [PATCH 130/248] Add target for FrSky's ROVERF7 FC --- make/release.mk | 4 +- make/targets.mk | 2 +- src/main/target/FRSKY_ROVERF7/target.c | 38 ++++++ src/main/target/FRSKY_ROVERF7/target.h | 154 ++++++++++++++++++++++++ src/main/target/FRSKY_ROVERF7/target.mk | 17 +++ 5 files changed, 213 insertions(+), 2 deletions(-) create mode 100755 src/main/target/FRSKY_ROVERF7/target.c create mode 100755 src/main/target/FRSKY_ROVERF7/target.h create mode 100755 src/main/target/FRSKY_ROVERF7/target.mk diff --git a/make/release.mk b/make/release.mk index 46153676805..b00ac8b4bc1 100644 --- a/make/release.mk +++ b/make/release.mk @@ -38,4 +38,6 @@ RELEASE_TARGETS += ZEEZF7 HGLRCF722 RELEASE_TARGETS += FLYWOOF7DUAL FLYWOOF411 -RELEASE_TARGETS += FRSKYPILOT +RELEASE_TARGETS += ZEEZF7 + +RELEASE_TARGETS += FRSKYPILOT FRSKY_ROVERF7 diff --git a/make/targets.mk b/make/targets.mk index 9133fe9fc5d..c725539ea6c 100644 --- a/make/targets.mk +++ b/make/targets.mk @@ -78,7 +78,7 @@ GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ALIENFLIGHTNGF7 PIXRACER GROUP_5_TARGETS := ASGARD32F7 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF4OSD GROUP_6_TARGETS := MAMBAF405 OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS AIKONF4 GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KFC32F3_INAV MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO -GROUP_8_TARGETS := MATEKF765 MATEKF722PX KAKUTEF7HDV ZEEZF7 FOXEERF722V2 FRSKYPILOT +GROUP_8_TARGETS := MATEKF765 MATEKF722PX KAKUTEF7HDV ZEEZF7 FOXEERF722V2 FRSKYPILOT FRSKY_ROVERF7 GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS) $(GROUP_3_TARGETS) $(GROUP_4_TARGETS) $(GROUP_5_TARGETS) $(GROUP_6_TARGETS) $(GROUP_7_TARGETS) $(GROUP_8_TARGETS), $(VALID_TARGETS)) ## targets-group-1 : build some targets diff --git a/src/main/target/FRSKY_ROVERF7/target.c b/src/main/target/FRSKY_ROVERF7/target.c new file mode 100755 index 00000000000..54910c83ef0 --- /dev/null +++ b/src/main/target/FRSKY_ROVERF7/target.c @@ -0,0 +1,38 @@ +/* +* This file is part of INAV. +* +* INAV is free software: you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation, either version 3 of the License, or +* (at your option) any later version. +* +* INAV is distributed in the hope that it will be useful, +* but WITHOUT ANY WARRANTY; without even the implied warranty of +* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +* GNU General Public License for more details. +* +* You should have received a copy of the GNU General Public License +* along with INAV. If not, see . +*/ + +#include + +#include "platform.h" + +#include "drivers/bus.h" +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" + +const timerHardware_t timerHardware[] = { + DEF_TIM(TIM3, CH3, PC8, TIM_USE_MC_MOTOR, 0, 0), // M1 + DEF_TIM(TIM3, CH4, PC9, TIM_USE_MC_MOTOR, 0, 0), // M2 + DEF_TIM(TIM1, CH2N, PB0, TIM_USE_MC_MOTOR, 0, 0), // M3 + + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MC_SERVO, 0, 0), // Servo left + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MC_SERVO, 0, 0), // Servo right + + DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // LED +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/FRSKY_ROVERF7/target.h b/src/main/target/FRSKY_ROVERF7/target.h new file mode 100755 index 00000000000..30955d0bfd7 --- /dev/null +++ b/src/main/target/FRSKY_ROVERF7/target.h @@ -0,0 +1,154 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +#define TARGET_BOARD_IDENTIFIER "RVF7" + +#define USBD_PRODUCT_STRING "ROVERF7" + +#define LED0 PA3 + +#define BEEPER PB2 +#define BEEPER_INVERTED + +// *************** Gyro & ACC ********************** +#define USE_SPI +#define USE_SPI_DEVICE_1 + +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW0_DEG +#define MPU6000_CS_PIN PC4 +#define MPU6000_SPI_BUS BUS_SPI1 + +#define USE_EXTI +#define GYRO_INT_EXTI PA4 +#define USE_MPU_DATA_READY_SIGNAL + + +// *************** I2C/Baro/Mag ********************* +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB8 // SCL pad +#define I2C1_SDA PB9 // SDA pad + +#define USE_BARO +#define BARO_I2C_BUS BUS_I2C1 +#define USE_BARO_BMP280 +#define USE_BARO_MS5611 +#define USE_BARO_BMP085 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_MAG3110 +#define USE_MAG_LIS3MDL + +#define TEMPERATURE_I2C_BUS BUS_I2C1 + +#define PITOT_I2C_BUS BUS_I2C1 + +// *************** SPI2 Flash *********************** +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define M25P16_SPI_BUS BUS_SPI2 +#define M25P16_CS_PIN PB12 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +// *************** OSD ***************************** +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +#define USE_OSD +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI3 +#define MAX7456_CS_PIN PD2 + +// *************** UART ***************************** +#define USE_VCP +//#define VBUS_SENSING_PIN PB12 +//#define VBUS_SENSING_ENABLED + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART2 +#define UART2_RX_PIN NONE +#define UART2_TX_PIN PA2 + +#define USE_UART3 +#define UART3_RX_PIN PC11 +#define UART3_TX_PIN PC10 + +#define USE_UART4 +#define UART4_RX_PIN NONE +#define UART4_TX_PIN PA0 + +#define USE_UART5 +#define UART5_RX_PIN NONE +#define UART5_TX_PIN PC12 + +#define SERIAL_PORT_COUNT 6 + +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_PROVIDER SERIALRX_FPORT +#define SERIALRX_UART SERIAL_PORT_USART1 + +// *************** ADC ***************************** +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define ADC1_DMA_STREAM DMA2_Stream0 +#define ADC_CHANNEL_1_PIN PC0 +#define ADC_CHANNEL_2_PIN PC1 +#define VBAT_ADC_CHANNEL ADC_CHN_1 +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2 +#define CURRENT_METER_SCALE 1790 + +#define USE_RANGEFINDER +#define RANGEFINDER_I2C_BUS BUS_I2C1 + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_CURRENT_METER | FEATURE_TELEMETRY| FEATURE_VBAT | FEATURE_OSD ) + +#define USE_LED_STRIP +#define WS2811_PIN PA15 //TIM2_CH1 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff + +#define MAX_PWM_OUTPUT_PORTS 5 +#define USE_DSHOT +#define USE_ESC_SENSOR +#define USE_SERIALSHOT diff --git a/src/main/target/FRSKY_ROVERF7/target.mk b/src/main/target/FRSKY_ROVERF7/target.mk new file mode 100755 index 00000000000..b1677ea5fdc --- /dev/null +++ b/src/main/target/FRSKY_ROVERF7/target.mk @@ -0,0 +1,17 @@ +F7X2RE_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH MSC + +TARGET_SRC = \ + drivers/accgyro/accgyro_mpu6000.c \ + drivers/barometer/barometer_bmp085.c \ + drivers/barometer/barometer_bmp280.c \ + drivers/barometer/barometer_ms56xx.c \ + drivers/compass/compass_ak8975.c \ + drivers/compass/compass_hmc5883l.c \ + drivers/compass/compass_qmc5883l.c \ + drivers/compass/compass_ist8310.c \ + drivers/compass/compass_ist8308.c \ + drivers/compass/compass_mag3110.c \ + drivers/compass/compass_lis3mdl.c \ + drivers/max7456.c \ + drivers/light_ws2811strip.c \ From 617a3a04bbb1dcf263d50dbb0176032fb427f893 Mon Sep 17 00:00:00 2001 From: "Qiusen \"Will\" Huang" <32228070+qwhcr@users.noreply.github.com> Date: Tue, 11 Aug 2020 13:25:59 -0400 Subject: [PATCH 131/248] [no risk] fix typo in max7456.c (#6039) --- src/main/drivers/max7456.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/max7456.c b/src/main/drivers/max7456.c index 1a88a792bab..588d77167d4 100644 --- a/src/main/drivers/max7456.c +++ b/src/main/drivers/max7456.c @@ -483,7 +483,7 @@ void max7456Write(uint8_t x, uint8_t y, const char *buff, uint8_t mode) } } -// Must be called with the lock held. Returns wether any new characters +// Must be called with the lock held. Returns whether any new characters // were drawn. static bool max7456DrawScreenPartial(void) { From cde13120ae276a182300fa36f6efc5d747b0a92f Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Wed, 12 Aug 2020 17:08:02 +0200 Subject: [PATCH 132/248] Take into account video aspect ratio when drawing AHI (#5962) --- src/main/io/osd.c | 8 ++++++-- src/main/io/osd.h | 1 + src/main/io/osd_grid.c | 17 ++++++++++++----- 3 files changed, 19 insertions(+), 7 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 29bdaedd902..0e45860759d 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -110,7 +110,6 @@ FILE_COMPILE_FOR_SPEED #endif #define VIDEO_BUFFER_CHARS_PAL 480 -#define IS_DISPLAY_PAL (displayScreenSize(osdDisplayPort) == VIDEO_BUFFER_CHARS_PAL) #define GFORCE_FILTER_TC 0.2 @@ -201,6 +200,11 @@ static int digitCount(int32_t value) return digits; } +bool osdDisplayIsPAL(void) +{ + return displayScreenSize(osdDisplayPort) == VIDEO_BUFFER_CHARS_PAL; +} + /** * Formats a number given in cents, to support non integer values * without using floating point math. Value is always right aligned @@ -2874,7 +2878,7 @@ static void osdShowStats(void) displayBeginTransaction(osdDisplayPort, DISPLAY_TRANSACTION_OPT_RESET_DRAWING); displayClearScreen(osdDisplayPort); - if (IS_DISPLAY_PAL) + if (osdDisplayIsPAL()) displayWrite(osdDisplayPort, statNameX, top++, " --- STATS ---"); if (STATE(GPS_FIX)) { diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 6415b7530b4..f1510ac41ba 100755 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -280,6 +280,7 @@ typedef struct displayPort_s displayPort_t; typedef struct displayCanvas_s displayCanvas_t; void osdInit(displayPort_t *osdDisplayPort); +bool osdDisplayIsPAL(void); void osdUpdate(timeUs_t currentTimeUs); void osdStartFullRedraw(void); // Sets a fixed OSD layout ignoring the RC input. Set it diff --git a/src/main/io/osd_grid.c b/src/main/io/osd_grid.c index 26a1c643389..fe8124b970d 100644 --- a/src/main/io/osd_grid.c +++ b/src/main/io/osd_grid.c @@ -34,6 +34,7 @@ #include "common/utils.h" #include "drivers/display.h" +#include "drivers/osd.h" #include "drivers/osd_symbols.h" #include "drivers/time.h" @@ -103,6 +104,11 @@ void osdGridDrawDirArrow(displayPort_t *display, unsigned gx, unsigned gy, float displayWriteChar(display, gx, gy, SYM_ARROW_UP + arrowOffset); } +static float osdGetAspectRatioCorrection(void) +{ + return osdDisplayIsPAL() ? 12.0f/15.0f : 12.0f/18.46f; +} + void osdGridDrawArtificialHorizon(displayPort_t *display, unsigned gx, unsigned gy, float pitchAngle, float rollAngle) { UNUSED(gx); @@ -117,10 +123,11 @@ void osdGridDrawArtificialHorizon(displayPort_t *display, unsigned gx, unsigned static int8_t previous_written[OSD_AHI_PREV_SIZE]; static int8_t previous_orient = -1; - float pitch_rad_to_char = (float)(OSD_AHI_HEIGHT / 2 + 0.5) / DEGREES_TO_RADIANS(osdConfig()->ahi_max_pitch); + const float pitch_rad_to_char = (float)(OSD_AHI_HEIGHT / 2 + 0.5) / DEGREES_TO_RADIANS(osdConfig()->ahi_max_pitch); - float ky = sin_approx(rollAngle); - float kx = cos_approx(rollAngle); + const float ky = sin_approx(rollAngle); + const float kx = cos_approx(rollAngle); + const float ratio = osdGetAspectRatioCorrection(); if (previous_orient != -1) { for (int i = 0; i < OSD_AHI_PREV_SIZE; ++i) { @@ -138,7 +145,7 @@ void osdGridDrawArtificialHorizon(displayPort_t *display, unsigned gx, unsigned previous_orient = 0; for (int8_t dx = -OSD_AHI_WIDTH / 2; dx <= OSD_AHI_WIDTH / 2; dx++) { - float fy = dx * (ky / kx) + pitchAngle * pitch_rad_to_char + 0.49f; + float fy = (ratio * dx) * (ky / kx) + pitchAngle * pitch_rad_to_char + 0.49f; int8_t dy = floorf(fy); const uint8_t chX = elemPosX + dx, chY = elemPosY - dy; uint16_t c; @@ -155,7 +162,7 @@ void osdGridDrawArtificialHorizon(displayPort_t *display, unsigned gx, unsigned previous_orient = 1; for (int8_t dy = -OSD_AHI_HEIGHT / 2; dy <= OSD_AHI_HEIGHT / 2; dy++) { - const float fx = (dy - pitchAngle * pitch_rad_to_char) * (kx / ky) + 0.5f; + const float fx = ((dy / ratio) - pitchAngle * pitch_rad_to_char) * (kx / ky) + 0.5f; const int8_t dx = floorf(fx); const uint8_t chX = elemPosX + dx, chY = elemPosY - dy; uint16_t c; From 4ea9a5f74a29cd25fed65d99f5a0d32724d6e6c9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Wed, 12 Aug 2020 22:48:38 +0100 Subject: [PATCH 133/248] [OSD] Fix default value for osd_sidebar_horizontal_offset Default value should be zero, otherwise the sidebars are always drawn at the edges of the screen. --- src/main/io/osd.c | 1 - 1 file changed, 1 deletion(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 0e45860759d..945acbf6354 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2557,7 +2557,6 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .ahi_width = OSD_AHI_WIDTH * OSD_CHAR_WIDTH, .ahi_height = OSD_AHI_HEIGHT * OSD_CHAR_HEIGHT, .ahi_vertical_offset = -OSD_CHAR_HEIGHT, - .sidebar_horizontal_offset = OSD_AH_SIDEBAR_WIDTH_POS * OSD_CHAR_WIDTH, ); void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) From 0df8dee3c9ca5c92025a428bc9a6795bcd04f808 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 14 Aug 2020 16:54:23 +0200 Subject: [PATCH 134/248] Disable KFC32F3 --- make/release.mk | 2 +- make/targets.mk | 2 +- src/main/target/KFC32F3_INAV/{target.mk => target.mk_} | 0 3 files changed, 2 insertions(+), 2 deletions(-) rename src/main/target/KFC32F3_INAV/{target.mk => target.mk_} (100%) diff --git a/make/release.mk b/make/release.mk index b00ac8b4bc1..ecc5955e0cb 100644 --- a/make/release.mk +++ b/make/release.mk @@ -1,6 +1,6 @@ RELEASE_TARGETS = AIRHEROF3 AIRHEROF3_QUAD -RELEASE_TARGETS += LUX_RACE RCEXPLORERF3 RMDO SPARKY KFC32F3_INAV FALCORE MOTOLAB ANYFC BLUEJAYF4 COLIBRI F4BY DALRCF405 DALRCF722DUAL +RELEASE_TARGETS += LUX_RACE RCEXPLORERF3 RMDO SPARKY FALCORE MOTOLAB ANYFC BLUEJAYF4 COLIBRI F4BY DALRCF405 DALRCF722DUAL RELEASE_TARGETS += QUANTON REVO SPARKY2 PIKOBLX CLRACINGF4AIR CLRACINGF4AIRV2 PIXRACER BEEROTORF4 ANYFCF7 ANYFCF7_EXTERNAL_BARO RELEASE_TARGETS += ALIENFLIGHTNGF7 diff --git a/make/targets.mk b/make/targets.mk index c725539ea6c..f3150c9c7b2 100644 --- a/make/targets.mk +++ b/make/targets.mk @@ -77,7 +77,7 @@ GROUP_3_TARGETS := AIRBOTF4 BLUEJAYF4 OMNIBUSF4 OMNIBUSF4PRO FIREWORKSV2 SPARKY2 GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ALIENFLIGHTNGF7 PIXRACER YUPIF7 MATEKF405SE MATEKF411 MATEKF722 MATEKF405OSD MATEKF405_SERVOS6 NOX GROUP_5_TARGETS := ASGARD32F7 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF4OSD GROUP_6_TARGETS := MAMBAF405 OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS AIKONF4 -GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KFC32F3_INAV MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO +GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO GROUP_8_TARGETS := MATEKF765 MATEKF722PX KAKUTEF7HDV ZEEZF7 FOXEERF722V2 FRSKYPILOT FRSKY_ROVERF7 GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS) $(GROUP_3_TARGETS) $(GROUP_4_TARGETS) $(GROUP_5_TARGETS) $(GROUP_6_TARGETS) $(GROUP_7_TARGETS) $(GROUP_8_TARGETS), $(VALID_TARGETS)) diff --git a/src/main/target/KFC32F3_INAV/target.mk b/src/main/target/KFC32F3_INAV/target.mk_ similarity index 100% rename from src/main/target/KFC32F3_INAV/target.mk rename to src/main/target/KFC32F3_INAV/target.mk_ From 02093b335d6a05dd2723b2521c5b76b3b2168909 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Mon, 17 Aug 2020 10:22:52 +0200 Subject: [PATCH 135/248] [FRSKYPILOT] Update current sensor calibration (#6043) --- src/main/target/FRSKYPILOT/target.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/target/FRSKYPILOT/target.h b/src/main/target/FRSKYPILOT/target.h index 4d5181abf51..3a8ddbe2aaf 100644 --- a/src/main/target/FRSKYPILOT/target.h +++ b/src/main/target/FRSKYPILOT/target.h @@ -189,8 +189,8 @@ #define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX) #define VBAT_SCALE_DEFAULT 1545 -#define CURRENT_METER_SCALE 168 -#define CURRENT_METER_OFFSET 3277 +#define CURRENT_METER_SCALE 171 +#define CURRENT_METER_OFFSET 3288 #define USE_SERIAL_4WAY_BLHELI_INTERFACE From 02dfee1c5927807431eaf5d84f0ecaf575fb71a6 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Mon, 17 Aug 2020 11:42:56 +0200 Subject: [PATCH 136/248] [RTH Estimator] Fix display condition (#6040) --- src/main/flight/rth_estimator.c | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/src/main/flight/rth_estimator.c b/src/main/flight/rth_estimator.c index d3863981a10..d9897c32c74 100644 --- a/src/main/flight/rth_estimator.c +++ b/src/main/flight/rth_estimator.c @@ -149,9 +149,14 @@ static float calculateRemainingEnergyBeforeRTH(bool takeWindIntoAccount) { if (!STATE(FIXED_WING_LEGACY)) return -1; - if (!(feature(FEATURE_VBAT) && feature(FEATURE_CURRENT_METER) && navigationPositionEstimateIsHealthy() && (batteryMetersConfig()->cruise_power > 0) && (ARMING_FLAG(ARMED)) && ((!STATE(FIXED_WING_LEGACY)) || (isNavLaunchEnabled() && isFixedWingLaunchDetected())) && (navConfig()->fw.cruise_speed > 0) && (currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MWH) && (currentBatteryProfile->capacity.value > 0) && batteryWasFullWhenPluggedIn() && isImuHeadingValid() + if (!(feature(FEATURE_VBAT) && batteryWasFullWhenPluggedIn() + && feature(FEATURE_CURRENT_METER) && (batteryMetersConfig()->cruise_power > 0) + && (currentBatteryProfile->capacity.unit == BAT_CAPACITY_UNIT_MWH) && (currentBatteryProfile->capacity.value > 0) + && navigationPositionEstimateIsHealthy() && isImuHeadingValid() && (navConfig()->fw.cruise_speed > 0) + && ((!STATE(FIXED_WING_LEGACY)) || !isNavLaunchEnabled() || (isNavLaunchEnabled() && isFixedWingLaunchDetected())) + && (ARMING_FLAG(ARMED)) #ifdef USE_WIND_ESTIMATOR - && isEstimatedWindSpeedValid() + && (!takeWindIntoAccount || isEstimatedWindSpeedValid()) #endif )) return -1; From 291d4789a76693cab3baa042de3e6e06057a4ebf Mon Sep 17 00:00:00 2001 From: giacomo892 Date: Wed, 19 Aug 2020 10:38:41 +0200 Subject: [PATCH 137/248] improvements --- src/main/common/olc.c | 20 +++----------------- 1 file changed, 3 insertions(+), 17 deletions(-) diff --git a/src/main/common/olc.c b/src/main/common/olc.c index 7ae5ae58217..ca31bc0c5ac 100644 --- a/src/main/common/olc.c +++ b/src/main/common/olc.c @@ -29,7 +29,7 @@ static olc_coord_t initial_resolution; static void init_constants(void) { - static int inited = 0; + static bool inited = 0; if (inited) { return; } @@ -45,20 +45,6 @@ static void init_constants(void) initial_resolution = powf(ENCODING_BASE, initial_exponent) * OLC_DEG_MULTIPLIER; } -// Raises a number to an exponent, handling negative exponents. -static float pow_negf(float base, float exponent) -{ - if (exponent == 0) { - return 1; - } - - if (exponent > 0) { - return powf(base, exponent); - } - - return 1 / powf(base, -exponent); -} - // Compute the latitude precision value for a given code length. Lengths <= 10 // have the same precision for latitude and longitude, but lengths > 10 have // different precisions due to the grid method having fewer columns than rows. @@ -66,10 +52,10 @@ static float compute_precision_for_length(int length) { // Magic numbers! if (length <= (int)PAIR_CODE_LEN) { - return pow_negf(ENCODING_BASE, floorf((length / -2) + 2)); + return powf(ENCODING_BASE, floorf((length / -2) + 2)); } - return pow_negf(ENCODING_BASE, -3) / powf(5, length - (int)PAIR_CODE_LEN); + return powf(ENCODING_BASE, -3) / powf(5, length - (int)PAIR_CODE_LEN); } static olc_coord_t adjust_latitude(olc_coord_t lat, size_t code_len) From 72f0be89d0cac9cae42aa40977cd9f72b02256a1 Mon Sep 17 00:00:00 2001 From: Airwide Date: Sun, 23 Aug 2020 16:08:04 +0200 Subject: [PATCH 138/248] Created handlePIDAntiWindup. Changes FW behaviour to only activate anti windup once per flight. --- src/main/fc/fc_core.c | 95 ++++++++++++++++++++++++++++--------------- 1 file changed, 63 insertions(+), 32 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 5317dc04704..c46faf8b93a 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -513,6 +513,68 @@ void tryArm(void) } } +static void handlePIDAntiWindup(throttleStatus_e throttleStatus) +{ + static bool antiWindupWasActivatedOnce = false; + + // Track if ANTI_WINDUP was activated + if (!ARMING_FLAG(ARMED)) { + antiWindupWasActivatedOnce = false; + } + // In MANUAL mode we reset integrators prevent I-term wind-up (PID output is not used in MANUAL) + if (FLIGHT_MODE(MANUAL_MODE) || !ARMING_FLAG(ARMED)) { + DISABLE_STATE(ANTI_WINDUP); + pidResetErrorAccumulators(); + return; + } + + // At non-zero throttle - always disable ANTI_WINDUP + if (throttleStatus != THROTTLE_LOW) { + DISABLE_STATE(ANTI_WINDUP); + return; + } + + // This case applies only to MR when Airmode management is throttle threshold activated + if (rcControlsConfig()->airmodeHandlingType == THROTTLE_THRESHOLD) { + DISABLE_STATE(ANTI_WINDUP); + if (throttleStatus == THROTTLE_LOW && !STATE(AIRMODE_ACTIVE)) { + pidResetErrorAccumulators(); + } + return; + } + + rollPitchStatus_e rollPitchStatus = calculateRollPitchCenterStatus(); + + if (STATE(FIXED_WING_LEGACY)) { + if (STATE(AIRMODE_ACTIVE)) { + // On airplanes only activate ANTI_WINDUP if throttle = low, roll/pitch = center and ANTI_WINDUP was never activated this flight + if ((rollPitchStatus == CENTERED) && !antiWindupWasActivatedOnce) { + ENABLE_STATE(ANTI_WINDUP); + antiWindupWasActivatedOnce = true; + } + else { + DISABLE_STATE(ANTI_WINDUP); + } + } + else { + DISABLE_STATE(ANTI_WINDUP); + } + } + else { // MULTI_ROTOR + if (STATE(AIRMODE_ACTIVE) && !failsafeIsActive()) { + if ((rollPitchStatus == CENTERED) || feature(FEATURE_MOTOR_STOP)) { + ENABLE_STATE(ANTI_WINDUP); + } + else { + DISABLE_STATE(ANTI_WINDUP); + } + } + else { + DISABLE_STATE(ANTI_WINDUP); + } + } +} + void processRx(timeUs_t currentTimeUs) { // Calculate RPY channel data @@ -649,38 +711,7 @@ void processRx(timeUs_t currentTimeUs) /* In airmode Iterm should be prevented to grow when Low thottle and Roll + Pitch Centered. This is needed to prevent Iterm winding on the ground, but keep full stabilisation on 0 throttle while in air Low Throttle + roll and Pitch centered is assuming the copter is on the ground. Done to prevent complex air/ground detections */ - if (FLIGHT_MODE(MANUAL_MODE) || !ARMING_FLAG(ARMED)) { - /* In MANUAL mode we reset integrators prevent I-term wind-up (PID output is not used in MANUAL) */ - pidResetErrorAccumulators(); - } - else if (STATE(FIXED_WING_LEGACY) || rcControlsConfig()->airmodeHandlingType == STICK_CENTER) { - if (throttleStatus == THROTTLE_LOW) { - if (STATE(AIRMODE_ACTIVE) && !failsafeIsActive() && ARMING_FLAG(ARMED)) { - rollPitchStatus_e rollPitchStatus = calculateRollPitchCenterStatus(); - - // ANTI_WINDUP at centred stick with MOTOR_STOP is needed on MRs and not needed on FWs - if ((rollPitchStatus == CENTERED) || (feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING_LEGACY))) { - ENABLE_STATE(ANTI_WINDUP); - } - else { - DISABLE_STATE(ANTI_WINDUP); - } - } - else { - DISABLE_STATE(ANTI_WINDUP); - pidResetErrorAccumulators(); - } - } - else { - DISABLE_STATE(ANTI_WINDUP); - } - } else if (rcControlsConfig()->airmodeHandlingType == THROTTLE_THRESHOLD) { - DISABLE_STATE(ANTI_WINDUP); - //This case applies only to MR when Airmode management is throttle threshold activated - if (throttleStatus == THROTTLE_LOW && !STATE(AIRMODE_ACTIVE)) { - pidResetErrorAccumulators(); - } - } + handlePIDAntiWindup(throttleStatus); if (mixerConfig()->platformType == PLATFORM_AIRPLANE) { DISABLE_FLIGHT_MODE(HEADFREE_MODE); From 0115e2e278269ccf0816dca7b39b4ce8c7384d1d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Niccol=C3=B2=20Maggioni?= Date: Mon, 24 Aug 2020 22:26:45 +0200 Subject: [PATCH 139/248] Include undocumented settings in docs (#6061) * Update autogenerated settings doc * Include undocumented settings in docs --- docs/Settings.md | 60 +++++++++++++++++++++++++++++++++++- src/utils/update_cli_docs.py | 17 +++++++--- 2 files changed, 71 insertions(+), 6 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 3ec4d6442a6..3f5a76e9cdf 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -12,6 +12,8 @@ | acc_hardware | AUTO | Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info | | acc_lpf_hz | 15 | Software-based filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. | | acc_lpf_type | BIQUAD | Specifies the type of the software LPF of the acc signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. | +| acc_notch_cutoff | | | +| acc_notch_hz | | | | accgain_x | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | | accgain_y | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | | accgain_z | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | @@ -52,6 +54,9 @@ | current_meter_offset | 0 | This sets the output offset voltage of the current sensor in millivolts. | | current_meter_scale | 400 | This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt. | | current_meter_type | ADC | ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position. | +| d_boost_factor | | | +| d_boost_gyro_delta_lpf_hz | | | +| d_boost_max_at_acceleration | | | | deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. | | debug_mode | NONE | Defines debug values exposed in debug variables (developer / debugging setting) | | disarm_kill_switch | ON | Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel. | @@ -64,6 +69,14 @@ | dynamic_gyro_notch_min_hz | 150 | Minimum frequency for dynamic notches. Default value of `150` works best with 5" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7" drones. 10" can go down to `60` - `70` | | dynamic_gyro_notch_q | 120 | Q factor for dynamic notches | | dynamic_gyro_notch_range | `MEDIUM` | Range for dynamic gyro notches. `MEDIUM` for 5", `HIGH` for 3" and `MEDIUM`/`LOW` for 7" and bigger propellers | +| eleres_freq | | | +| eleres_loc_delay | | | +| eleres_loc_en | | | +| eleres_loc_power | | | +| eleres_signature | | | +| eleres_telemetry_en | | | +| eleres_telemetry_power | | | +| esc_sensor_listen_only | | | | failsafe_delay | 5 | Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). | | failsafe_fw_pitch_angle | 100 | Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb | | failsafe_fw_roll_angle | -200 | Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll | @@ -82,6 +95,7 @@ | failsafe_throttle_low_delay | 100 | If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout | | fixed_wing_auto_arm | OFF | Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured. | | flaperon_throw_offset | 200 | Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated. | +| fpv_mix_degrees | | | | frsky_coordinates_format | 0 | D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA | | frsky_default_latitude | 0.000 | D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. | | frsky_default_longitude | 0.000 | D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. | @@ -122,9 +136,12 @@ | gyro_hardware_lpf | 42HZ | Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first. | | gyro_lpf_hz | 60 | Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. | | gyro_lpf_type | BIQUAD | Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. | +| gyro_notch_cutoff | | | +| gyro_notch_hz | | | | gyro_stage2_lowpass_hz | 0 | Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz) | | gyro_stage2_lowpass_type | `BIQUAD` | Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | | gyro_sync | OFF | This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf | +| gyro_to_use | | | | has_flaps | OFF | Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot | | heading_hold_rate_limit | 90 | This setting limits yaw rotation rate that HEADING_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when HEADING_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes. | | hott_alarm_sound_interval | 5 | Battery alarm delay in seconds for Hott telemetry | @@ -145,15 +162,21 @@ | inav_max_surface_altitude | 200 | Max allowed altitude for surface following mode. [cm] | | inav_reset_altitude | FIRST_ARM | Defines when relative estimated altitude is reset to zero. Variants - `NEVER` (once reference is acquired it's used regardless); `FIRST_ARM` (keep altitude at zero until firstly armed), `EACH_ARM` (altitude is reset to zero on each arming) | | inav_reset_home | FIRST_ARM | Allows to chose when the home position is reset. Can help prevent resetting home position after accidental mid-air disarm. Possible values are: NEVER, FIRST_ARM and EACH_ARM | +| inav_use_gps_no_baro | | | | inav_use_gps_velned | ON | Defined if iNav should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF iNav will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance. | | inav_w_acc_bias | 0.010 | Weight for accelerometer drift estimation | +| inav_w_xy_flow_p | | | +| inav_w_xy_flow_v | | | | inav_w_xy_gps_p | 1.000 | Weight of GPS coordinates in estimated UAV position and speed. | | inav_w_xy_gps_v | 2.000 | Weight of GPS velocity data in estimated UAV speed | | inav_w_xy_res_v | 0.500 | Decay coefficient for estimated velocity when GPS reference for position is lost | +| inav_w_xyz_acc_p | | | | inav_w_z_baro_p | 0.350 | Weight of barometer measurements in estimated altitude and climb rate | | inav_w_z_gps_p | 0.200 | Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes | | inav_w_z_gps_v | 0.500 | Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero | | inav_w_z_res_v | 0.500 | Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost | +| inav_w_z_surface_p | | | +| inav_w_z_surface_v | | | | iterm_windup | 50 | Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter) | | ledstrip_visual_beeper | OFF | | | log_level | `ERROR` | Defines serial debugging log level. See `docs/development/serial_printf_debugging.md` for usage. | @@ -164,6 +187,9 @@ | mag_declination | 0 | Current location magnetic declination in format. For example, -6deg 37min = -637 for Japan. Leading zero in ddd not required. Get your local magnetic declination here: http://magnetic-declination.com/ . Not in use if inav_auto_mag_decl is turned on and you acquire valid GPS fix. | | mag_hardware | AUTO | Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info | | mag_to_use | | Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target | +| maggain_x | 0 | Magnetometer calibration X gain. If 0, no calibration or calibration failed | +| maggain_y | 0 | Magnetometer calibration Y gain. If 0, no calibration or calibration failed | +| maggain_z | 0 | Magnetometer calibration Z gain. If 0, no calibration or calibration failed | | magzero_x | 0 | Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed. | | magzero_y | 0 | Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed. | | magzero_z | 0 | Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed. | @@ -172,6 +198,11 @@ | manual_rc_yaw_expo | 20 | Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100] | | manual_roll_rate | 100 | Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]% | | manual_yaw_rate | 100 | Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]% | +| mavlink_ext_status_rate | | | +| mavlink_extra1_rate | | | +| mavlink_extra2_rate | | | +| mavlink_pos_rate | | | +| mavlink_rc_chan_rate | | | | max_angle_inclination_pit | 300 | Maximum inclination in level (angle) mode (PITCH axis). 100=10° | | max_angle_inclination_rll | 300 | Maximum inclination in level (angle) mode (ROLL axis). 100=10° | | max_check | 1900 | These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value. | @@ -190,6 +221,8 @@ | mc_i_pitch | 30 | Multicopter rate stabilisation I-gain for PITCH | | mc_i_roll | 30 | Multicopter rate stabilisation I-gain for ROLL | | mc_i_yaw | 45 | Multicopter rate stabilisation I-gain for YAW | +| mc_iterm_relax | | | +| mc_iterm_relax_cutoff | | | | mc_p_level | 20 | Multicopter attitude stabilisation P-gain | | mc_p_pitch | 40 | Multicopter rate stabilisation P-gain for PITCH | | mc_p_roll | 40 | Multicopter rate stabilisation P-gain for ROLL | @@ -202,6 +235,7 @@ | motor_accel_time | 0 | Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000] | | motor_decel_time | 0 | Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000] | | motor_direction_inverted | OFF | Use if you need to inverse yaw motor direction. | +| motor_poles | | | | motor_pwm_protocol | STANDARD | Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED | | motor_pwm_rate | 400 | Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000. | | msp_override_channels | 0 | Mask of RX channels that may be overridden by MSP `SET_RAW_RC`. Note that this requires custom firmware with `USE_RX_MSP` and `USE_MSP_RC_OVERRIDE` compile options and the `MSP RC Override` flight mode. | @@ -253,6 +287,7 @@ | nav_landing_speed | 200 | Vertical descent velocity during the RTH landing phase. [cm/s] | | nav_manual_climb_rate | 200 | Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] | | nav_manual_speed | 500 | Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only] | +| nav_max_terrain_follow_alt | | | | nav_mc_auto_disarm_delay | 2000 | Delay before multi-rotor disarms when `nav_disarm_on_landing` is set (m/s) | | nav_mc_bank_angle | 30 | Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude | | nav_mc_braking_bank_angle | 40 | max angle that MR is allowed to bank in BOOST mode | @@ -273,6 +308,8 @@ | nav_mc_vel_xy_dterm_attenuation | 90 | Maximum D-term attenution percentage for horizontal velocity PID controller (Multirotor). It allows to smooth the PosHold CRUISE, WP and RTH when Multirotor is traveling at full speed. Dterm is not attenuated at low speeds, breaking and accelerating. | | nav_mc_vel_xy_dterm_attenuation_end | 60 | A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation reaches maximum | | nav_mc_vel_xy_dterm_attenuation_start | 10" | A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation begins | +| nav_mc_vel_xy_dterm_lpf_hz | | | +| nav_mc_vel_xy_ff | | | | nav_mc_vel_xy_i | 15 | I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot | | nav_mc_vel_xy_p | 40 | P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause "nervous" behavior and oscillations | | nav_mc_vel_z_d | 10 | D gain of velocity PID controller | @@ -295,6 +332,7 @@ | nav_wp_radius | 100 | Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius | | nav_wp_safe_distance | 10000 | First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check. | | opflow_hardware | | Selection of OPFLOW hardware. | +| opflow_scale | | | | osd_ahi_bordered | OFF | Shows a border/corners around the AHI region (pixel OSD only) | | osd_ahi_height | 162 | AHI height in pixels (pixel OSD only) | | osd_ahi_style | DEFAULT | Sets OSD Artificial Horizon style "DEFAULT" or "LINE" for the FrSky Graphical OSD. | @@ -302,11 +340,13 @@ | osd_ahi_width | 132 | AHI width in pixels (pixel OSD only) | | osd_alt_alarm | 100 | Value above which to make the OSD relative altitude indicator blink (meters) | | osd_artificial_horizon_max_pitch | 20 | Max pitch, in degrees, for OSD artificial horizon | +| osd_artificial_horizon_reverse_roll | | | | osd_baro_temp_alarm_max | 600 | Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade) | | osd_baro_temp_alarm_min | -200 | Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade) | | osd_camera_fov_h | 135 | Horizontal field of view for the camera in degres | | osd_camera_fov_v | 85 | Vertical field of view for the camera in degres | | osd_camera_uptilt | 0 | Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal | +| osd_coordinate_digits | | | | osd_crosshairs_style | DEFAULT | To set the visual type for the crosshair | | osd_current_alarm | 0 | Value above which the OSD current consumption element will start blinking. Measured in full Amperes. | | osd_dist_alarm | 1000 | Value above which to make the OSD distance from home indicator blink (meters) | @@ -330,13 +370,17 @@ | osd_hud_wp_disp | 0 | How many navigation waypoints are displayed, set to 0 (zero) to disable. As sample, if set to 2, and you just passed the 3rd waypoint of the mission, you'll see markers for the 4th waypoint (marked 1) and the 5th waypoint (marked 2) | | osd_imu_temp_alarm_max | 600 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | | osd_imu_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | +| osd_left_sidebar_scroll | | | | osd_left_sidebar_scroll_step | 0 | How many units each sidebar step represents. 0 means the default value for the scroll type. | | osd_main_voltage_decimals | 1 | Number of decimals for the battery voltages displayed in the OSD [1-2]. | | osd_neg_alt_alarm | 5 | Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters) | +| osd_plus_code_digits | | | +| osd_right_sidebar_scroll | | | | osd_right_sidebar_scroll_step | 0 | Same as left_sidebar_scroll_step, but for the right sidebar | | osd_row_shiftdown | 0 | Number of rows to shift the OSD display (increase if top rows are cut off) | | osd_rssi_alarm | 20 | Value bellow which to make the OSD RSSI indicator blink | | osd_sidebar_horizontal_offset | 0 | Sidebar horizontal offset from default position. Positive values move the sidebars closer to the edges. | +| osd_sidebar_scroll_arrows | | | | osd_stats_energy_unit | MAH | Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour) | | osd_temp_label_align | LEFT | Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT` | | osd_time_alarm | 10 | Value above which to make the OSD flight time indicator blink (minutes) | @@ -345,8 +389,14 @@ | pid_type | | Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID` | | pidsum_limit | 500 | A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | | pidsum_limit_yaw | 400 | A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help | +| pinio_box1 | | | +| pinio_box2 | | | +| pinio_box3 | | | +| pinio_box4 | | | | pitch_rate | 20 | Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. | | pitot_hardware | NONE | Selection of pitot hardware. | +| pitot_lpf_milli_hz | | | +| pitot_scale | | | | platform_type | "MULTIROTOR" | Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented | | pos_hold_deadband | 20 | Stick deadband in [r/c points], applied after r/c deadband and expo | | rangefinder_hardware | NONE | Selection of rangefinder hardware. | @@ -372,8 +422,12 @@ | rth_energy_margin | 5 | Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation | | rx_max_usec | 2115 | Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of mid_rc. | | rx_min_usec | 885 | Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc. | +| rx_spi_id | | | +| rx_spi_protocol | | | +| rx_spi_rf_channel_count | | | +| sbus_sync_interval | | | | sdcard_detect_inverted | `TARGET dependent` | This setting drives the way SD card is detected in card slot. On some targets (AnyFC F7 clone) different card slot was used and depending of hardware revision ON or OFF setting might be required. If card is not detected, change this value. | -| serialrx_halfduplex | AUTO | Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire | +| serialrx_halfduplex | AUTO | Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire. | | serialrx_inverted | OFF | Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY). | | serialrx_provider | SPEK1024 | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. | | servo_center_pulse | 1500 | Servo midpoint | @@ -391,9 +445,12 @@ | sim_transmit_interval | 60 | Text message transmission interval in seconds for SIM module. Minimum value: 10 | | small_angle | 25 | If the aircraft tilt angle exceed this value the copter will refuse to arm. | | smartport_fuel_unit | MAH | S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH] | +| smartport_master_halfduplex | | | +| smartport_master_inverted | | | | spektrum_sat_bind | 0 | 0 = disabled. Used to bind the spektrum satellite to RX | | stats | OFF | General switch of the statistics recording feature (a.k.a. odometer) | | stats_total_dist | 0 | Total flight distance [in meters]. The value is updated on every disarm when "stats" are enabled. | +| stats_total_energy | | | | stats_total_time | 0 | Total flight time [in seconds]. The value is updated on every disarm when "stats" are enabled. | | switch_disarm_delay | 250 | Delay before disarming when requested by switch (ms) [0-1000] | | telemetry_halfduplex | OFF | S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details | @@ -422,6 +479,7 @@ | vtx_halfduplex | ON | Use half duplex UART to communicate with the VTX, using only a TX pin in the FC. | | vtx_low_power_disarm | OFF | When the craft is disarmed, set the VTX to its lowest power. `ON` will set the power to its minimum value on startup, increase it to `vtx_power` when arming and change it back to its lowest setting after disarming. `UNTIL_FIRST_ARM` will start with minimum power, but once the craft is armed it will increase to `vtx_power` and it will never decrease until the craft is power cycled. | | vtx_max_power_override | 0 | Some VTXes may report max power incorrectly (i.e. 200mW for a 600mW VTX). Use this to override max supported power. 0 to disable and use whatever VTX reports as its capabilities | +| vtx_pit_mode_chan | | | | vtx_power | 1 | VTX RF power level to use. The exact number of mw depends on the VTX hardware. | | yaw_deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. | | yaw_lpf_hz | 30 | Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below) | diff --git a/src/utils/update_cli_docs.py b/src/utils/update_cli_docs.py index 47bd255ab65..7ca8bdf7113 100755 --- a/src/utils/update_cli_docs.py +++ b/src/utils/update_cli_docs.py @@ -1,5 +1,6 @@ #!/usr/bin/env python3 +import optparse import yaml # pyyaml / python-yaml SETTINGS_MD_PATH = "docs/Settings.md" @@ -18,11 +19,12 @@ def generate_md_table_from_yaml(settings_yaml): # Extract description and default value of each setting from the YAML specs (if present) for group in settings_yaml['groups']: for member in group['members']: - if any(key in member for key in ["description", "default_value"]): - params[member['name']] = { - "description": member["description"] if "description" in member else "", - "default": member["default_value"] if "default_value" in member else "" - } + if not any(key in member for key in ["description", "default_value"]) and not options.quiet: + print("Setting \"{}\" has no description or default value specified".format(member['name'])) + params[member['name']] = { + "description": member["description"] if "description" in member else "", + "default": member["default_value"] if "default_value" in member else "" + } # MD table header md_table_lines = [ @@ -44,6 +46,11 @@ def write_settings_md(lines): settings_md.writelines(lines) if __name__ == "__main__": + global options, args + parser = optparse.OptionParser() + parser.add_option('-q', '--quiet', action="store_true", default=False, help="do not write anything to stdout") + options, args = parser.parse_args() + settings_yaml = parse_settings_yaml() md_table_lines = generate_md_table_from_yaml(settings_yaml) settings_md_lines = \ From fd24510b7138eccd44fcc461eb13090f425ef735 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Mon, 24 Aug 2020 22:27:06 +0200 Subject: [PATCH 140/248] Improve the settings generator's error reporting (#6068) Make the settings generator report when it can't find the values for a table instead of outputting a cryptic error --- src/utils/settings.rb | 1 + 1 file changed, 1 insertion(+) diff --git a/src/utils/settings.rb b/src/utils/settings.rb index bb517de362b..3f02725be46 100644 --- a/src/utils/settings.rb +++ b/src/utils/settings.rb @@ -532,6 +532,7 @@ def write_impl_file(file) table_names.each do |name| buf << "const char * const #{table_variable_name(name)}[] = {\n" tbl = @tables[name] + raise "values not found for table #{name}" unless tbl.has_key? 'values' tbl["values"].each do |v| buf << "\t#{v.inspect},\n" end From 0811839935309a0ef6c18f989ff8afa171eab5c7 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Tue, 9 Jun 2020 14:25:33 +0100 Subject: [PATCH 141/248] [BUILD] Port all f405 and f427 targets to cmake --- cmake/inav.cmake | 12 +- cmake/stm32-usb.cmake | 7 - cmake/stm32.cmake | 196 ++++++------------ cmake/stm32f4.cmake | 151 ++++++++++++++ src/CMakeLists.txt | 1 + src/main/CMakeLists.txt | 142 +++++++++---- src/main/target/AIKONF4/CMakeLists.txt | 1 + src/main/target/AIRBOTF4/CMakeLists.txt | 1 + src/main/target/ASGARD32F4/CMakeLists.txt | 1 + src/main/target/BEEROTORF4/CMakeLists.txt | 1 + src/main/target/BETAFLIGHTF4/CMakeLists.txt | 1 + src/main/target/BLUEJAYF4/CMakeLists.txt | 1 + src/main/target/CLRACINGF4AIR/CMakeLists.txt | 3 + src/main/target/COLIBRI/CMakeLists.txt | 2 + src/main/target/DALRCF405/CMakeLists.txt | 1 + src/main/target/F4BY/CMakeLists.txt | 1 + .../target/FF_F35_LIGHTNING/CMakeLists.txt | 2 + src/main/target/FF_FORTINIF4/CMakeLists.txt | 1 + src/main/target/FF_PIKOF4/CMakeLists.txt | 2 + src/main/target/FIREWORKSV2/CMakeLists.txt | 2 + src/main/target/FISHDRONEF4/CMakeLists.txt | 1 + src/main/target/FOXEERF405/CMakeLists.txt | 1 + src/main/target/FRSKYF4/CMakeLists.txt | 1 + src/main/target/FURYF4OSD/CMakeLists.txt | 2 + .../target/IFLIGHTF4_TWING/CMakeLists.txt | 1 + src/main/target/KAKUTEF4/CMakeLists.txt | 2 + src/main/target/MAMBAF405US/CMakeLists.txt | 1 + src/main/target/MATEKF405/CMakeLists.txt | 3 + src/main/target/MATEKF405SE/CMakeLists.txt | 1 + src/main/target/OMNIBUSF4/CMakeLists.txt | 12 ++ src/main/target/PIXRACER/CMakeLists.txt | 1 + src/main/target/REVO/CMakeLists.txt | 1 + src/main/target/SPARKY2/CMakeLists.txt | 1 + src/main/target/SPEEDYBEEF4/CMakeLists.txt | 3 + src/main/target/SPRACINGF4EVO/CMakeLists.txt | 1 + 35 files changed, 381 insertions(+), 180 deletions(-) create mode 100644 cmake/stm32f4.cmake create mode 100644 src/CMakeLists.txt create mode 100644 src/main/target/AIKONF4/CMakeLists.txt create mode 100644 src/main/target/AIRBOTF4/CMakeLists.txt create mode 100644 src/main/target/ASGARD32F4/CMakeLists.txt create mode 100644 src/main/target/BEEROTORF4/CMakeLists.txt create mode 100644 src/main/target/BETAFLIGHTF4/CMakeLists.txt create mode 100644 src/main/target/BLUEJAYF4/CMakeLists.txt create mode 100644 src/main/target/CLRACINGF4AIR/CMakeLists.txt create mode 100644 src/main/target/COLIBRI/CMakeLists.txt create mode 100644 src/main/target/DALRCF405/CMakeLists.txt create mode 100644 src/main/target/F4BY/CMakeLists.txt create mode 100644 src/main/target/FF_F35_LIGHTNING/CMakeLists.txt create mode 100644 src/main/target/FF_FORTINIF4/CMakeLists.txt create mode 100644 src/main/target/FF_PIKOF4/CMakeLists.txt create mode 100644 src/main/target/FIREWORKSV2/CMakeLists.txt create mode 100644 src/main/target/FISHDRONEF4/CMakeLists.txt create mode 100644 src/main/target/FOXEERF405/CMakeLists.txt create mode 100644 src/main/target/FRSKYF4/CMakeLists.txt create mode 100644 src/main/target/FURYF4OSD/CMakeLists.txt create mode 100644 src/main/target/IFLIGHTF4_TWING/CMakeLists.txt create mode 100644 src/main/target/KAKUTEF4/CMakeLists.txt create mode 100644 src/main/target/MAMBAF405US/CMakeLists.txt create mode 100644 src/main/target/MATEKF405/CMakeLists.txt create mode 100644 src/main/target/MATEKF405SE/CMakeLists.txt create mode 100644 src/main/target/OMNIBUSF4/CMakeLists.txt create mode 100644 src/main/target/PIXRACER/CMakeLists.txt create mode 100644 src/main/target/REVO/CMakeLists.txt create mode 100644 src/main/target/SPARKY2/CMakeLists.txt create mode 100644 src/main/target/SPEEDYBEEF4/CMakeLists.txt create mode 100644 src/main/target/SPRACINGF4EVO/CMakeLists.txt diff --git a/cmake/inav.cmake b/cmake/inav.cmake index 190fb08193d..285ee1afeb0 100644 --- a/cmake/inav.cmake +++ b/cmake/inav.cmake @@ -4,11 +4,9 @@ set(INAV_INCLUDE_DIRS "${INAV_LIB_DIR}/main/MAVLink" ) -# TODO: We need a way to override HSE_VALUE set(INAV_DEFINITIONS __FORKNAME__=inav __REVISION__="${GIT_SHORT_HASH}" - HSE_VALUE=8000000 ) set(INAV_COMPILE_OPTIONS @@ -43,7 +41,7 @@ endmacro() function(setup_firmware_target name) target_compile_options(${name} PRIVATE ${INAV_COMPILE_OPTIONS}) target_include_directories(${name} PRIVATE ${INAV_INCLUDE_DIRS}) - target_compile_definitions(${name} PRIVATE ${INAV_DEFINITIONS} __TARGET__="${name}") + target_compile_definitions(${name} PRIVATE ${INAV_DEFINITIONS} __TARGET__="${name}" ${name}) enable_settings(${name}) # XXX: Don't make SETTINGS_GENERATED_C part of the build, # since it's compiled via #include in settings.c. This will @@ -59,7 +57,11 @@ endfunction() function(collect_targets) get_property(targets GLOBAL PROPERTY VALID_TARGETS) list(SORT targets) - add_custom_target("targets" + set(list_target_name "targets") + add_custom_target(${list_target_name} COMMAND cmake -E echo "Valid targets: ${targets}") - set_property(TARGET "targets" PROPERTY TARGET_MESSAGES OFF) + set_property(TARGET ${list_target_name} PROPERTY + TARGET_MESSAGES OFF + EXCLUDE_FROM_ALL 1 + EXCLUDE_FROM_DEFAULT_BUILD 1) endfunction() diff --git a/cmake/stm32-usb.cmake b/cmake/stm32-usb.cmake index 40dbf413b5a..2ae663e46d8 100644 --- a/cmake/stm32-usb.cmake +++ b/cmake/stm32-usb.cmake @@ -16,13 +16,6 @@ set(STM32_STDPERIPH_USB_INCLUDE_DIRS "${STM32_STDPERIPH_USBFS_DIR}/inc" ) -SET(STM32_STDPERIPH_USBOTG_SRC_EXCLUDES - usb_bsp_template.c - usb_conf_template.c - usb_hcd_int.c - usb_hcd.c - usb_otg.c -) set(STM32_STDPERIPH_USBOTG_SRC usb_core.c usb_dcd.c diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake index d22eb104a6e..0f8bc44e9bc 100644 --- a/cmake/stm32.cmake +++ b/cmake/stm32.cmake @@ -1,6 +1,9 @@ include(arm-none-eabi) +include(stm32f4) include(stm32-usb) +include(CMakeParseArguments) + set(CMSIS_DIR "${INAV_LIB_DIR}/main/CMSIS") set(CMSIS_INCLUDE_DIR "${CMSIS_DIR}/Core/Include") set(CMSIS_DSP_DIR "${INAV_LIB_DIR}/main/CMSIS/DSP") @@ -27,6 +30,21 @@ set(STM32_VCP_SRC ) main_sources(STM32_VCP_SRC) +set(STM32_SDCARD_SRC + drivers/sdcard/sdcard.c + drivers/sdcard/sdcard_spi.c + drivers/sdcard/sdcard_sdio.c + drivers/sdcard/sdcard_standard.c +) +main_sources(STM32_SDCARD_SRC) + +# XXX: This code is not STM32 specific +set(STM32_ASYNCFATFS_SRC + io/asyncfatfs/asyncfatfs.c + io/asyncfatfs/fat_standard.c +) +main_sources(STM32_ASYNCFATFS_SRC) + set(STM32_MSC_SRC msc/usbd_msc_desc.c msc/usbd_storage.c @@ -40,65 +58,25 @@ set(STM32_MSC_FLASH_SRC ) main_sources(STM32_MSC_FLASH_SRC) -set(STM32F4_STDPERIPH_DIR "${INAV_LIB_DIR}/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver") -set(STM32F4_CMSIS_DEVICE_DIR "${INAV_LIB_DIR}/main/STM32F4/Drivers/CMSIS/Device/ST/STM32F4xx") -set(STM32F4_CMSIS_DRIVERS_DIR "${INAV_LIB_DIR}/main/STM32F4/Drivers/CMSIS") -set(STM32F4_VCP_DIR "${INAV_MAIN_SRC_DIR}/vcpf4") - -set(STM32F4_STDPERIPH_SRC_EXCLUDES - stm32f4xx_can.c - stm32f4xx_cec.c - stm32f4xx_crc.c - stm32f4xx_cryp.c - stm32f4xx_cryp_aes.c - stm32f4xx_cryp_des.c - stm32f4xx_cryp_tdes.c - stm32f4xx_dbgmcu.c - stm32f4xx_dsi.c - stm32f4xx_flash_ramfunc.c - stm32f4xx_fmpi2c.c - stm32f4xx_fmc.c - stm32f4xx_hash.c - stm32f4xx_hash_md5.c - stm32f4xx_hash_sha1.c - stm32f4xx_lptim.c - stm32f4xx_qspi.c - stm32f4xx_sai.c - stm32f4xx_spdifrx.c +set(STM32_MSC_SDCARD_SRC + msc/usbd_storage_sd_spi.c ) +main_sources(STM32_MSC_SDCARD_SRC) -set(STM32F4_STDPERIPH_SRC_DIR "${STM32F4_STDPERIPH_DIR}/Src") -glob_except(STM32F4_STDPERIPH_SRC "${STM32F4_STDPERIPH_SRC_DIR}/*.c" STM32F4_STDPERIPH_SRC_EXCLUDES) - -set(STM32F4_VCP_SRC - stm32f4xx_it.c - usb_bsp.c - usbd_desc.c - usbd_usr.c - usbd_cdc_vcp.c -) -list(TRANSFORM STM32F4_VCP_SRC PREPEND "${STM32F4_VCP_DIR}/") - -set(STM32F4_MSC_SRC - drivers/usb_msc_f4xx.c -) -main_sources(STM32F4_MSC_SRC) - -set(STM32F4_INCLUDE_DIRS +set(STM32_INCLUDE_DIRS "${CMSIS_INCLUDE_DIR}" "${CMSIS_DSP_INCLUDE_DIR}" - "${STM32F4_STDPERIPH_DIR}/inc" - "${STM32F4_CMSIS_DEVICE_DIR}" - "${STM32F4_CMSIS_DRIVERS_DIR}" - "${STM32F4_VCP_DIR}" + "${INAV_MAIN_SRC_DIR}/target" ) -set(STM32_INCLUDE_DIRS - "${INAV_MAIN_SRC_DIR}/target" +set(STM32_DEFINITIONS ) +set(STM32_DEFAULT_HSE_MHZ 8) + set(STM32_LINKER_DIR "${INAV_MAIN_SRC_DIR}/target/link") + #if(SEMIHOSTING) # set(SEMIHOSTING_DEFINITIONS "SEMIHOSTING") # set(SEMIHOSTING_LDFLAGS @@ -135,57 +113,6 @@ set(STM32_LINK_OPTIONS -Wl,--print-memory-usage ) -set(STM32F4_SRC - target/system_stm32f4xx.c - drivers/accgyro/accgyro.c - drivers/accgyro/accgyro_mpu.c - drivers/adc_stm32f4xx.c - drivers/adc_stm32f4xx.c - drivers/bus_i2c_stm32f40x.c - drivers/serial_softserial.c - drivers/serial_uart_stm32f4xx.c - drivers/system_stm32f4xx.c - drivers/timer.c - drivers/timer_impl_stdperiph.c - drivers/timer_stm32f4xx.c - drivers/uart_inverter.c - drivers/dma_stm32f4xx.c - drivers/sdcard/sdmmc_sdio_f4xx.c -) - -main_sources(STM32F4_SRC) - -set(STM32F4_DEFINITIONS - STM32F4 - USE_STDPERIPH_DRIVER - ARM_MATH_MATRIX_CHECK - ARM_MATH_ROUNDING - __FPU_PRESENT=1 - UNALIGNED_SUPPORT_DISABLE - ARM_MATH_CM4 -) - -set(STM32F4_COMMON_OPTIONS - -mthumb - -mcpu=cortex-m4 - -march=armv7e-m - -mfloat-abi=hard - -mfpu=fpv4-sp-d16 - -fsingle-precision-constant -) - -set(STM32F4_COMPILE_OPTIONS -) - -set(SETM32F4_LINK_OPTIONS -) - -set(STM32F411_STDPERIPH_SRC_EXCLUDES "stm32f4xx_fsmc.c") - -set(STM32F411_COMPILE_DEFINITIONS - FLASH_SIZE=512 -) - macro(get_stm32_target_features) # out-var dir file(READ "${ARGV1}/target.h" _contents) string(REGEX MATCH "#define[\t ]+USE_VCP" HAS_VCP ${_contents}) @@ -196,30 +123,63 @@ macro(get_stm32_target_features) # out-var dir if(HAS_FLASHFS) list(APPEND ${ARGV0} FLASHFS) endif() - if (HAS_FLASHFS) # || SDCARD + string(REGEX MATCH "define[\t ]+USE_SDCARD" HAS_SDCARD ${_contents}) + if (HAS_SDCARD) + list(APPEND ${ARGV0} SDCARD) + endif() + if(HAS_FLASHFS OR HAS_SDCARD) list(APPEND ${ARGV0} MSC) endif() endmacro() -function(target_stm32 name) +function(target_stm32 name startup ldscript) + set(target_definitions) + # Parse keyword arguments + cmake_parse_arguments( + PARSED_ARGS + "" # No boolean arguments + "HSE_MHZ" # Single value arguments + "" # No multi-value arguments + ${ARGN} # Start parsing after the known arguments + ) + if (PARSED_ARGS_HSE_MHZ) + set(hse_mhz ${PARSED_ARGS_HSE_MHZ}) + else() + set(hse_mhz ${STM32_DEFAULT_HSE_MHZ}) + endif() + # Main .elf target add_executable(${name} ${COMMON_SRC} ${CMSIS_DSP_SRC}) file(GLOB target_c_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.c") file(GLOB target_h_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.h") target_sources(${name} PRIVATE ${target_c_sources} ${target_h_sources}) + target_sources(${name} PRIVATE "${STM32_STARTUP_DIR}/${startup}") + target_link_options(${name} PRIVATE "-T${STM32_LINKER_DIR}/${ldscript}") target_include_directories(${name} PRIVATE . ${STM32_INCLUDE_DIRS}) target_link_libraries(${name} PRIVATE ${STM32_LINK_LIBRARIES}) target_link_options(${name} PRIVATE ${STM32_LINK_OPTIONS}) + + set(target_definitions ${STM32_DEFINITIONS}) + math(EXPR hse_value "${hse_mhz} * 1000000") + list(APPEND target_definitions "HSE_VALUE=${hse_value}") + target_compile_definitions(${name} PRIVATE ${target_definitions}) + get_stm32_target_features(features "${CMAKE_CURRENT_SOURCE_DIR}") set_property(TARGET ${name} PROPERTY FEATURES ${features}) if(VCP IN_LIST features) target_sources(${name} PRIVATE ${STM32_VCP_SRC}) endif() + if(SDCARD IN_LIST features) + target_sources(${name} PRIVATE ${STM32_SDCARD_SRC} ${STM32_ASYNCFATFS_SRC}) + endif() if(MSC IN_LIST features) target_sources(${name} PRIVATE ${STM32_MSC_SRC}) if (FLASHFS IN_LIST features) target_sources(${name} PRIVATE ${STM32_MSC_FLASH_SRC}) endif() + if (SDCARD IN_LIST features) + target_sources(${name} PRIVATE ${STM32_MSC_SDCARD_SRC}) + endif() endif() # Generate .hex set(hexdir "${CMAKE_BINARY_DIR}/hex") @@ -232,32 +192,8 @@ function(target_stm32 name) add_custom_target(${clean_target} COMMAND cmake -E rm -r "${CMAKE_CURRENT_BINARY_DIR}" COMMENT "Removeng intermediate files for ${name}") - set_property(TARGET ${clean_target} PROPERTY TARGET_MESSAGES OFF) -endfunction() - -function(target_stm32f4xx name) - target_stm32(${name}) - target_sources(${name} PRIVATE ${STM32F4_SRC}) - target_compile_options(${name} PRIVATE ${STM32F4_COMMON_OPTIONS} ${STM32F4_COMPILE_OPTIONS}) - target_include_directories(${name} PRIVATE ${STM32_STDPERIPH_USB_INCLUDE_DIRS} ${STM32F4_INCLUDE_DIRS}) - target_compile_definitions(${name} PRIVATE ${STM32F4_DEFINITIONS}) - target_link_options(${name} PRIVATE ${STM32F4_COMMON_OPTIONS} ${STM32F4_LINK_OPTIONS}) - - get_property(features TARGET ${name} PROPERTY FEATURES) - if(VCP IN_LIST features) - target_sources(${name} PRIVATE ${STM32_STDPERIPH_USB_SRC} ${STM32F4_VCP_SRC}) - endif() - if(MSC IN_LIST features) - target_sources(${name} PRIVATE ${STM32F4_MSC_SRC}) - endif() -endfunction() - -function(target_stm32f411 name) - target_stm32f4xx(${name}) - set(STM32F411_STDPERIPH_SRC ${STM32F4_STDPERIPH_SRC}) - exclude_basenames(STM32F411_STDPERIPH_SRC STM32F411_STDPERIPH_SRC_EXCLUDES) - target_sources(${name} PRIVATE "${STM32_STARTUP_DIR}/startup_stm32f411xe.s" ${STM32F411_STDPERIPH_SRC}) - target_link_options(${name} PRIVATE "-T${STM32_LINKER_DIR}/stm32_flash_f411.ld") - target_compile_definitions(${name} PRIVATE STM32F411xE ${STM32F411_COMPILE_DEFINITIONS}) - setup_firmware_target(${name}) + set_property(TARGET ${clean_target} PROPERTY + TARGET_MESSAGES OFF + EXCLUDE_FROM_ALL 1 + EXCLUDE_FROM_DEFAULT_BUILD 1) endfunction() diff --git a/cmake/stm32f4.cmake b/cmake/stm32f4.cmake new file mode 100644 index 00000000000..2a0ab719c7c --- /dev/null +++ b/cmake/stm32f4.cmake @@ -0,0 +1,151 @@ +set(STM32F4_STDPERIPH_DIR "${INAV_LIB_DIR}/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver") +set(STM32F4_CMSIS_DEVICE_DIR "${INAV_LIB_DIR}/main/STM32F4/Drivers/CMSIS/Device/ST/STM32F4xx") +set(STM32F4_CMSIS_DRIVERS_DIR "${INAV_LIB_DIR}/main/STM32F4/Drivers/CMSIS") +set(STM32F4_VCP_DIR "${INAV_MAIN_SRC_DIR}/vcpf4") + +set(STM32F4_STDPERIPH_SRC_EXCLUDES + stm32f4xx_can.c + stm32f4xx_cec.c + stm32f4xx_crc.c + stm32f4xx_cryp.c + stm32f4xx_cryp_aes.c + stm32f4xx_cryp_des.c + stm32f4xx_cryp_tdes.c + stm32f4xx_dbgmcu.c + stm32f4xx_dsi.c + stm32f4xx_flash_ramfunc.c + stm32f4xx_fmpi2c.c + stm32f4xx_fmc.c + stm32f4xx_hash.c + stm32f4xx_hash_md5.c + stm32f4xx_hash_sha1.c + stm32f4xx_lptim.c + stm32f4xx_qspi.c + stm32f4xx_sai.c + stm32f4xx_spdifrx.c +) + +set(STM32F4_STDPERIPH_SRC_DIR "${STM32F4_STDPERIPH_DIR}/Src") +glob_except(STM32F4_STDPERIPH_SRC "${STM32F4_STDPERIPH_SRC_DIR}/*.c" STM32F4_STDPERIPH_SRC_EXCLUDES) + +set(STM32F4_SRC + target/system_stm32f4xx.c + drivers/adc_stm32f4xx.c + drivers/adc_stm32f4xx.c + drivers/bus_i2c_stm32f40x.c + drivers/serial_softserial.c + drivers/serial_uart_stm32f4xx.c + drivers/system_stm32f4xx.c + drivers/timer.c + drivers/timer_impl_stdperiph.c + drivers/timer_stm32f4xx.c + drivers/uart_inverter.c + drivers/dma_stm32f4xx.c + drivers/sdcard/sdmmc_sdio_f4xx.c +) +main_sources(STM32F4_SRC) + +set(STM32F4_VCP_SRC + stm32f4xx_it.c + usb_bsp.c + usbd_desc.c + usbd_usr.c + usbd_cdc_vcp.c +) +list(TRANSFORM STM32F4_VCP_SRC PREPEND "${STM32F4_VCP_DIR}/") + +set(STM32F4_MSC_SRC + drivers/usb_msc_f4xx.c +) +main_sources(STM32F4_MSC_SRC) + +set(STM32F4_INCLUDE_DIRS + "${CMSIS_INCLUDE_DIR}" + "${CMSIS_DSP_INCLUDE_DIR}" + "${STM32F4_STDPERIPH_DIR}/inc" + "${STM32F4_CMSIS_DEVICE_DIR}" + "${STM32F4_CMSIS_DRIVERS_DIR}" + "${STM32F4_VCP_DIR}" +) + +set(STM32F4_DEFINITIONS + STM32F4 + USE_STDPERIPH_DRIVER + ARM_MATH_MATRIX_CHECK + ARM_MATH_ROUNDING + __FPU_PRESENT=1 + UNALIGNED_SUPPORT_DISABLE + ARM_MATH_CM4 +) + +set(STM32F4_COMMON_OPTIONS + -mthumb + -mcpu=cortex-m4 + -march=armv7e-m + -mfloat-abi=hard + -mfpu=fpv4-sp-d16 + -fsingle-precision-constant +) + +set(STM32F4_COMPILE_OPTIONS +) + +set(SETM32F4_LINK_OPTIONS +) + +function(target_stm32f4xx name startup ldscript) + target_stm32(${name} ${startup} ${ldscript} ${ARGN}) + target_sources(${name} PRIVATE ${STM32F4_SRC}) + target_compile_options(${name} PRIVATE ${STM32F4_COMMON_OPTIONS} ${STM32F4_COMPILE_OPTIONS}) + target_include_directories(${name} PRIVATE ${STM32_STDPERIPH_USB_INCLUDE_DIRS} ${STM32F4_INCLUDE_DIRS}) + target_compile_definitions(${name} PRIVATE ${STM32F4_DEFINITIONS}) + target_link_options(${name} PRIVATE ${STM32F4_COMMON_OPTIONS} ${STM32F4_LINK_OPTIONS}) + + get_property(features TARGET ${name} PROPERTY FEATURES) + if(VCP IN_LIST features) + target_sources(${name} PRIVATE ${STM32_STDPERIPH_USB_SRC} ${STM32F4_VCP_SRC}) + endif() + if(MSC IN_LIST features) + target_sources(${name} PRIVATE ${STM32F4_MSC_SRC}) + endif() +endfunction() + +set(STM32F405_COMPILE_DEFINITIONS + STM32F40_41xxx + STM32F405xx + FLASH_SIZE=1024 +) + +function(target_stm32f405 name) + target_stm32f4xx(${name} startup_stm32f40xx.s stm32_flash_f405.ld ${ARGN}) + target_sources(${name} PRIVATE ${STM32F4_STDPERIPH_SRC}) + target_compile_definitions(${name} PRIVATE ${STM32F405_COMPILE_DEFINITIONS}) + setup_firmware_target(${name}) +endfunction() + +set(STM32F411_OR_F427_STDPERIPH_SRC ${STM32F4_STDPERIPH_SRC}) +set(STM32F411_OR_F427_STDPERIPH_SRC_EXCLUDES "stm32f4xx_fsmc.c") +exclude_basenames(STM32F411_OR_F427_STDPERIPH_SRC STM32F411_OR_F427_STDPERIPH_SRC_EXCLUDES) + +set(STM32F411_COMPILE_DEFINITIONS + STM32F411xE + FLASH_SIZE=512 +) + +function(target_stm32f411 name) + target_stm32f4xx(${name} startup_stm32f411xe.s stm32_flash_f411.ld) + target_sources(${name} PRIVATE ${STM32F411_OR_F427_STDPERIPH_SRC}) + target_compile_definitions(${name} PRIVATE ${STM32F411_COMPILE_DEFINITIONS}) + setup_firmware_target(${name}) +endfunction() + +set(STM32F427_COMPILE_DEFINITIONS + STM32F427_437xx + FLASH_SIZE=1024 +) +function(target_stm32f427 name) + target_stm32f4xx(${name} startup_stm32f427xx.s stm32_flash_f427.ld ${ARGN}) + target_sources(${name} PRIVATE ${STM32F411_OR_F427_STDPERIPH_SRC}) + target_compile_definitions(${name} PRIVATE ${STM32F427_COMPILE_DEFINITIONS}) + setup_firmware_target(${name}) +endfunction() diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt new file mode 100644 index 00000000000..9a263aae2ec --- /dev/null +++ b/src/CMakeLists.txt @@ -0,0 +1 @@ +add_subdirectory(main) diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index a631d744480..0095b7eddf9 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -35,50 +35,143 @@ set(COMMON_SRC config/parameter_group.c config/general_settings.c + drivers/1-wire.c + drivers/1-wire/ds_crc.c + drivers/1-wire/ds2482.c + + drivers/accgyro/accgyro.c + drivers/accgyro/accgyro.h + drivers/accgyro/accgyro_adxl345.c + drivers/accgyro/accgyro_adxl345.h + drivers/accgyro/accgyro_bma280.c + drivers/accgyro/accgyro_bma280.h + drivers/accgyro/accgyro_bmi160.c + drivers/accgyro/accgyro_bmi160.h + drivers/accgyro/accgyro_fake.c + drivers/accgyro/accgyro_fake.h + drivers/accgyro/accgyro_icm20689.c + drivers/accgyro/accgyro_icm20689.h + drivers/accgyro/accgyro_l3g4200d.c + drivers/accgyro/accgyro_l3g4200d.h + drivers/accgyro/accgyro_l3gd20.c + drivers/accgyro/accgyro_l3gd20.h + drivers/accgyro/accgyro_lsm303dlhc.c + drivers/accgyro/accgyro_lsm303dlhc.h + drivers/accgyro/accgyro_mma845x.c + drivers/accgyro/accgyro_mma845x.h + drivers/accgyro/accgyro_mpu.c + drivers/accgyro/accgyro_mpu.h + drivers/accgyro/accgyro_mpu3050.c + drivers/accgyro/accgyro_mpu3050.h + drivers/accgyro/accgyro_mpu6000.c + drivers/accgyro/accgyro_mpu6000.h + drivers/accgyro/accgyro_mpu6050.c + drivers/accgyro/accgyro_mpu6050.h + drivers/accgyro/accgyro_mpu6500.c + drivers/accgyro/accgyro_mpu6500.h + drivers/accgyro/accgyro_mpu9250.c + drivers/accgyro/accgyro_mpu9250.h + drivers/adc.c + + drivers/barometer/barometer.h + drivers/barometer/barometer_bmp085.c + drivers/barometer/barometer_bmp085.h + drivers/barometer/barometer_bmp280.c + drivers/barometer/barometer_bmp280.h + drivers/barometer/barometer_bmp388.c + drivers/barometer/barometer_bmp388.h + drivers/barometer/barometer_fake.c + drivers/barometer/barometer_fake.h + drivers/barometer/barometer_lps25h.c + drivers/barometer/barometer_lps25h.h + drivers/barometer/barometer_ms56xx.c + drivers/barometer/barometer_ms56xx.h + drivers/barometer/barometer_spl06.c + drivers/barometer/barometer_spl06.h + drivers/buf_writer.c drivers/bus.c drivers/bus_busdev_i2c.c drivers/bus_busdev_spi.c drivers/bus_i2c_soft.c drivers/bus_spi.c + + drivers/compass/compass.h + drivers/compass/compass_ak8963.c + drivers/compass/compass_ak8963.h + drivers/compass/compass_ak8975.c + drivers/compass/compass_ak8975.h + drivers/compass/compass_fake.c + drivers/compass/compass_fake.h + drivers/compass/compass_hmc5883l.c + drivers/compass/compass_hmc5883l.h + drivers/compass/compass_ist8308.c + drivers/compass/compass_ist8308.h + drivers/compass/compass_ist8310.c + drivers/compass/compass_ist8310.h + drivers/compass/compass_lis3mdl.c + drivers/compass/compass_lis3mdl.h + drivers/compass/compass_mag3110.c + drivers/compass/compass_mag3110.h + drivers/compass/compass_mpu9250.c + drivers/compass/compass_mpu9250.h + drivers/compass/compass_qmc5883l.c + drivers/compass/compass_qmc5883l.h + drivers/display.c drivers/display_canvas.c drivers/display_font_metadata.c + drivers/display_ug2864hsweg01.c drivers/exti.c + drivers/flash.c + drivers/flash_m25p16.c drivers/io.c drivers/io_pca9685.c drivers/irlock.c drivers/light_led.c + drivers/light_ws2811strip.c + drivers/lights_io.c + drivers/max7456.c + + drivers/opflow/opflow_fake.c + drivers/opflow/opflow_virtual.c + drivers/osd.c drivers/persistent.c - drivers/resource.c - drivers/rx_nrf24l01.c - drivers/rx_spi.c - drivers/rx_xn297.c drivers/pitotmeter_adc.c + drivers/pitotmeter_ms4525.c drivers/pitotmeter_virtual.c drivers/pwm_esc_detect.c drivers/pwm_mapping.c drivers/pwm_output.c drivers/pinio.c + + drivers/rangefinder/rangefinder_hcsr04.c + drivers/rangefinder/rangefinder_hcsr04_i2c.c + drivers/rangefinder/rangefinder_srf10.c + drivers/rangefinder/rangefinder_vl53l0x.c + drivers/rangefinder/rangefinder_virtual.c + + drivers/resource.c drivers/rcc.c + drivers/rx_nrf24l01.c drivers/rx_pwm.c + drivers/rx_spi.c + drivers/rx_xn297.c drivers/serial.c drivers/serial_uart.c drivers/sound_beeper.c drivers/stack_check.c drivers/system.c + + drivers/temperature/ds18b20.c + drivers/temperature/lm75.c + drivers/time.c drivers/timer.c drivers/usb_msc.c - drivers/lights_io.c - drivers/1-wire.c - drivers/1-wire/ds_crc.c - drivers/1-wire/ds2482.c - drivers/temperature/ds18b20.c - drivers/temperature/lm75.c - drivers/pitotmeter_ms4525.c + drivers/vtx_common.c fc/cli.c fc/config.c @@ -186,33 +279,6 @@ set(COMMON_SRC cms/cms_menu_saveexit.c cms/cms_menu_vtx.c - drivers/accgyro/accgyro_mpu6000.c - drivers/accgyro/accgyro_mpu6500.c - drivers/barometer/barometer_bmp085.c - drivers/barometer/barometer_bmp280.c - drivers/barometer/barometer_ms56xx.c - drivers/compass/compass_ak8975.c - drivers/compass/compass_hmc5883l.c - drivers/compass/compass_mag3110.c - drivers/compass/compass_qmc5883l.c - drivers/compass/compass_ist8308.c - drivers/compass/compass_ist8310.c - drivers/compass/compass_lis3mdl.c - drivers/display_ug2864hsweg01.c - drivers/flash.c - drivers/flash_m25p16.c - drivers/light_ws2811strip.c - drivers/max7456.c - drivers/rangefinder/rangefinder_hcsr04.c - drivers/rangefinder/rangefinder_hcsr04_i2c.c - drivers/rangefinder/rangefinder_srf10.c - drivers/rangefinder/rangefinder_vl53l0x.c - drivers/rangefinder/rangefinder_virtual.c - drivers/opflow/opflow_fake.c - drivers/opflow/opflow_virtual.c - drivers/pitotmeter_adc.c - drivers/vtx_common.c - io/rangefinder_msp.c io/rangefinder_benewake.c io/opflow_cxof.c diff --git a/src/main/target/AIKONF4/CMakeLists.txt b/src/main/target/AIKONF4/CMakeLists.txt new file mode 100644 index 00000000000..483f54efbbc --- /dev/null +++ b/src/main/target/AIKONF4/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405(AIKONF4) diff --git a/src/main/target/AIRBOTF4/CMakeLists.txt b/src/main/target/AIRBOTF4/CMakeLists.txt new file mode 100644 index 00000000000..b86030b6e8f --- /dev/null +++ b/src/main/target/AIRBOTF4/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405(AIRBOTF4) diff --git a/src/main/target/ASGARD32F4/CMakeLists.txt b/src/main/target/ASGARD32F4/CMakeLists.txt new file mode 100644 index 00000000000..ec7bd4458e8 --- /dev/null +++ b/src/main/target/ASGARD32F4/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405(ASGARD32F4) diff --git a/src/main/target/BEEROTORF4/CMakeLists.txt b/src/main/target/BEEROTORF4/CMakeLists.txt new file mode 100644 index 00000000000..a30103b89dd --- /dev/null +++ b/src/main/target/BEEROTORF4/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405(BEEROTORF4) diff --git a/src/main/target/BETAFLIGHTF4/CMakeLists.txt b/src/main/target/BETAFLIGHTF4/CMakeLists.txt new file mode 100644 index 00000000000..0160a3c7efd --- /dev/null +++ b/src/main/target/BETAFLIGHTF4/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405(BETAFLIGHTF4) diff --git a/src/main/target/BLUEJAYF4/CMakeLists.txt b/src/main/target/BLUEJAYF4/CMakeLists.txt new file mode 100644 index 00000000000..ba93ee7b423 --- /dev/null +++ b/src/main/target/BLUEJAYF4/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405(BLUEJAYF4) diff --git a/src/main/target/CLRACINGF4AIR/CMakeLists.txt b/src/main/target/CLRACINGF4AIR/CMakeLists.txt new file mode 100644 index 00000000000..b2566244c30 --- /dev/null +++ b/src/main/target/CLRACINGF4AIR/CMakeLists.txt @@ -0,0 +1,3 @@ +target_stm32f405(CLRACINGF4AIR) +target_stm32f405(CLRACINGF4AIRV2) +target_stm32f405(CLRACINGF4AIRV3) diff --git a/src/main/target/COLIBRI/CMakeLists.txt b/src/main/target/COLIBRI/CMakeLists.txt new file mode 100644 index 00000000000..355c8d3e025 --- /dev/null +++ b/src/main/target/COLIBRI/CMakeLists.txt @@ -0,0 +1,2 @@ +target_stm32f405(COLIBRI HSE_MHZ 16) +target_stm32f405(QUANTON HSE_MHZ 16) diff --git a/src/main/target/DALRCF405/CMakeLists.txt b/src/main/target/DALRCF405/CMakeLists.txt new file mode 100644 index 00000000000..43f7c6c669d --- /dev/null +++ b/src/main/target/DALRCF405/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405(DALRCF405) diff --git a/src/main/target/F4BY/CMakeLists.txt b/src/main/target/F4BY/CMakeLists.txt new file mode 100644 index 00000000000..532ae1bfd40 --- /dev/null +++ b/src/main/target/F4BY/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405(F4BY) diff --git a/src/main/target/FF_F35_LIGHTNING/CMakeLists.txt b/src/main/target/FF_F35_LIGHTNING/CMakeLists.txt new file mode 100644 index 00000000000..d575693d719 --- /dev/null +++ b/src/main/target/FF_F35_LIGHTNING/CMakeLists.txt @@ -0,0 +1,2 @@ +target_stm32f405(FF_F35_LIGHTNING) +target_stm32f405(WINGFC) diff --git a/src/main/target/FF_FORTINIF4/CMakeLists.txt b/src/main/target/FF_FORTINIF4/CMakeLists.txt new file mode 100644 index 00000000000..51eb0287a89 --- /dev/null +++ b/src/main/target/FF_FORTINIF4/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405(FF_FORTINIF4) diff --git a/src/main/target/FF_PIKOF4/CMakeLists.txt b/src/main/target/FF_PIKOF4/CMakeLists.txt new file mode 100644 index 00000000000..d439ef8febe --- /dev/null +++ b/src/main/target/FF_PIKOF4/CMakeLists.txt @@ -0,0 +1,2 @@ +target_stm32f405(FF_PIKOF4) +target_stm32f405(FF_PIKOF4OSD) diff --git a/src/main/target/FIREWORKSV2/CMakeLists.txt b/src/main/target/FIREWORKSV2/CMakeLists.txt new file mode 100644 index 00000000000..8ed374297ff --- /dev/null +++ b/src/main/target/FIREWORKSV2/CMakeLists.txt @@ -0,0 +1,2 @@ +target_stm32f405(FIREWORKSV2) +target_stm32f405(OMNIBUSF4V6) diff --git a/src/main/target/FISHDRONEF4/CMakeLists.txt b/src/main/target/FISHDRONEF4/CMakeLists.txt new file mode 100644 index 00000000000..468386fc689 --- /dev/null +++ b/src/main/target/FISHDRONEF4/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405(FISHDRONEF4) diff --git a/src/main/target/FOXEERF405/CMakeLists.txt b/src/main/target/FOXEERF405/CMakeLists.txt new file mode 100644 index 00000000000..e9136cf0f4e --- /dev/null +++ b/src/main/target/FOXEERF405/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405(FOXEERF405) diff --git a/src/main/target/FRSKYF4/CMakeLists.txt b/src/main/target/FRSKYF4/CMakeLists.txt new file mode 100644 index 00000000000..cb13fbed3ce --- /dev/null +++ b/src/main/target/FRSKYF4/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405(FRSKYF4) diff --git a/src/main/target/FURYF4OSD/CMakeLists.txt b/src/main/target/FURYF4OSD/CMakeLists.txt new file mode 100644 index 00000000000..620d9f3a7bc --- /dev/null +++ b/src/main/target/FURYF4OSD/CMakeLists.txt @@ -0,0 +1,2 @@ +target_stm32f405(FURYF4OSD) +target_stm32f405(MAMBAF405) diff --git a/src/main/target/IFLIGHTF4_TWING/CMakeLists.txt b/src/main/target/IFLIGHTF4_TWING/CMakeLists.txt new file mode 100644 index 00000000000..048646799df --- /dev/null +++ b/src/main/target/IFLIGHTF4_TWING/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405(IFLIGHTF4_TWING) diff --git a/src/main/target/KAKUTEF4/CMakeLists.txt b/src/main/target/KAKUTEF4/CMakeLists.txt new file mode 100644 index 00000000000..84419108726 --- /dev/null +++ b/src/main/target/KAKUTEF4/CMakeLists.txt @@ -0,0 +1,2 @@ +target_stm32f405(KAKUTEF4) +target_stm32f405(KAKUTEF4V2) diff --git a/src/main/target/MAMBAF405US/CMakeLists.txt b/src/main/target/MAMBAF405US/CMakeLists.txt new file mode 100644 index 00000000000..270627d9138 --- /dev/null +++ b/src/main/target/MAMBAF405US/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405(MAMBAF405US) diff --git a/src/main/target/MATEKF405/CMakeLists.txt b/src/main/target/MATEKF405/CMakeLists.txt new file mode 100644 index 00000000000..8ffba845e58 --- /dev/null +++ b/src/main/target/MATEKF405/CMakeLists.txt @@ -0,0 +1,3 @@ +target_stm32f405(MATEKF405) +target_stm32f405(MATEKF405_SERVOS6) +target_stm32f405(MATEKF405OSD) diff --git a/src/main/target/MATEKF405SE/CMakeLists.txt b/src/main/target/MATEKF405SE/CMakeLists.txt new file mode 100644 index 00000000000..4fedcde60a8 --- /dev/null +++ b/src/main/target/MATEKF405SE/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405(MATEKF405SE) diff --git a/src/main/target/OMNIBUSF4/CMakeLists.txt b/src/main/target/OMNIBUSF4/CMakeLists.txt new file mode 100644 index 00000000000..b6c2077d0f1 --- /dev/null +++ b/src/main/target/OMNIBUSF4/CMakeLists.txt @@ -0,0 +1,12 @@ +target_stm32f405(DYSF4PRO) +target_stm32f405(DYSF4PROV2) +target_stm32f405(OMNIBUSF4) +# the OMNIBUSF4SD has an SDCARD instead of flash, a BMP280 baro and therefore a slightly different ppm/pwm and SPI mapping +target_stm32f405(OMNIBUSF4PRO) +target_stm32f405(OMNIBUSF4PRO_LEDSTRIPM5) +target_stm32f405(OMNIBUSF4V3_S5_S6_2SS) +target_stm32f405(OMNIBUSF4V3_S5S6_SS) +target_stm32f405(OMNIBUSF4V3_S6_SS) +# OMNIBUSF4V3 is a (almost identical) variant of OMNIBUSF4PRO target, +# except for an inverter on UART6. +target_stm32f405(OMNIBUSF4V3) diff --git a/src/main/target/PIXRACER/CMakeLists.txt b/src/main/target/PIXRACER/CMakeLists.txt new file mode 100644 index 00000000000..d55ca6feffb --- /dev/null +++ b/src/main/target/PIXRACER/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f427(PIXRACER HSE_MHZ 24) diff --git a/src/main/target/REVO/CMakeLists.txt b/src/main/target/REVO/CMakeLists.txt new file mode 100644 index 00000000000..4b7a04fb539 --- /dev/null +++ b/src/main/target/REVO/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405(REVO) diff --git a/src/main/target/SPARKY2/CMakeLists.txt b/src/main/target/SPARKY2/CMakeLists.txt new file mode 100644 index 00000000000..ea3e9b15d8a --- /dev/null +++ b/src/main/target/SPARKY2/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405(SPARKY2) diff --git a/src/main/target/SPEEDYBEEF4/CMakeLists.txt b/src/main/target/SPEEDYBEEF4/CMakeLists.txt new file mode 100644 index 00000000000..ed18e3403cf --- /dev/null +++ b/src/main/target/SPEEDYBEEF4/CMakeLists.txt @@ -0,0 +1,3 @@ +target_stm32f405(SPEEDYBEEF4) +target_stm32f405(SPEEDYBEEF4_SFTSRL1) +target_stm32f405(SPEEDYBEEF4_SFTSRL2) diff --git a/src/main/target/SPRACINGF4EVO/CMakeLists.txt b/src/main/target/SPRACINGF4EVO/CMakeLists.txt new file mode 100644 index 00000000000..0b9e390d717 --- /dev/null +++ b/src/main/target/SPRACINGF4EVO/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405(SPRACINGF4EVO) From 57e21bf310ced4bc627a776824417209772063f9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Tue, 9 Jun 2020 15:02:49 +0100 Subject: [PATCH 142/248] [BUILD] Fix .hex and .map generation with cmake --- CMakeLists.txt | 2 ++ cmake/stm32.cmake | 16 +++++++++++----- 2 files changed, 13 insertions(+), 5 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index df804980cd1..a9c54dc8031 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -40,6 +40,8 @@ set(INAV_MAIN_SRC_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src/main") list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake") +set(FIRMWARE_VERSION ${PROJECT_VERSION}) + include(settings) include(inav) include(stm32) diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake index 0f8bc44e9bc..096b27ad7a2 100644 --- a/cmake/stm32.cmake +++ b/cmake/stm32.cmake @@ -106,7 +106,7 @@ set(STM32_LINK_OPTIONS -nostartfiles --specs=nano.specs -static - -Wl,-gc-sections,-Map,target.map + -Wl,-gc-sections -Wl,-L${STM32_LINKER_DIR} -Wl,--cref -Wl,--no-wchar-size-warning @@ -155,6 +155,7 @@ function(target_stm32 name startup ldscript) target_sources(${name} PRIVATE ${target_c_sources} ${target_h_sources}) target_sources(${name} PRIVATE "${STM32_STARTUP_DIR}/${startup}") target_link_options(${name} PRIVATE "-T${STM32_LINKER_DIR}/${ldscript}") + target_link_options(${name} PRIVATE "-Wl,-Map,$.map") target_include_directories(${name} PRIVATE . ${STM32_INCLUDE_DIRS}) target_link_libraries(${name} PRIVATE ${STM32_LINK_LIBRARIES}) target_link_options(${name} PRIVATE ${STM32_LINK_OPTIONS}) @@ -182,16 +183,21 @@ function(target_stm32 name startup ldscript) endif() endif() # Generate .hex + # XXX: Generator expressions are not supported for add_custom_command() + # OUTPUT nor BYPRODUCTS, so we can't rely of them. Instead, build the filename + # for the .hex from the target name set(hexdir "${CMAKE_BINARY_DIR}/hex") - set(hex "${hexdir}/$.hex") + set(hex "${hexdir}/${PROJECT_NAME}_${name}_${FIRMWARE_VERSION}.hex") add_custom_command(TARGET ${name} POST_BUILD - COMMAND ${CMAKE_COMMAND} -E make_directory "${hexdir}" - COMMAND ${CMAKE_OBJCOPY} -Oihex $ "${hex}") + COMMAND ${CMAKE_COMMAND} -E make_directory ${hexdir} + COMMAND ${CMAKE_OBJCOPY} -Oihex $ ${hex} + BYPRODUCTS ${hex} + ) # clean_ set(clean_target "clean_${name}") add_custom_target(${clean_target} COMMAND cmake -E rm -r "${CMAKE_CURRENT_BINARY_DIR}" - COMMENT "Removeng intermediate files for ${name}") + COMMENT "Removing intermediate files for ${name}") set_property(TARGET ${clean_target} PROPERTY TARGET_MESSAGES OFF EXCLUDE_FROM_ALL 1 From fedabef03e056a7cf6f7be1756298907aa0c3c7b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Wed, 8 Jul 2020 21:21:00 +0100 Subject: [PATCH 143/248] [BUILD] Add support for building F3 targets with cmake --- cmake/arm-none-eabi.cmake | 2 +- cmake/cortex-m4f.cmake | 23 ++++++ cmake/stm32-usb.cmake | 58 ------------- cmake/stm32.cmake | 15 ++-- cmake/stm32f3-usb.cmake | 16 ++++ cmake/stm32f3.cmake | 81 +++++++++++++++++++ cmake/stm32f4-usb.cmake | 55 +++++++++++++ cmake/stm32f4.cmake | 35 +++----- src/main/target/AIRHEROF3/CMakeLists.txt | 2 + src/main/target/BETAFLIGHTF3/CMakeLists.txt | 1 + src/main/target/FALCORE/CMakeLists.txt | 1 + src/main/target/FRSKYF3/CMakeLists.txt | 1 + src/main/target/FURYF3/CMakeLists.txt | 2 + src/main/target/KFC32F3_INAV/CMakeLists.txt | 1 + src/main/target/LUX_RACE/CMakeLists.txt | 1 + src/main/target/MOTOLAB/CMakeLists.txt | 1 + src/main/target/OMNIBUS/CMakeLists.txt | 1 + src/main/target/PIKOBLX/CMakeLists.txt | 1 + src/main/target/RCEXPLORERF3/CMakeLists.txt | 1 + src/main/target/RMDO/CMakeLists.txt | 1 + src/main/target/SPARKY/CMakeLists.txt | 1 + src/main/target/SPRACINGF3/CMakeLists.txt | 1 + src/main/target/SPRACINGF3EVO/CMakeLists.txt | 2 + src/main/target/SPRACINGF3MINI/CMakeLists.txt | 1 + 24 files changed, 214 insertions(+), 90 deletions(-) create mode 100644 cmake/cortex-m4f.cmake delete mode 100644 cmake/stm32-usb.cmake create mode 100644 cmake/stm32f3-usb.cmake create mode 100644 cmake/stm32f3.cmake create mode 100644 cmake/stm32f4-usb.cmake create mode 100644 src/main/target/AIRHEROF3/CMakeLists.txt create mode 100644 src/main/target/BETAFLIGHTF3/CMakeLists.txt create mode 100644 src/main/target/FALCORE/CMakeLists.txt create mode 100644 src/main/target/FRSKYF3/CMakeLists.txt create mode 100644 src/main/target/FURYF3/CMakeLists.txt create mode 100644 src/main/target/KFC32F3_INAV/CMakeLists.txt create mode 100644 src/main/target/LUX_RACE/CMakeLists.txt create mode 100644 src/main/target/MOTOLAB/CMakeLists.txt create mode 100644 src/main/target/OMNIBUS/CMakeLists.txt create mode 100644 src/main/target/PIKOBLX/CMakeLists.txt create mode 100644 src/main/target/RCEXPLORERF3/CMakeLists.txt create mode 100644 src/main/target/RMDO/CMakeLists.txt create mode 100644 src/main/target/SPARKY/CMakeLists.txt create mode 100644 src/main/target/SPRACINGF3/CMakeLists.txt create mode 100644 src/main/target/SPRACINGF3EVO/CMakeLists.txt create mode 100644 src/main/target/SPRACINGF3MINI/CMakeLists.txt diff --git a/cmake/arm-none-eabi.cmake b/cmake/arm-none-eabi.cmake index 18c6102991a..066bedf5642 100644 --- a/cmake/arm-none-eabi.cmake +++ b/cmake/arm-none-eabi.cmake @@ -47,7 +47,7 @@ set(CMAKE_BUILD_TYPE RelWithDebInfo CACHE STRING "Build Type" FORCE) set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS ${CMAKE_CONFIGURATION_TYPES}) set(arm_none_eabi_debug "-Og -g") -set(arm_none_eabi_release "-O2 -DNDEBUG -flto -fuse-linker-plugin") +set(arm_none_eabi_release "-Os -DNDEBUG -flto -fuse-linker-plugin") set(arm_none_eabi_relwithdebinfo "-ggdb3 ${arm_none_eabi_release}") SET(CMAKE_C_FLAGS_DEBUG ${arm_none_eabi_debug} CACHE INTERNAL "c compiler flags debug") diff --git a/cmake/cortex-m4f.cmake b/cmake/cortex-m4f.cmake new file mode 100644 index 00000000000..981af7a8ff3 --- /dev/null +++ b/cmake/cortex-m4f.cmake @@ -0,0 +1,23 @@ +set(CORTEX_M4F_COMMON_OPTIONS + -mthumb + -mcpu=cortex-m4 + -march=armv7e-m + -mfloat-abi=hard + -mfpu=fpv4-sp-d16 + -fsingle-precision-constant + -Wdouble-promotion +) + +set(CORTEX_M4F_COMPILE_OPTIONS +) + +set(CORTEX_M4F_LINK_OPTIONS +) + +set(CORTEX_M4F_DEFINITIONS + __FPU_PRESENT=1 + ARM_MATH_CM4 + ARM_MATH_MATRIX_CHECK + ARM_MATH_ROUNDING + UNALIGNED_SUPPORT_DISABLE +) diff --git a/cmake/stm32-usb.cmake b/cmake/stm32-usb.cmake deleted file mode 100644 index 2ae663e46d8..00000000000 --- a/cmake/stm32-usb.cmake +++ /dev/null @@ -1,58 +0,0 @@ -set(STM32_STDPERIPH_USBOTG_DIR "${INAV_LIB_DIR}/main/STM32_USB_OTG_Driver") -set(STM32_STDPERIPH_USBCORE_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Core") -set(STM32_STDPERIPH_USBCDC_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/cdc") -set(STM32_STDPERIPH_USBHID_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/hid") -set(STM32_STDPERIPH_USBWRAPPER_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/hid_cdc_wrapper") -set(STM32_STDPERIPH_USBMSC_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/msc") -set(STM32_STDPERIPH_USBFS_DIR "${INAV_LIB_DIR}/main/STM32_USB-FS-Device_Driver") - -set(STM32_STDPERIPH_USB_INCLUDE_DIRS - "${STM32_STDPERIPH_USBOTG_DIR}/inc" - "${STM32_STDPERIPH_USBCORE_DIR}/inc" - "${STM32_STDPERIPH_USBCDC_DIR}/inc" - "${STM32_STDPERIPH_USBHID_DIR}/inc" - "${STM32_STDPERIPH_USBWRAPPER_DIR}/inc" - "${STM32_STDPERIPH_USBMSC_DIR}/inc" - "${STM32_STDPERIPH_USBFS_DIR}/inc" -) - -set(STM32_STDPERIPH_USBOTG_SRC - usb_core.c - usb_dcd.c - usb_dcd_int.c -) -list(TRANSFORM STM32_STDPERIPH_USBOTG_SRC PREPEND "${STM32_STDPERIPH_USBOTG_DIR}/src/") - -set(STM32_STDPERIPH_USBCORE_SRC - usbd_core.c - usbd_ioreq.c - usbd_req.c -) -list(TRANSFORM STM32_STDPERIPH_USBCORE_SRC PREPEND "${STM32_STDPERIPH_USBCORE_DIR}/src/") - -set(STM32_STDPERIPH_USBCDC_SRC - "${STM32_STDPERIPH_USBCDC_DIR}/src/usbd_cdc_core.c" -) - -set(STM32_STDPERIPH_USBHID_SRC - "${STM32_STDPERIPH_USBHID_DIR}/src/usbd_hid_core.c" -) - -set(STM32_STDPERIPH_USBWRAPPER_SRC - "${STM32_STDPERIPH_USBWRAPPER_DIR}/src/usbd_hid_cdc_wrapper.c" -) - -set(STM32_STDPERIPH_USBMSC_SRC - usbd_msc_bot.c - usbd_msc_core.c - usbd_msc_data.c - usbd_msc_scsi.c -) -list(TRANSFORM STM32_STDPERIPH_USBMSC_SRC PREPEND "${STM32_STDPERIPH_USBMSC_DIR}/src/") - -list(APPEND STM32_STDPERIPH_USB_SRC ${STM32_STDPERIPH_USBOTG_SRC}) -list(APPEND STM32_STDPERIPH_USB_SRC ${STM32_STDPERIPH_USBCORE_SRC}) -list(APPEND STM32_STDPERIPH_USB_SRC ${STM32_STDPERIPH_USBCDC_SRC}) -list(APPEND STM32_STDPERIPH_USB_SRC ${STM32_STDPERIPH_USBHID_SRC}) -list(APPEND STM32_STDPERIPH_USB_SRC ${STM32_STDPERIPH_USBWRAPPER_SRC}) -list(APPEND STM32_STDPERIPH_USB_SRC ${STM32_STDPERIPH_USBMSC_SRC}) diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake index 096b27ad7a2..930519c8c56 100644 --- a/cmake/stm32.cmake +++ b/cmake/stm32.cmake @@ -1,6 +1,6 @@ include(arm-none-eabi) +include(stm32f3) include(stm32f4) -include(stm32-usb) include(CMakeParseArguments) @@ -137,10 +137,10 @@ function(target_stm32 name startup ldscript) # Parse keyword arguments cmake_parse_arguments( PARSED_ARGS - "" # No boolean arguments - "HSE_MHZ" # Single value arguments - "" # No multi-value arguments - ${ARGN} # Start parsing after the known arguments + "DISABLE_MSC" # Boolean arguments + "HSE_MHZ" # Single value arguments + "DEFINITIONS" # Multi-value arguments + ${ARGN} # Start parsing after the known arguments ) if (PARSED_ARGS_HSE_MHZ) set(hse_mhz ${PARSED_ARGS_HSE_MHZ}) @@ -163,6 +163,9 @@ function(target_stm32 name startup ldscript) set(target_definitions ${STM32_DEFINITIONS}) math(EXPR hse_value "${hse_mhz} * 1000000") list(APPEND target_definitions "HSE_VALUE=${hse_value}") + if(PARSED_ARGS_DEFINITIONS) + list(APPEND target_definitions ${PARSED_ARGS_DEFINITIONS}) + endif() target_compile_definitions(${name} PRIVATE ${target_definitions}) get_stm32_target_features(features "${CMAKE_CURRENT_SOURCE_DIR}") @@ -173,7 +176,7 @@ function(target_stm32 name startup ldscript) if(SDCARD IN_LIST features) target_sources(${name} PRIVATE ${STM32_SDCARD_SRC} ${STM32_ASYNCFATFS_SRC}) endif() - if(MSC IN_LIST features) + if(NOT PARSED_ARGS_DISABLE_MSC AND MSC IN_LIST features) target_sources(${name} PRIVATE ${STM32_MSC_SRC}) if (FLASHFS IN_LIST features) target_sources(${name} PRIVATE ${STM32_MSC_FLASH_SRC}) diff --git a/cmake/stm32f3-usb.cmake b/cmake/stm32f3-usb.cmake new file mode 100644 index 00000000000..231608757a1 --- /dev/null +++ b/cmake/stm32f3-usb.cmake @@ -0,0 +1,16 @@ +set(STM32_USBFS_DIR "${INAV_LIB_DIR}/main/STM32_USB-FS-Device_Driver") + +set(STM32_USBFS_SRC + usb_core.c + usb_init.c + usb_int.c + usb_mem.c + usb_regs.c + usb_sil.c +) +list(TRANSFORM STM32_USBFS_SRC PREPEND "${STM32_USBFS_DIR}/src/") + +set(STM32F3_USB_INCLUDE_DIRS + ${STM32_USBFS_DIR}/inc +) +set(STM32F3_USB_SRC ${STM32_USBFS_SRC}) diff --git a/cmake/stm32f3.cmake b/cmake/stm32f3.cmake new file mode 100644 index 00000000000..cbce55354b5 --- /dev/null +++ b/cmake/stm32f3.cmake @@ -0,0 +1,81 @@ +include(cortex-m4f) +include(stm32f3-usb) + +set(STM32F3_STDPERIPH_DIR "${INAV_LIB_DIR}/main/STM32F3/Drivers/STM32F30x_StdPeriph_Driver") +set(STM32F3_CMSIS_DEVICE_DIR "${INAV_LIB_DIR}/main/STM32F3/Drivers/CMSIS/Device/ST/STM32F30x") +set(STM32F3_CMSIS_DRIVERS_DIR "${INAV_LIB_DIR}/main/STM32F3/Drivers/CMSIS") +set(STM32F3_VCP_DIR "${INAV_MAIN_SRC_DIR}/vcp") + +set(STM32F3_STDPERIPH_SRC_EXCLUDES + stm32f30x_crc.c + stm32f30x_can.c +) +set(STM32F3_STDPERIPH_SRC_DIR "${STM32F3_STDPERIPH_DIR}/Src") +glob_except(STM32F3_STDPERIPH_SRC "${STM32F3_STDPERIPH_SRC_DIR}/*.c" STM32F3_STDPERIPH_SRC_EXCLUDES) + + +set(STM32F3_SRC + target/system_stm32f30x.c + drivers/adc_stm32f30x.c + drivers/bus_i2c_stm32f30x.c + drivers/dma_stm32f3xx.c + drivers/serial_uart_stm32f30x.c + drivers/system_stm32f30x.c + drivers/timer_impl_stdperiph.c + drivers/timer_stm32f30x.c +) +main_sources(STM32F3_SRC) + +set(STM32F3_VCP_SRC + hw_config.c + stm32_it.c + usb_desc.c + usb_endp.c + usb_istr.c + usb_prop.c + usb_pwr.c +) +list(TRANSFORM STM32F3_VCP_SRC PREPEND "${STM32F3_VCP_DIR}/") + +set(STM32F3_INCLUDE_DIRS + "${CMSIS_INCLUDE_DIR}" + "${CMSIS_DSP_INCLUDE_DIR}" + "${STM32F3_STDPERIPH_DIR}/inc" + "${STM32F3_CMSIS_DEVICE_DIR}" + "${STM32F3_CMSIS_DRIVERS_DIR}" + "${STM32F3_VCP_DIR}" +) + +set(STM32F3_DEFINITIONS + ${CORTEX_M4F_DEFINITIONS} + STM32F3 + USE_STDPERIPH_DRIVER +) + +set(STM32F303_DEFINITIONS + STM32F303 + STM32F303xC + FLASH_SIZE=256 +) + +function(target_stm32f3xx name startup ldscript) + # F3 targets don't support MSC + target_stm32(${name} ${startup} ${ldscript} DISABLE_MSC ${ARGN}) + target_sources(${name} PRIVATE ${STM32F3_STDPERIPH_SRC} ${STM32F3_SRC}) + target_compile_options(${name} PRIVATE ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_COMPILE_OPTIONS}) + target_include_directories(${name} PRIVATE ${STM32F3_INCLUDE_DIRS}) + target_compile_definitions(${name} PRIVATE ${STM32F3_DEFINITIONS}) + target_link_options(${name} PRIVATE ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_LINK_OPTIONS}) + + get_property(features TARGET ${name} PROPERTY FEATURES) + if(VCP IN_LIST features) + target_include_directories(${name} PRIVATE ${STM32F3_USB_INCLUDE_DIRS}) + target_sources(${name} PRIVATE ${STM32F3_USB_SRC} ${STM32F3_VCP_SRC}) + endif() +endfunction() + +function(target_stm32f303 name) + target_stm32f3xx(${name} startup_stm32f30x_md_gcc.S stm32_flash_f303_256k.ld ${ARGN}) + target_compile_definitions(${name} PRIVATE ${STM32F303_DEFINITIONS}) + setup_firmware_target(${name}) +endfunction() diff --git a/cmake/stm32f4-usb.cmake b/cmake/stm32f4-usb.cmake new file mode 100644 index 00000000000..3fbaec4d8dd --- /dev/null +++ b/cmake/stm32f4-usb.cmake @@ -0,0 +1,55 @@ +set(STM32_USBOTG_DIR "${INAV_LIB_DIR}/main/STM32_USB_OTG_Driver") +set(STM32_USBCORE_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Core") +set(STM32_USBCDC_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/cdc") +set(STM32_USBHID_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/hid") +set(STM32_USBWRAPPER_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/hid_cdc_wrapper") +set(STM32_USBMSC_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/msc") + +set(STM32F4_USB_INCLUDE_DIRS + "${STM32_USBOTG_DIR}/inc" + "${STM32_USBCORE_DIR}/inc" + "${STM32_USBCDC_DIR}/inc" + "${STM32_USBHID_DIR}/inc" + "${STM32_USBWRAPPER_DIR}/inc" + "${STM32_USBMSC_DIR}/inc" +) + +set(STM32_USBOTG_SRC + usb_core.c + usb_dcd.c + usb_dcd_int.c +) +list(TRANSFORM STM32_USBOTG_SRC PREPEND "${STM32_USBOTG_DIR}/src/") + +set(STM32_USBCORE_SRC + usbd_core.c + usbd_ioreq.c + usbd_req.c +) +list(TRANSFORM STM32_USBCORE_SRC PREPEND "${STM32_USBCORE_DIR}/src/") + +set(STM32_USBCDC_SRC + "${STM32_USBCDC_DIR}/src/usbd_cdc_core.c" +) + +set(STM32_USBHID_SRC + "${STM32_USBHID_DIR}/src/usbd_hid_core.c" +) + +set(STM32_USBWRAPPER_SRC + "${STM32_USBWRAPPER_DIR}/src/usbd_hid_cdc_wrapper.c" +) + +set(STM32F4_USBMSC_SRC + usbd_msc_bot.c + usbd_msc_core.c + usbd_msc_data.c + usbd_msc_scsi.c +) +list(TRANSFORM STM32F4_USBMSC_SRC PREPEND "${STM32_USBMSC_DIR}/src/") + +list(APPEND STM32F4_USB_SRC ${STM32_USBOTG_SRC}) +list(APPEND STM32F4_USB_SRC ${STM32_USBCORE_SRC}) +list(APPEND STM32F4_USB_SRC ${STM32_USBCDC_SRC}) +list(APPEND STM32F4_USB_SRC ${STM32_USBHID_SRC}) +list(APPEND STM32F4_USB_SRC ${STM32_USBWRAPPER_SRC}) \ No newline at end of file diff --git a/cmake/stm32f4.cmake b/cmake/stm32f4.cmake index 2a0ab719c7c..b5c780e964a 100644 --- a/cmake/stm32f4.cmake +++ b/cmake/stm32f4.cmake @@ -1,3 +1,6 @@ +include(cortex-m4f) +include(stm32f4-usb) + set(STM32F4_STDPERIPH_DIR "${INAV_LIB_DIR}/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver") set(STM32F4_CMSIS_DEVICE_DIR "${INAV_LIB_DIR}/main/STM32F4/Drivers/CMSIS/Device/ST/STM32F4xx") set(STM32F4_CMSIS_DRIVERS_DIR "${INAV_LIB_DIR}/main/STM32F4/Drivers/CMSIS") @@ -69,44 +72,26 @@ set(STM32F4_INCLUDE_DIRS ) set(STM32F4_DEFINITIONS + ${CORTEX_M4F_DEFINITIONS} STM32F4 USE_STDPERIPH_DRIVER - ARM_MATH_MATRIX_CHECK - ARM_MATH_ROUNDING - __FPU_PRESENT=1 - UNALIGNED_SUPPORT_DISABLE - ARM_MATH_CM4 -) - -set(STM32F4_COMMON_OPTIONS - -mthumb - -mcpu=cortex-m4 - -march=armv7e-m - -mfloat-abi=hard - -mfpu=fpv4-sp-d16 - -fsingle-precision-constant -) - -set(STM32F4_COMPILE_OPTIONS -) - -set(SETM32F4_LINK_OPTIONS ) function(target_stm32f4xx name startup ldscript) target_stm32(${name} ${startup} ${ldscript} ${ARGN}) target_sources(${name} PRIVATE ${STM32F4_SRC}) - target_compile_options(${name} PRIVATE ${STM32F4_COMMON_OPTIONS} ${STM32F4_COMPILE_OPTIONS}) - target_include_directories(${name} PRIVATE ${STM32_STDPERIPH_USB_INCLUDE_DIRS} ${STM32F4_INCLUDE_DIRS}) + target_compile_options(${name} PRIVATE ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_COMPILE_OPTIONS}) + target_include_directories(${name} PRIVATE ${STM32F4_INCLUDE_DIRS}) target_compile_definitions(${name} PRIVATE ${STM32F4_DEFINITIONS}) - target_link_options(${name} PRIVATE ${STM32F4_COMMON_OPTIONS} ${STM32F4_LINK_OPTIONS}) + target_link_options(${name} PRIVATE ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_LINK_OPTIONS}) get_property(features TARGET ${name} PROPERTY FEATURES) if(VCP IN_LIST features) - target_sources(${name} PRIVATE ${STM32_STDPERIPH_USB_SRC} ${STM32F4_VCP_SRC}) + target_include_directories(${name} PRIVATE ${STM32F4_USB_INCLUDE_DIRS}) + target_sources(${name} PRIVATE ${STM32F4_USB_SRC} ${STM32F4_VCP_SRC}) endif() if(MSC IN_LIST features) - target_sources(${name} PRIVATE ${STM32F4_MSC_SRC}) + target_sources(${name} PRIVATE ${STM32F4_USBMSC_SRC} ${STM32F4_MSC_SRC}) endif() endfunction() diff --git a/src/main/target/AIRHEROF3/CMakeLists.txt b/src/main/target/AIRHEROF3/CMakeLists.txt new file mode 100644 index 00000000000..f18202b6487 --- /dev/null +++ b/src/main/target/AIRHEROF3/CMakeLists.txt @@ -0,0 +1,2 @@ +target_stm32f303(AIRHEROF3 HSE_MHZ 12) +target_stm32f303(AIRHEROF3_QUAD HSE_MHZ 12) \ No newline at end of file diff --git a/src/main/target/BETAFLIGHTF3/CMakeLists.txt b/src/main/target/BETAFLIGHTF3/CMakeLists.txt new file mode 100644 index 00000000000..728fff1e743 --- /dev/null +++ b/src/main/target/BETAFLIGHTF3/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f303(BETAFLIGHTF3 DEFINITIONS "SPRACINGF3") \ No newline at end of file diff --git a/src/main/target/FALCORE/CMakeLists.txt b/src/main/target/FALCORE/CMakeLists.txt new file mode 100644 index 00000000000..f792193dd66 --- /dev/null +++ b/src/main/target/FALCORE/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f303(FALCORE HSE_MHZ 12) \ No newline at end of file diff --git a/src/main/target/FRSKYF3/CMakeLists.txt b/src/main/target/FRSKYF3/CMakeLists.txt new file mode 100644 index 00000000000..ebd8e1a8b39 --- /dev/null +++ b/src/main/target/FRSKYF3/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f303(FRSKYF3) \ No newline at end of file diff --git a/src/main/target/FURYF3/CMakeLists.txt b/src/main/target/FURYF3/CMakeLists.txt new file mode 100644 index 00000000000..ed0e4238930 --- /dev/null +++ b/src/main/target/FURYF3/CMakeLists.txt @@ -0,0 +1,2 @@ +target_stm32f303(FURYF3) +target_stm32f303(FURYF3_SPIFLASH) \ No newline at end of file diff --git a/src/main/target/KFC32F3_INAV/CMakeLists.txt b/src/main/target/KFC32F3_INAV/CMakeLists.txt new file mode 100644 index 00000000000..5f1543c39fd --- /dev/null +++ b/src/main/target/KFC32F3_INAV/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f303(KFC32F3_INAV) \ No newline at end of file diff --git a/src/main/target/LUX_RACE/CMakeLists.txt b/src/main/target/LUX_RACE/CMakeLists.txt new file mode 100644 index 00000000000..797a42bbec6 --- /dev/null +++ b/src/main/target/LUX_RACE/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f303(LUX_RACE) \ No newline at end of file diff --git a/src/main/target/MOTOLAB/CMakeLists.txt b/src/main/target/MOTOLAB/CMakeLists.txt new file mode 100644 index 00000000000..d3372f5056a --- /dev/null +++ b/src/main/target/MOTOLAB/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f303(MOTOLAB) \ No newline at end of file diff --git a/src/main/target/OMNIBUS/CMakeLists.txt b/src/main/target/OMNIBUS/CMakeLists.txt new file mode 100644 index 00000000000..a87b5286677 --- /dev/null +++ b/src/main/target/OMNIBUS/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f303(OMNIBUS) \ No newline at end of file diff --git a/src/main/target/PIKOBLX/CMakeLists.txt b/src/main/target/PIKOBLX/CMakeLists.txt new file mode 100644 index 00000000000..8ed14ef8757 --- /dev/null +++ b/src/main/target/PIKOBLX/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f303(PIKOBLX) \ No newline at end of file diff --git a/src/main/target/RCEXPLORERF3/CMakeLists.txt b/src/main/target/RCEXPLORERF3/CMakeLists.txt new file mode 100644 index 00000000000..2a069102f9e --- /dev/null +++ b/src/main/target/RCEXPLORERF3/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f303(RCEXPLORERF3) \ No newline at end of file diff --git a/src/main/target/RMDO/CMakeLists.txt b/src/main/target/RMDO/CMakeLists.txt new file mode 100644 index 00000000000..f3a2c36eeba --- /dev/null +++ b/src/main/target/RMDO/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f303(RMDO DEFINITIONS "SPRACINGF3") \ No newline at end of file diff --git a/src/main/target/SPARKY/CMakeLists.txt b/src/main/target/SPARKY/CMakeLists.txt new file mode 100644 index 00000000000..1a6f1f0e23e --- /dev/null +++ b/src/main/target/SPARKY/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f303(SPARKY) \ No newline at end of file diff --git a/src/main/target/SPRACINGF3/CMakeLists.txt b/src/main/target/SPRACINGF3/CMakeLists.txt new file mode 100644 index 00000000000..dae18ee21fb --- /dev/null +++ b/src/main/target/SPRACINGF3/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f303(SPRACINGF3) \ No newline at end of file diff --git a/src/main/target/SPRACINGF3EVO/CMakeLists.txt b/src/main/target/SPRACINGF3EVO/CMakeLists.txt new file mode 100644 index 00000000000..c2dbd822b01 --- /dev/null +++ b/src/main/target/SPRACINGF3EVO/CMakeLists.txt @@ -0,0 +1,2 @@ +target_stm32f303(SPRACINGF3EVO) +target_stm32f303(SPRACINGF3EVO_1SS) \ No newline at end of file diff --git a/src/main/target/SPRACINGF3MINI/CMakeLists.txt b/src/main/target/SPRACINGF3MINI/CMakeLists.txt new file mode 100644 index 00000000000..d9518a0920a --- /dev/null +++ b/src/main/target/SPRACINGF3MINI/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f303(SPRACINGF3MINI) \ No newline at end of file From 477fcfd52a8d65da31c323a6607a669fb1b46ddc Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Wed, 8 Jul 2020 21:22:36 +0100 Subject: [PATCH 144/248] [BUILD] Add missing f405 based target ANYFC --- src/main/target/ANYFC/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) create mode 100644 src/main/target/ANYFC/CMakeLists.txt diff --git a/src/main/target/ANYFC/CMakeLists.txt b/src/main/target/ANYFC/CMakeLists.txt new file mode 100644 index 00000000000..88ab8c97f75 --- /dev/null +++ b/src/main/target/ANYFC/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405(ANYFC) \ No newline at end of file From 65c04ae234c7f76129db2df438e371a889fc0d03 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Fri, 10 Jul 2020 09:42:02 +0100 Subject: [PATCH 145/248] [BUILD] Build F7 based targets with cmake --- cmake/cortex-m7.cmake | 22 ++++ cmake/stm32-stdperiph.cmake | 5 + cmake/stm32.cmake | 46 ++++++- cmake/stm32f3.cmake | 3 +- cmake/stm32f4.cmake | 4 +- cmake/stm32f7-usb.cmake | 48 +++++++ cmake/stm32f7.cmake | 121 ++++++++++++++++++ docs/USB_Mass_Storage_(MSC)_mode.md | 10 +- src/main/CMakeLists.txt | 3 +- src/main/target/AIRBOTF7/CMakeLists.txt | 2 + .../target/ALIENFLIGHTNGF7/CMakeLists.txt | 1 + src/main/target/ANYFCF7/CMakeLists.txt | 2 + src/main/target/ASGARD32F7/CMakeLists.txt | 1 + src/main/target/DALRCF722DUAL/CMakeLists.txt | 1 + src/main/target/FOXEERF722DUAL/CMakeLists.txt | 1 + .../target/IFLIGHTF7_TWING/CMakeLists.txt | 1 + src/main/target/KAKUTEF7/CMakeLists.txt | 3 + src/main/target/MAMBAF722/CMakeLists.txt | 1 + src/main/target/MATEKF722/CMakeLists.txt | 2 + src/main/target/MATEKF722PX/CMakeLists.txt | 1 + src/main/target/MATEKF722SE/CMakeLists.txt | 2 + src/main/target/MATEKF765/CMakeLists.txt | 1 + src/main/target/OMNIBUSF7/CMakeLists.txt | 2 + src/main/target/OMNIBUSF7NXT/CMakeLists.txt | 1 + src/main/target/SPRACINGF7DUAL/CMakeLists.txt | 1 + src/main/target/YUPIF7/CMakeLists.txt | 1 + src/main/target/ZEEZF7/CMakeLists.txt | 1 + 27 files changed, 267 insertions(+), 20 deletions(-) create mode 100644 cmake/cortex-m7.cmake create mode 100644 cmake/stm32-stdperiph.cmake create mode 100644 cmake/stm32f7-usb.cmake create mode 100644 cmake/stm32f7.cmake create mode 100644 src/main/target/AIRBOTF7/CMakeLists.txt create mode 100644 src/main/target/ALIENFLIGHTNGF7/CMakeLists.txt create mode 100644 src/main/target/ANYFCF7/CMakeLists.txt create mode 100644 src/main/target/ASGARD32F7/CMakeLists.txt create mode 100644 src/main/target/DALRCF722DUAL/CMakeLists.txt create mode 100644 src/main/target/FOXEERF722DUAL/CMakeLists.txt create mode 100644 src/main/target/IFLIGHTF7_TWING/CMakeLists.txt create mode 100644 src/main/target/KAKUTEF7/CMakeLists.txt create mode 100644 src/main/target/MAMBAF722/CMakeLists.txt create mode 100644 src/main/target/MATEKF722/CMakeLists.txt create mode 100644 src/main/target/MATEKF722PX/CMakeLists.txt create mode 100644 src/main/target/MATEKF722SE/CMakeLists.txt create mode 100644 src/main/target/MATEKF765/CMakeLists.txt create mode 100644 src/main/target/OMNIBUSF7/CMakeLists.txt create mode 100644 src/main/target/OMNIBUSF7NXT/CMakeLists.txt create mode 100644 src/main/target/SPRACINGF7DUAL/CMakeLists.txt create mode 100644 src/main/target/YUPIF7/CMakeLists.txt create mode 100644 src/main/target/ZEEZF7/CMakeLists.txt diff --git a/cmake/cortex-m7.cmake b/cmake/cortex-m7.cmake new file mode 100644 index 00000000000..f02b9a39187 --- /dev/null +++ b/cmake/cortex-m7.cmake @@ -0,0 +1,22 @@ +set(CORTEX_M7_COMMON_OPTIONS + -mthumb + -mcpu=cortex-m7 + -mfloat-abi=hard + -mfpu=fpv5-sp-d16 + -fsingle-precision-constant + -Wdouble-promotion +) + +set(CORTEX_M7_COMPILE_OPTIONS +) + +set(CORTEX_M7_LINK_OPTIONS +) + +set(CORTEX_M7_DEFINITIONS + __FPU_PRESENT=1 + ARM_MATH_CM7 + ARM_MATH_MATRIX_CHECK + ARM_MATH_ROUNDING + UNALIGNED_SUPPORT_DISABLE +) diff --git a/cmake/stm32-stdperiph.cmake b/cmake/stm32-stdperiph.cmake new file mode 100644 index 00000000000..8b4e9c2f5b6 --- /dev/null +++ b/cmake/stm32-stdperiph.cmake @@ -0,0 +1,5 @@ +set(STM32_STDPERIPH_SRC + drivers/bus_spi.c + drivers/serial_uart.c +) +main_sources(STM32_STDPERIPH_SRC) \ No newline at end of file diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake index 930519c8c56..61f3fc58002 100644 --- a/cmake/stm32.cmake +++ b/cmake/stm32.cmake @@ -1,6 +1,7 @@ include(arm-none-eabi) include(stm32f3) include(stm32f4) +include(stm32f7) include(CMakeParseArguments) @@ -58,10 +59,15 @@ set(STM32_MSC_FLASH_SRC ) main_sources(STM32_MSC_FLASH_SRC) -set(STM32_MSC_SDCARD_SRC +set(STM32_MSC_SDCARD_SPI_SRC msc/usbd_storage_sd_spi.c ) -main_sources(STM32_MSC_SDCARD_SRC) +main_sources(STM32_MSC_SDCARD_SPI_SRC) + +set(STM32_MSC_SDCARD_SDIO_SRC + msc/usbd_storage_sdio.c +) +main_sources(STM32_MSC_SDCARD_SDIO_SRC) set(STM32_INCLUDE_DIRS "${CMSIS_INCLUDE_DIR}" @@ -76,7 +82,7 @@ set(STM32_DEFAULT_HSE_MHZ 8) set(STM32_LINKER_DIR "${INAV_MAIN_SRC_DIR}/target/link") - +set(STM32_LIBS lnosys) #if(SEMIHOSTING) # set(SEMIHOSTING_DEFINITIONS "SEMIHOSTING") # set(SEMIHOSTING_LDFLAGS @@ -102,6 +108,14 @@ set(STM32_LINK_LIBRARIES -lc ) +if(SEMIHOSTING) + # TODO: Is -lc needed again here due to library order or can it be deleted? + list(APPEND STM32_LINK_LIBRARIES --specs=rdimon.specs -lc -lrdimon) + list(APPEND STM32_DEFINITIONS SEMIHOSTING) +else() + list(APPEND STM32_LINK_LIBRARIES -lnosys) +endif() + set(STM32_LINK_OPTIONS -nostartfiles --specs=nano.specs @@ -113,8 +127,17 @@ set(STM32_LINK_OPTIONS -Wl,--print-memory-usage ) -macro(get_stm32_target_features) # out-var dir - file(READ "${ARGV1}/target.h" _contents) +macro(get_stm32_target_features output_var dir target_name) + execute_process(COMMAND "${CMAKE_C_COMPILER}" -E -dD -D${ARGV2} "${ARGV1}/target.h" + ERROR_VARIABLE _errors + RESULT_VARIABLE _result + OUTPUT_STRIP_TRAILING_WHITESPACE + OUTPUT_VARIABLE _contents) + + if(NOT _result EQUAL 0) + message(FATAL_ERROR "error extracting features for stm32 target ${ARGV2}: ${_errors}") + endif() + string(REGEX MATCH "#define[\t ]+USE_VCP" HAS_VCP ${_contents}) if(HAS_VCP) list(APPEND ${ARGV0} VCP) @@ -126,6 +149,10 @@ macro(get_stm32_target_features) # out-var dir string(REGEX MATCH "define[\t ]+USE_SDCARD" HAS_SDCARD ${_contents}) if (HAS_SDCARD) list(APPEND ${ARGV0} SDCARD) + string(REGEX MATCH "define[\t ]+USE_SDCARD_SDIO" HAS_SDIO ${_contents}) + if (HAS_SDIO) + list(APPEND ${ARGV0} SDIO) + endif() endif() if(HAS_FLASHFS OR HAS_SDCARD) list(APPEND ${ARGV0} MSC) @@ -168,7 +195,7 @@ function(target_stm32 name startup ldscript) endif() target_compile_definitions(${name} PRIVATE ${target_definitions}) - get_stm32_target_features(features "${CMAKE_CURRENT_SOURCE_DIR}") + get_stm32_target_features(features "${CMAKE_CURRENT_SOURCE_DIR}" ${name}) set_property(TARGET ${name} PROPERTY FEATURES ${features}) if(VCP IN_LIST features) target_sources(${name} PRIVATE ${STM32_VCP_SRC}) @@ -178,11 +205,16 @@ function(target_stm32 name startup ldscript) endif() if(NOT PARSED_ARGS_DISABLE_MSC AND MSC IN_LIST features) target_sources(${name} PRIVATE ${STM32_MSC_SRC}) + target_compile_definitions(${name} PRIVATE USE_USB_MSC) if (FLASHFS IN_LIST features) target_sources(${name} PRIVATE ${STM32_MSC_FLASH_SRC}) endif() if (SDCARD IN_LIST features) - target_sources(${name} PRIVATE ${STM32_MSC_SDCARD_SRC}) + if (SDIO IN_LIST features) + target_sources(${name} PRIVATE ${STM32_MSC_SDCARD_SDIO_SRC}) + else() + target_sources(${name} PRIVATE ${STM32_MSC_SDCARD_SPI_SRC}) + endif() endif() endif() # Generate .hex diff --git a/cmake/stm32f3.cmake b/cmake/stm32f3.cmake index cbce55354b5..81ff2abc6d3 100644 --- a/cmake/stm32f3.cmake +++ b/cmake/stm32f3.cmake @@ -1,4 +1,5 @@ include(cortex-m4f) +include(stm32-stdperiph) include(stm32f3-usb) set(STM32F3_STDPERIPH_DIR "${INAV_LIB_DIR}/main/STM32F3/Drivers/STM32F30x_StdPeriph_Driver") @@ -61,7 +62,7 @@ set(STM32F303_DEFINITIONS function(target_stm32f3xx name startup ldscript) # F3 targets don't support MSC target_stm32(${name} ${startup} ${ldscript} DISABLE_MSC ${ARGN}) - target_sources(${name} PRIVATE ${STM32F3_STDPERIPH_SRC} ${STM32F3_SRC}) + target_sources(${name} PRIVATE ${STM32_STDPERIPH_SRC} ${STM32F3_STDPERIPH_SRC} ${STM32F3_SRC}) target_compile_options(${name} PRIVATE ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_COMPILE_OPTIONS}) target_include_directories(${name} PRIVATE ${STM32F3_INCLUDE_DIRS}) target_compile_definitions(${name} PRIVATE ${STM32F3_DEFINITIONS}) diff --git a/cmake/stm32f4.cmake b/cmake/stm32f4.cmake index b5c780e964a..405828d905d 100644 --- a/cmake/stm32f4.cmake +++ b/cmake/stm32f4.cmake @@ -1,4 +1,5 @@ include(cortex-m4f) +include(stm32-stdperiph) include(stm32f4-usb) set(STM32F4_STDPERIPH_DIR "${INAV_LIB_DIR}/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver") @@ -36,7 +37,6 @@ set(STM32F4_SRC drivers/adc_stm32f4xx.c drivers/adc_stm32f4xx.c drivers/bus_i2c_stm32f40x.c - drivers/serial_softserial.c drivers/serial_uart_stm32f4xx.c drivers/system_stm32f4xx.c drivers/timer.c @@ -79,7 +79,7 @@ set(STM32F4_DEFINITIONS function(target_stm32f4xx name startup ldscript) target_stm32(${name} ${startup} ${ldscript} ${ARGN}) - target_sources(${name} PRIVATE ${STM32F4_SRC}) + target_sources(${name} PRIVATE ${STM32_STDPERIPH_SRC} ${STM32F4_SRC}) target_compile_options(${name} PRIVATE ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_COMPILE_OPTIONS}) target_include_directories(${name} PRIVATE ${STM32F4_INCLUDE_DIRS}) target_compile_definitions(${name} PRIVATE ${STM32F4_DEFINITIONS}) diff --git a/cmake/stm32f7-usb.cmake b/cmake/stm32f7-usb.cmake new file mode 100644 index 00000000000..851bb98e2f9 --- /dev/null +++ b/cmake/stm32f7-usb.cmake @@ -0,0 +1,48 @@ +set(STM32F7_USBCORE_DIR "${INAV_LIB_DIR}/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Core") +set(STM32F7_USBCORE_SRC + usbd_core.c + usbd_ctlreq.c + usbd_ioreq.c +) +list(TRANSFORM STM32F7_USBCORE_SRC PREPEND "${STM32F7_USBCORE_DIR}/Src/") + +set(STM32F7_USBCDC_DIR "${INAV_LIB_DIR}/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC") +set(STM32F7_USBCDC_SRC + usbd_cdc.c +) +list(TRANSFORM STM32F7_USBCDC_SRC PREPEND "${STM32F7_USBCDC_DIR}/Src/") + +set(STM32F7_USBHID_DIR "${INAV_LIB_DIR}/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/HID") +set(STM32F7_USBHID_SRC + usbd_hid.c +) +list(TRANSFORM STM32F7_USBHID_SRC PREPEND "${STM32F7_USBHID_DIR}/Src/") + +set(STM32F7_USBCDCHID_DIR "${INAV_LIB_DIR}/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_HID") +set(STM32F7_USBCDCHID_SRC + usbd_cdc_hid.c +) +list(TRANSFORM STM32F7_USBCDCHID_SRC PREPEND "${STM32F7_USBCDCHID_DIR}/Src/") + +set(STM32F7_USBMSC_DIR "${INAV_LIB_DIR}/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC") +set(STM32F7_USBMSC_SRC + usbd_msc.c + usbd_msc_bot.c + usbd_msc_data.c + usbd_msc_scsi.c +) +list(TRANSFORM STM32F7_USBMSC_SRC PREPEND "${STM32F7_USBMSC_DIR}/Src/") + +set(STM32F7_USB_INCLUDE_DIRS + "${STM32F7_USBCORE_DIR}/Inc" + "${STM32F7_USBCDC_DIR}/Inc" + "${STM32F7_USBHID_DIR}/Inc" + "${STM32F7_USBCDCHID_DIR}/Inc" + "${STM32F7_USBMSC_DIR}/Inc" +) + +list(APPEND STM32F7_USB_SRC ${STM32F7_USBCORE_SRC}) +list(APPEND STM32F7_USB_SRC ${STM32F7_USBCDC_SRC}) +list(APPEND STM32F7_USB_SRC ${STM32F7_USBHID_SRC}) +list(APPEND STM32F7_USB_SRC ${STM32F7_USBCDCHID_SRC}) +list(APPEND STM32F7_USB_SRC ${STM32F7_USBMSC_SRC}) diff --git a/cmake/stm32f7.cmake b/cmake/stm32f7.cmake new file mode 100644 index 00000000000..6a3db80cdfe --- /dev/null +++ b/cmake/stm32f7.cmake @@ -0,0 +1,121 @@ +include(cortex-m7) +include(stm32f7-usb) + +set(STM32F7_HAL_DIR "${INAV_LIB_DIR}/main/STM32F7/Drivers/STM32F7xx_HAL_Driver") + +set(STM32F7_HAL_SRC + stm32f7xx_hal.c + stm32f7xx_hal_adc.c + stm32f7xx_hal_adc_ex.c + stm32f7xx_hal_cortex.c + stm32f7xx_hal_dac.c + stm32f7xx_hal_dac_ex.c + stm32f7xx_hal_dma.c + stm32f7xx_hal_dma_ex.c + stm32f7xx_hal_flash.c + stm32f7xx_hal_flash_ex.c + stm32f7xx_hal_gpio.c + stm32f7xx_hal_i2c.c + stm32f7xx_hal_i2c_ex.c + stm32f7xx_hal_pcd.c + stm32f7xx_hal_pcd_ex.c + stm32f7xx_hal_pwr.c + stm32f7xx_hal_pwr_ex.c + stm32f7xx_hal_rcc.c + stm32f7xx_hal_rcc_ex.c + stm32f7xx_hal_rtc.c + stm32f7xx_hal_rtc_ex.c + stm32f7xx_hal_spi.c + stm32f7xx_hal_tim.c + stm32f7xx_hal_tim_ex.c + stm32f7xx_hal_uart.c + stm32f7xx_hal_usart.c + stm32f7xx_ll_dma.c + stm32f7xx_ll_dma2d.c + stm32f7xx_ll_gpio.c + stm32f7xx_ll_rcc.c + stm32f7xx_ll_spi.c + stm32f7xx_ll_tim.c + stm32f7xx_ll_usb.c + stm32f7xx_ll_utils.c +) +list(TRANSFORM STM32F7_HAL_SRC PREPEND "${STM32F7_HAL_DIR}/src/") + +set(STM32F7_CMSIS_DEVICE_DIR "${INAV_LIB_DIR}/main/STM32F7/Drivers/CMSIS/Device/ST/STM32F7xx") + +set(STM32F7_VCP_DIR "${INAV_MAIN_SRC_DIR}/vcp_hal") + +set(STM32F7_VCP_SRC + usbd_desc.c + usbd_conf.c + usbd_cdc_interface.c +) +list(TRANSFORM STM32F7_VCP_SRC PREPEND "${STM32F7_VCP_DIR}/") + +set(STM32F7_INCLUDE_DIRS + ${STM32F7_HAL_DIR}/inc + ${STM32F7_CMSIS_DEVICE_DIR}/Include +) + +set(STM32F7_SRC + target/system_stm32f7xx.c + drivers/adc_stm32f7xx.c + drivers/bus_i2c_hal.c + drivers/dma_stm32f7xx.c + drivers/bus_spi_hal.c + drivers/timer.c + drivers/timer_impl_hal.c + drivers/timer_stm32f7xx.c + drivers/system_stm32f7xx.c + drivers/serial_uart_stm32f7xx.c + drivers/serial_uart_hal.c + drivers/sdcard/sdmmc_sdio_f7xx.c +) +main_sources(STM32F7_SRC) + +set(STM32F7_MSC_SRC + drivers/usb_msc_f7xx.c +) +main_sources(STM32F7_MSC_SRC) + +set(STM32F7_DEFINITIONS + ${CORTEX_M7_DEFINITIONS} + USE_HAL_DRIVER + USE_FULL_LL_DRIVER +) + +function(target_stm32f7xx name startup ldscript) + target_stm32(${name} ${startup} ${ldscript} ${ARGN}) + target_sources(${name} PRIVATE ${STM32F7_HAL_SRC} ${STM32F7_SRC}) + target_compile_options(${name} PRIVATE ${CORTEX_M7_COMMON_OPTIONS} ${CORTEX_M7_COMPILE_OPTIONS}) + target_include_directories(${name} PRIVATE ${STM32F7_INCLUDE_DIRS}) + target_compile_definitions(${name} PRIVATE ${STM32F7_DEFINITIONS}) + target_link_options(${name} PRIVATE ${CORTEX_M7_COMMON_OPTIONS} ${CORTEX_M7_LINK_OPTIONS}) + + get_property(features TARGET ${name} PROPERTY FEATURES) + if(VCP IN_LIST features) + target_include_directories(${name} PRIVATE ${STM32F7_USB_INCLUDE_DIRS} ${STM32F7_VCP_DIR}) + target_sources(${name} PRIVATE ${STM32F7_USB_SRC} ${STM32F7_VCP_SRC}) + endif() + if(MSC IN_LIST features) + target_sources(${name} PRIVATE ${STM32F7_USBMSC_SRC} ${STM32F7_MSC_SRC}) + endif() +endfunction() + +macro(define_target_stm32f7 suffix flash_size) + function(target_stm32f7${suffix} name) + target_stm32f7xx(${name} startup_stm32f7${suffix}xx.s stm32_flash_f7${suffix}.ld ${ARGN}) + set(definitions + STM32F7 + STM32F7${suffix}xx + FLASH_SIZE=${flash_size} + ) + target_compile_definitions(${name} PRIVATE ${definitions}) + setup_firmware_target(${name}) + endfunction() +endmacro() + +define_target_stm32f7("22" 512) +define_target_stm32f7("45" 2048) +define_target_stm32f7("46" 2048) +define_target_stm32f7("65" 2048) \ No newline at end of file diff --git a/docs/USB_Mass_Storage_(MSC)_mode.md b/docs/USB_Mass_Storage_(MSC)_mode.md index 730230db12a..1812c4fbc09 100644 --- a/docs/USB_Mass_Storage_(MSC)_mode.md +++ b/docs/USB_Mass_Storage_(MSC)_mode.md @@ -83,11 +83,5 @@ Data rate 496Hz 35806 bytes/s 358100 baud ``` ## Developer Notes -Providing MSC for a target requires that the `.mk` file includes in `FEATURES` the key `MSC` and at least one of `ONBOARDFLASH` and /or `SDCARD`. - -For F4 and F7 targets, `USE_USB_MSC` is set unconditionally in `common.h`; if your target does not support blackbox logging to either SD card or internal flash, you should over-ride this in `target.h` -``` -#ifdef USE_USB_MSC -# undef USE_USB_MSC -#endif -``` \ No newline at end of file +Providing MSC is automatically enabled for all F4 and up a targets that support +`ONBOARDFLASH` and /or `SDCARD`. \ No newline at end of file diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 0095b7eddf9..cc1ddafed81 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -95,7 +95,6 @@ set(COMMON_SRC drivers/bus_busdev_i2c.c drivers/bus_busdev_spi.c drivers/bus_i2c_soft.c - drivers/bus_spi.c drivers/compass/compass.h drivers/compass/compass_ak8963.c @@ -133,6 +132,7 @@ set(COMMON_SRC drivers/light_ws2811strip.c drivers/lights_io.c drivers/max7456.c + drivers/serial_softserial.c drivers/opflow/opflow_fake.c drivers/opflow/opflow_virtual.c @@ -160,7 +160,6 @@ set(COMMON_SRC drivers/rx_spi.c drivers/rx_xn297.c drivers/serial.c - drivers/serial_uart.c drivers/sound_beeper.c drivers/stack_check.c drivers/system.c diff --git a/src/main/target/AIRBOTF7/CMakeLists.txt b/src/main/target/AIRBOTF7/CMakeLists.txt new file mode 100644 index 00000000000..17d2773f098 --- /dev/null +++ b/src/main/target/AIRBOTF7/CMakeLists.txt @@ -0,0 +1,2 @@ +target_stm32f722(AIRBOTF7) +target_stm32f722(OMNIBUSF7NANOV7) \ No newline at end of file diff --git a/src/main/target/ALIENFLIGHTNGF7/CMakeLists.txt b/src/main/target/ALIENFLIGHTNGF7/CMakeLists.txt new file mode 100644 index 00000000000..8ad2eb2cca0 --- /dev/null +++ b/src/main/target/ALIENFLIGHTNGF7/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722(ALIENFLIGHTNGF7) \ No newline at end of file diff --git a/src/main/target/ANYFCF7/CMakeLists.txt b/src/main/target/ANYFCF7/CMakeLists.txt new file mode 100644 index 00000000000..28cd0006c85 --- /dev/null +++ b/src/main/target/ANYFCF7/CMakeLists.txt @@ -0,0 +1,2 @@ +target_stm32f745(ANYFCF7) +target_stm32f745(ANYFCF7_EXTERNAL_BARO) \ No newline at end of file diff --git a/src/main/target/ASGARD32F7/CMakeLists.txt b/src/main/target/ASGARD32F7/CMakeLists.txt new file mode 100644 index 00000000000..1a219728094 --- /dev/null +++ b/src/main/target/ASGARD32F7/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722(ASGARD32F7) \ No newline at end of file diff --git a/src/main/target/DALRCF722DUAL/CMakeLists.txt b/src/main/target/DALRCF722DUAL/CMakeLists.txt new file mode 100644 index 00000000000..ea04ea8ea6f --- /dev/null +++ b/src/main/target/DALRCF722DUAL/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722(DALRCF722DUAL) \ No newline at end of file diff --git a/src/main/target/FOXEERF722DUAL/CMakeLists.txt b/src/main/target/FOXEERF722DUAL/CMakeLists.txt new file mode 100644 index 00000000000..bc00522e869 --- /dev/null +++ b/src/main/target/FOXEERF722DUAL/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722(FOXEERF722DUAL) \ No newline at end of file diff --git a/src/main/target/IFLIGHTF7_TWING/CMakeLists.txt b/src/main/target/IFLIGHTF7_TWING/CMakeLists.txt new file mode 100644 index 00000000000..8ce43face71 --- /dev/null +++ b/src/main/target/IFLIGHTF7_TWING/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722(IFLIGHTF7_TWING) \ No newline at end of file diff --git a/src/main/target/KAKUTEF7/CMakeLists.txt b/src/main/target/KAKUTEF7/CMakeLists.txt new file mode 100644 index 00000000000..78856cbd159 --- /dev/null +++ b/src/main/target/KAKUTEF7/CMakeLists.txt @@ -0,0 +1,3 @@ +target_stm32f745(KAKUTEF7) +target_stm32f745(KAKUTEF7HDV) +target_stm32f745(KAKUTEF7MINI) \ No newline at end of file diff --git a/src/main/target/MAMBAF722/CMakeLists.txt b/src/main/target/MAMBAF722/CMakeLists.txt new file mode 100644 index 00000000000..5494780c064 --- /dev/null +++ b/src/main/target/MAMBAF722/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722(MAMBAF722) \ No newline at end of file diff --git a/src/main/target/MATEKF722/CMakeLists.txt b/src/main/target/MATEKF722/CMakeLists.txt new file mode 100644 index 00000000000..cbafe79506b --- /dev/null +++ b/src/main/target/MATEKF722/CMakeLists.txt @@ -0,0 +1,2 @@ +target_stm32f722(MATEKF722) +target_stm32f722(MATEKF722_HEXSERVO) \ No newline at end of file diff --git a/src/main/target/MATEKF722PX/CMakeLists.txt b/src/main/target/MATEKF722PX/CMakeLists.txt new file mode 100644 index 00000000000..9e53706f3f9 --- /dev/null +++ b/src/main/target/MATEKF722PX/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722(MATEKF722PX) \ No newline at end of file diff --git a/src/main/target/MATEKF722SE/CMakeLists.txt b/src/main/target/MATEKF722SE/CMakeLists.txt new file mode 100644 index 00000000000..66c55b0fbfb --- /dev/null +++ b/src/main/target/MATEKF722SE/CMakeLists.txt @@ -0,0 +1,2 @@ +target_stm32f722(MATEKF722SE) +target_stm32f722(MATEKF722MINI) \ No newline at end of file diff --git a/src/main/target/MATEKF765/CMakeLists.txt b/src/main/target/MATEKF765/CMakeLists.txt new file mode 100644 index 00000000000..ab9f4e7e77e --- /dev/null +++ b/src/main/target/MATEKF765/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f765(MATEKF765) \ No newline at end of file diff --git a/src/main/target/OMNIBUSF7/CMakeLists.txt b/src/main/target/OMNIBUSF7/CMakeLists.txt new file mode 100644 index 00000000000..5f2f42d4c69 --- /dev/null +++ b/src/main/target/OMNIBUSF7/CMakeLists.txt @@ -0,0 +1,2 @@ +target_stm32f745(OMNIBUSF7) +target_stm32f745(OMNIBUSF7V2) \ No newline at end of file diff --git a/src/main/target/OMNIBUSF7NXT/CMakeLists.txt b/src/main/target/OMNIBUSF7NXT/CMakeLists.txt new file mode 100644 index 00000000000..d75488409b4 --- /dev/null +++ b/src/main/target/OMNIBUSF7NXT/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722(OMNIBUSF7NXT) \ No newline at end of file diff --git a/src/main/target/SPRACINGF7DUAL/CMakeLists.txt b/src/main/target/SPRACINGF7DUAL/CMakeLists.txt new file mode 100644 index 00000000000..9f470b18e70 --- /dev/null +++ b/src/main/target/SPRACINGF7DUAL/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722(SPRACINGF7DUAL) \ No newline at end of file diff --git a/src/main/target/YUPIF7/CMakeLists.txt b/src/main/target/YUPIF7/CMakeLists.txt new file mode 100644 index 00000000000..e1073f8d00c --- /dev/null +++ b/src/main/target/YUPIF7/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722(YUPIF7) \ No newline at end of file diff --git a/src/main/target/ZEEZF7/CMakeLists.txt b/src/main/target/ZEEZF7/CMakeLists.txt new file mode 100644 index 00000000000..8c1536bee4f --- /dev/null +++ b/src/main/target/ZEEZF7/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722(ZEEZF7) \ No newline at end of file From 518e8243cb63a9eb2e234aca770f9cdbd4c60254 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Fri, 10 Jul 2020 12:37:30 +0100 Subject: [PATCH 146/248] [BUILD] Refactor cmake macros and variable names Make them a bit more generic --- CMakeLists.txt | 10 +++++----- cmake/{inav.cmake => main.cmake} | 23 ++++++++++++----------- cmake/settings.cmake | 6 +++--- cmake/stm32-stdperiph.cmake | 5 ++--- cmake/stm32.cmake | 31 ++++++++++++------------------- cmake/stm32f3-usb.cmake | 2 +- cmake/stm32f3.cmake | 11 +++++------ cmake/stm32f4-usb.cmake | 12 ++++++------ cmake/stm32f4.cmake | 14 ++++++-------- cmake/stm32f7-usb.cmake | 10 +++++----- cmake/stm32f7.cmake | 12 +++++------- src/main/CMakeLists.txt | 4 +--- 12 files changed, 63 insertions(+), 77 deletions(-) rename cmake/{inav.cmake => main.cmake} (78%) diff --git a/CMakeLists.txt b/CMakeLists.txt index a9c54dc8031..aa37d9e5071 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -33,17 +33,17 @@ if (NO_GIT_HASH) message(FATAL_ERROR "Could not find git revision. Is git installed?") endif() -set(INAV_DIR "${CMAKE_CURRENT_SOURCE_DIR}") -set(INAV_LIB_DIR "${CMAKE_CURRENT_SOURCE_DIR}/lib") -set(INAV_UTILS_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src/utils") -set(INAV_MAIN_SRC_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src/main") +set(MAIN_DIR "${CMAKE_CURRENT_SOURCE_DIR}") +set(MAIN_LIB_DIR "${CMAKE_CURRENT_SOURCE_DIR}/lib") +set(MAIN_UTILS_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src/utils") +set(MAIN_SRC_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src/main") list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake") set(FIRMWARE_VERSION ${PROJECT_VERSION}) include(settings) -include(inav) +include(main) include(stm32) add_subdirectory(src) diff --git a/cmake/inav.cmake b/cmake/main.cmake similarity index 78% rename from cmake/inav.cmake rename to cmake/main.cmake index 285ee1afeb0..977c97f1093 100644 --- a/cmake/inav.cmake +++ b/cmake/main.cmake @@ -1,15 +1,15 @@ -set(INAV_INCLUDE_DIRS - "${INAV_LIB_DIR}" - "${INAV_MAIN_SRC_DIR}" - "${INAV_LIB_DIR}/main/MAVLink" +set(MAIN_INCLUDE_DIRS + "${MAIN_LIB_DIR}" + "${MAIN_SRC_DIR}" + "${MAIN_LIB_DIR}/main/MAVLink" ) -set(INAV_DEFINITIONS +set(MAIN_DEFINITIONS __FORKNAME__=inav __REVISION__="${GIT_SHORT_HASH}" ) -set(INAV_COMPILE_OPTIONS +set(MAIN_COMPILE_OPTIONS -Wall -Wextra -Wunsafe-loop-optimizations @@ -18,8 +18,9 @@ set(INAV_COMPILE_OPTIONS -Werror=switch ) -macro(main_sources) # list-var - list(TRANSFORM ${ARGV0} PREPEND "${INAV_MAIN_SRC_DIR}/") +macro(main_sources var) # list-var src-1...src-n + set(${var} ${ARGN}) + list(TRANSFORM ${var} PREPEND "${MAIN_SRC_DIR}/") endmacro() macro(exclude_basenames) # list-var excludes-var @@ -39,9 +40,9 @@ macro(glob_except) # var-name pattern excludes-var endmacro() function(setup_firmware_target name) - target_compile_options(${name} PRIVATE ${INAV_COMPILE_OPTIONS}) - target_include_directories(${name} PRIVATE ${INAV_INCLUDE_DIRS}) - target_compile_definitions(${name} PRIVATE ${INAV_DEFINITIONS} __TARGET__="${name}" ${name}) + target_compile_options(${name} PRIVATE ${MAIN_COMPILE_OPTIONS}) + target_include_directories(${name} PRIVATE ${MAIN_INCLUDE_DIRS}) + target_compile_definitions(${name} PRIVATE ${MAIN_DEFINITIONS} __TARGET__="${name}" ${name}) enable_settings(${name}) # XXX: Don't make SETTINGS_GENERATED_C part of the build, # since it's compiled via #include in settings.c. This will diff --git a/cmake/settings.cmake b/cmake/settings.cmake index f74f6589d99..1521fbc8b9a 100644 --- a/cmake/settings.cmake +++ b/cmake/settings.cmake @@ -1,8 +1,8 @@ set(SETTINGS_GENERATED "settings_generated") set(SETTINGS_GENERATED_C "${SETTINGS_GENERATED}.c") set(SETTINGS_GENERATED_H "${SETTINGS_GENERATED}.h") -set(SETTINGS_FILE "${INAV_MAIN_SRC_DIR}/fc/settings.yaml") -set(SETTINGS_GENERATOR "${INAV_UTILS_DIR}/settings.rb") +set(SETTINGS_FILE "${MAIN_SRC_DIR}/fc/settings.yaml") +set(SETTINGS_GENERATOR "${MAIN_UTILS_DIR}/settings.rb") function(enable_settings target) set(dir "${CMAKE_CURRENT_BINARY_DIR}/${target}") @@ -19,7 +19,7 @@ function(enable_settings target) OUTPUT ${dir}/${SETTINGS_GENERATED_H} ${dir}/${SETTINGS_GENERATED_C} COMMAND ${CMAKE_COMMAND} -E env CFLAGS="${cflags}" TARGET=${target} - ${RUBY_EXECUTABLE} ${SETTINGS_GENERATOR} ${INAV_DIR} ${SETTINGS_FILE} -o "${dir}" + ${RUBY_EXECUTABLE} ${SETTINGS_GENERATOR} ${MAIN_DIR} ${SETTINGS_FILE} -o "${dir}" DEPENDS ${SETTINGS_GENERATOR} ${SETTINGS_FILE} ) endfunction() diff --git a/cmake/stm32-stdperiph.cmake b/cmake/stm32-stdperiph.cmake index 8b4e9c2f5b6..d085dc67144 100644 --- a/cmake/stm32-stdperiph.cmake +++ b/cmake/stm32-stdperiph.cmake @@ -1,5 +1,4 @@ -set(STM32_STDPERIPH_SRC +main_sources(STM32_STDPERIPH_SRC drivers/bus_spi.c drivers/serial_uart.c -) -main_sources(STM32_STDPERIPH_SRC) \ No newline at end of file +) \ No newline at end of file diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake index 61f3fc58002..bed6af3e019 100644 --- a/cmake/stm32.cmake +++ b/cmake/stm32.cmake @@ -5,9 +5,9 @@ include(stm32f7) include(CMakeParseArguments) -set(CMSIS_DIR "${INAV_LIB_DIR}/main/CMSIS") +set(CMSIS_DIR "${MAIN_LIB_DIR}/main/CMSIS") set(CMSIS_INCLUDE_DIR "${CMSIS_DIR}/Core/Include") -set(CMSIS_DSP_DIR "${INAV_LIB_DIR}/main/CMSIS/DSP") +set(CMSIS_DSP_DIR "${MAIN_LIB_DIR}/main/CMSIS/DSP") set(CMSIS_DSP_INCLUDE_DIR "${CMSIS_DSP_DIR}/Include") set(CMSIS_DSP_SRC @@ -23,56 +23,49 @@ set(CMSIS_DSP_SRC ) list(TRANSFORM CMSIS_DSP_SRC PREPEND "${CMSIS_DSP_DIR}/Source/") -set(STM32_STARTUP_DIR "${INAV_MAIN_SRC_DIR}/startup") +set(STM32_STARTUP_DIR "${MAIN_SRC_DIR}/startup") -set(STM32_VCP_SRC +main_sources(STM32_VCP_SRC drivers/serial_usb_vcp.c drivers/usb_io.c ) -main_sources(STM32_VCP_SRC) -set(STM32_SDCARD_SRC +main_sources(STM32_SDCARD_SRC drivers/sdcard/sdcard.c drivers/sdcard/sdcard_spi.c drivers/sdcard/sdcard_sdio.c drivers/sdcard/sdcard_standard.c ) -main_sources(STM32_SDCARD_SRC) # XXX: This code is not STM32 specific -set(STM32_ASYNCFATFS_SRC +main_sources(STM32_ASYNCFATFS_SRC io/asyncfatfs/asyncfatfs.c io/asyncfatfs/fat_standard.c ) -main_sources(STM32_ASYNCFATFS_SRC) -set(STM32_MSC_SRC +main_sources(STM32_MSC_SRC msc/usbd_msc_desc.c msc/usbd_storage.c ) -main_sources(STM32_MSC_SRC) -set(STM32_MSC_FLASH_SRC +main_sources(STM32_MSC_FLASH_SRC msc/usbd_storage_emfat.c msc/emfat.c msc/emfat_file.c ) -main_sources(STM32_MSC_FLASH_SRC) -set(STM32_MSC_SDCARD_SPI_SRC +main_sources(STM32_MSC_SDCARD_SPI_SRC msc/usbd_storage_sd_spi.c ) -main_sources(STM32_MSC_SDCARD_SPI_SRC) -set(STM32_MSC_SDCARD_SDIO_SRC +main_sources(STM32_MSC_SDCARD_SDIO_SRC msc/usbd_storage_sdio.c ) -main_sources(STM32_MSC_SDCARD_SDIO_SRC) set(STM32_INCLUDE_DIRS "${CMSIS_INCLUDE_DIR}" "${CMSIS_DSP_INCLUDE_DIR}" - "${INAV_MAIN_SRC_DIR}/target" + "${MAIN_SRC_DIR}/target" ) set(STM32_DEFINITIONS @@ -80,7 +73,7 @@ set(STM32_DEFINITIONS set(STM32_DEFAULT_HSE_MHZ 8) -set(STM32_LINKER_DIR "${INAV_MAIN_SRC_DIR}/target/link") +set(STM32_LINKER_DIR "${MAIN_SRC_DIR}/target/link") set(STM32_LIBS lnosys) #if(SEMIHOSTING) diff --git a/cmake/stm32f3-usb.cmake b/cmake/stm32f3-usb.cmake index 231608757a1..c14443458f4 100644 --- a/cmake/stm32f3-usb.cmake +++ b/cmake/stm32f3-usb.cmake @@ -1,4 +1,4 @@ -set(STM32_USBFS_DIR "${INAV_LIB_DIR}/main/STM32_USB-FS-Device_Driver") +set(STM32_USBFS_DIR "${MAIN_LIB_DIR}/main/STM32_USB-FS-Device_Driver") set(STM32_USBFS_SRC usb_core.c diff --git a/cmake/stm32f3.cmake b/cmake/stm32f3.cmake index 81ff2abc6d3..bc1e34c7654 100644 --- a/cmake/stm32f3.cmake +++ b/cmake/stm32f3.cmake @@ -2,10 +2,10 @@ include(cortex-m4f) include(stm32-stdperiph) include(stm32f3-usb) -set(STM32F3_STDPERIPH_DIR "${INAV_LIB_DIR}/main/STM32F3/Drivers/STM32F30x_StdPeriph_Driver") -set(STM32F3_CMSIS_DEVICE_DIR "${INAV_LIB_DIR}/main/STM32F3/Drivers/CMSIS/Device/ST/STM32F30x") -set(STM32F3_CMSIS_DRIVERS_DIR "${INAV_LIB_DIR}/main/STM32F3/Drivers/CMSIS") -set(STM32F3_VCP_DIR "${INAV_MAIN_SRC_DIR}/vcp") +set(STM32F3_STDPERIPH_DIR "${MAIN_LIB_DIR}/main/STM32F3/Drivers/STM32F30x_StdPeriph_Driver") +set(STM32F3_CMSIS_DEVICE_DIR "${MAIN_LIB_DIR}/main/STM32F3/Drivers/CMSIS/Device/ST/STM32F30x") +set(STM32F3_CMSIS_DRIVERS_DIR "${MAIN_LIB_DIR}/main/STM32F3/Drivers/CMSIS") +set(STM32F3_VCP_DIR "${MAIN_SRC_DIR}/vcp") set(STM32F3_STDPERIPH_SRC_EXCLUDES stm32f30x_crc.c @@ -15,7 +15,7 @@ set(STM32F3_STDPERIPH_SRC_DIR "${STM32F3_STDPERIPH_DIR}/Src") glob_except(STM32F3_STDPERIPH_SRC "${STM32F3_STDPERIPH_SRC_DIR}/*.c" STM32F3_STDPERIPH_SRC_EXCLUDES) -set(STM32F3_SRC +main_sources(STM32F3_SRC target/system_stm32f30x.c drivers/adc_stm32f30x.c drivers/bus_i2c_stm32f30x.c @@ -25,7 +25,6 @@ set(STM32F3_SRC drivers/timer_impl_stdperiph.c drivers/timer_stm32f30x.c ) -main_sources(STM32F3_SRC) set(STM32F3_VCP_SRC hw_config.c diff --git a/cmake/stm32f4-usb.cmake b/cmake/stm32f4-usb.cmake index 3fbaec4d8dd..177d5322df7 100644 --- a/cmake/stm32f4-usb.cmake +++ b/cmake/stm32f4-usb.cmake @@ -1,9 +1,9 @@ -set(STM32_USBOTG_DIR "${INAV_LIB_DIR}/main/STM32_USB_OTG_Driver") -set(STM32_USBCORE_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Core") -set(STM32_USBCDC_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/cdc") -set(STM32_USBHID_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/hid") -set(STM32_USBWRAPPER_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/hid_cdc_wrapper") -set(STM32_USBMSC_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/msc") +set(STM32_USBOTG_DIR "${MAIN_LIB_DIR}/main/STM32_USB_OTG_Driver") +set(STM32_USBCORE_DIR "${MAIN_LIB_DIR}/main/STM32_USB_Device_Library/Core") +set(STM32_USBCDC_DIR "${MAIN_LIB_DIR}/main/STM32_USB_Device_Library/Class/cdc") +set(STM32_USBHID_DIR "${MAIN_LIB_DIR}/main/STM32_USB_Device_Library/Class/hid") +set(STM32_USBWRAPPER_DIR "${MAIN_LIB_DIR}/main/STM32_USB_Device_Library/Class/hid_cdc_wrapper") +set(STM32_USBMSC_DIR "${MAIN_LIB_DIR}/main/STM32_USB_Device_Library/Class/msc") set(STM32F4_USB_INCLUDE_DIRS "${STM32_USBOTG_DIR}/inc" diff --git a/cmake/stm32f4.cmake b/cmake/stm32f4.cmake index 405828d905d..3e76e7801fd 100644 --- a/cmake/stm32f4.cmake +++ b/cmake/stm32f4.cmake @@ -2,10 +2,10 @@ include(cortex-m4f) include(stm32-stdperiph) include(stm32f4-usb) -set(STM32F4_STDPERIPH_DIR "${INAV_LIB_DIR}/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver") -set(STM32F4_CMSIS_DEVICE_DIR "${INAV_LIB_DIR}/main/STM32F4/Drivers/CMSIS/Device/ST/STM32F4xx") -set(STM32F4_CMSIS_DRIVERS_DIR "${INAV_LIB_DIR}/main/STM32F4/Drivers/CMSIS") -set(STM32F4_VCP_DIR "${INAV_MAIN_SRC_DIR}/vcpf4") +set(STM32F4_STDPERIPH_DIR "${MAIN_LIB_DIR}/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver") +set(STM32F4_CMSIS_DEVICE_DIR "${MAIN_LIB_DIR}/main/STM32F4/Drivers/CMSIS/Device/ST/STM32F4xx") +set(STM32F4_CMSIS_DRIVERS_DIR "${MAIN_LIB_DIR}/main/STM32F4/Drivers/CMSIS") +set(STM32F4_VCP_DIR "${MAIN_SRC_DIR}/vcpf4") set(STM32F4_STDPERIPH_SRC_EXCLUDES stm32f4xx_can.c @@ -32,7 +32,7 @@ set(STM32F4_STDPERIPH_SRC_EXCLUDES set(STM32F4_STDPERIPH_SRC_DIR "${STM32F4_STDPERIPH_DIR}/Src") glob_except(STM32F4_STDPERIPH_SRC "${STM32F4_STDPERIPH_SRC_DIR}/*.c" STM32F4_STDPERIPH_SRC_EXCLUDES) -set(STM32F4_SRC +main_sources(STM32F4_SRC target/system_stm32f4xx.c drivers/adc_stm32f4xx.c drivers/adc_stm32f4xx.c @@ -46,7 +46,6 @@ set(STM32F4_SRC drivers/dma_stm32f4xx.c drivers/sdcard/sdmmc_sdio_f4xx.c ) -main_sources(STM32F4_SRC) set(STM32F4_VCP_SRC stm32f4xx_it.c @@ -57,10 +56,9 @@ set(STM32F4_VCP_SRC ) list(TRANSFORM STM32F4_VCP_SRC PREPEND "${STM32F4_VCP_DIR}/") -set(STM32F4_MSC_SRC +main_sources(STM32F4_MSC_SRC drivers/usb_msc_f4xx.c ) -main_sources(STM32F4_MSC_SRC) set(STM32F4_INCLUDE_DIRS "${CMSIS_INCLUDE_DIR}" diff --git a/cmake/stm32f7-usb.cmake b/cmake/stm32f7-usb.cmake index 851bb98e2f9..b57f49e13ac 100644 --- a/cmake/stm32f7-usb.cmake +++ b/cmake/stm32f7-usb.cmake @@ -1,4 +1,4 @@ -set(STM32F7_USBCORE_DIR "${INAV_LIB_DIR}/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Core") +set(STM32F7_USBCORE_DIR "${MAIN_LIB_DIR}/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Core") set(STM32F7_USBCORE_SRC usbd_core.c usbd_ctlreq.c @@ -6,25 +6,25 @@ set(STM32F7_USBCORE_SRC ) list(TRANSFORM STM32F7_USBCORE_SRC PREPEND "${STM32F7_USBCORE_DIR}/Src/") -set(STM32F7_USBCDC_DIR "${INAV_LIB_DIR}/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC") +set(STM32F7_USBCDC_DIR "${MAIN_LIB_DIR}/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC") set(STM32F7_USBCDC_SRC usbd_cdc.c ) list(TRANSFORM STM32F7_USBCDC_SRC PREPEND "${STM32F7_USBCDC_DIR}/Src/") -set(STM32F7_USBHID_DIR "${INAV_LIB_DIR}/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/HID") +set(STM32F7_USBHID_DIR "${MAIN_LIB_DIR}/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/HID") set(STM32F7_USBHID_SRC usbd_hid.c ) list(TRANSFORM STM32F7_USBHID_SRC PREPEND "${STM32F7_USBHID_DIR}/Src/") -set(STM32F7_USBCDCHID_DIR "${INAV_LIB_DIR}/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_HID") +set(STM32F7_USBCDCHID_DIR "${MAIN_LIB_DIR}/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_HID") set(STM32F7_USBCDCHID_SRC usbd_cdc_hid.c ) list(TRANSFORM STM32F7_USBCDCHID_SRC PREPEND "${STM32F7_USBCDCHID_DIR}/Src/") -set(STM32F7_USBMSC_DIR "${INAV_LIB_DIR}/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC") +set(STM32F7_USBMSC_DIR "${MAIN_LIB_DIR}/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC") set(STM32F7_USBMSC_SRC usbd_msc.c usbd_msc_bot.c diff --git a/cmake/stm32f7.cmake b/cmake/stm32f7.cmake index 6a3db80cdfe..7627fd4334e 100644 --- a/cmake/stm32f7.cmake +++ b/cmake/stm32f7.cmake @@ -1,7 +1,7 @@ include(cortex-m7) include(stm32f7-usb) -set(STM32F7_HAL_DIR "${INAV_LIB_DIR}/main/STM32F7/Drivers/STM32F7xx_HAL_Driver") +set(STM32F7_HAL_DIR "${MAIN_LIB_DIR}/main/STM32F7/Drivers/STM32F7xx_HAL_Driver") set(STM32F7_HAL_SRC stm32f7xx_hal.c @@ -41,9 +41,9 @@ set(STM32F7_HAL_SRC ) list(TRANSFORM STM32F7_HAL_SRC PREPEND "${STM32F7_HAL_DIR}/src/") -set(STM32F7_CMSIS_DEVICE_DIR "${INAV_LIB_DIR}/main/STM32F7/Drivers/CMSIS/Device/ST/STM32F7xx") +set(STM32F7_CMSIS_DEVICE_DIR "${MAIN_LIB_DIR}/main/STM32F7/Drivers/CMSIS/Device/ST/STM32F7xx") -set(STM32F7_VCP_DIR "${INAV_MAIN_SRC_DIR}/vcp_hal") +set(STM32F7_VCP_DIR "${MAIN_SRC_DIR}/vcp_hal") set(STM32F7_VCP_SRC usbd_desc.c @@ -57,7 +57,7 @@ set(STM32F7_INCLUDE_DIRS ${STM32F7_CMSIS_DEVICE_DIR}/Include ) -set(STM32F7_SRC +main_sources(STM32F7_SRC target/system_stm32f7xx.c drivers/adc_stm32f7xx.c drivers/bus_i2c_hal.c @@ -71,12 +71,10 @@ set(STM32F7_SRC drivers/serial_uart_hal.c drivers/sdcard/sdmmc_sdio_f7xx.c ) -main_sources(STM32F7_SRC) -set(STM32F7_MSC_SRC +main_sources(STM32F7_MSC_SRC drivers/usb_msc_f7xx.c ) -main_sources(STM32F7_MSC_SRC) set(STM32F7_DEFINITIONS ${CORTEX_M7_DEFINITIONS} diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index cc1ddafed81..71eed6f906d 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -1,4 +1,4 @@ -set(COMMON_SRC +main_sources(COMMON_SRC main.c target/common_hardware.c @@ -336,6 +336,4 @@ set(COMMON_SRC io/vtx_control.c ) -main_sources(COMMON_SRC) - add_subdirectory(target) From fb9f61a583c8c39145af7cd7902d4587dbf9ad8a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sat, 11 Jul 2020 10:07:26 +0100 Subject: [PATCH 147/248] [BUILD] Use -Os for F3, -O2 for F4/F7 with cmake --- CMakeLists.txt | 4 ++++ cmake/arm-none-eabi.cmake | 10 +++++++--- cmake/stm32f3.cmake | 5 +++++ cmake/stm32f4.cmake | 4 ++++ cmake/stm32f7.cmake | 4 ++++ 5 files changed, 24 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index aa37d9e5071..e1619e176a8 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -9,6 +9,10 @@ endif() set(CMAKE_TOOLCHAIN_FILE "${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}.cmake") +if(CMAKE_BUILD_TYPE STREQUAL "Release" OR CMAKE_BUILD_TYPE STREQUAL "RelWithDebInfo") + set(IS_RELEASE_BUILD ON) +endif() + project(INAV VERSION 2.5.0) ENABLE_LANGUAGE(ASM) diff --git a/cmake/arm-none-eabi.cmake b/cmake/arm-none-eabi.cmake index 066bedf5642..83cbe322b07 100644 --- a/cmake/arm-none-eabi.cmake +++ b/cmake/arm-none-eabi.cmake @@ -33,7 +33,7 @@ set(CMAKE_CXX_COMPILER "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-g++${TOOL_EXECUTA set(CMAKE_OBJCOPY "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-objcopy${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "objcopy tool") set(CMAKE_OBJDUMP "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-objdump${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "objdump tool") set(CMAKE_SIZE "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-size${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "size tool") -set(CMAKE_DEBUGER "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-gdb${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "debuger") +set(CMAKE_DEBUGGER "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-gdb${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "debugger") set(CMAKE_CPPFILT "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-c++filt${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c++filt") set(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER) set(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY) @@ -43,11 +43,15 @@ set(CMAKE_EXECUTABLE_SUFFIX ".elf") if(NOT CMAKE_CONFIGURATION_TYPES) set(CMAKE_CONFIGURATION_TYPES Debug Release RelWithDebInfo) endif() -set(CMAKE_BUILD_TYPE RelWithDebInfo CACHE STRING "Build Type" FORCE) +if(CMAKE_BUILD_TYPE STREQUAL "") + set(CMAKE_BUILD_TYPE RelWithDebInfo) +endif() +set(CMAKE_BUILD_TYPE ${CMAKE_BUILD_TYPE} CACHE STRING "Build Type" FORCE) set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS ${CMAKE_CONFIGURATION_TYPES}) set(arm_none_eabi_debug "-Og -g") -set(arm_none_eabi_release "-Os -DNDEBUG -flto -fuse-linker-plugin") +# We set -Os or -O2 depending on the MCU family +set(arm_none_eabi_release "-DNDEBUG -flto -fuse-linker-plugin") set(arm_none_eabi_relwithdebinfo "-ggdb3 ${arm_none_eabi_release}") SET(CMAKE_C_FLAGS_DEBUG ${arm_none_eabi_debug} CACHE INTERNAL "c compiler flags debug") diff --git a/cmake/stm32f3.cmake b/cmake/stm32f3.cmake index bc1e34c7654..2634fcb2377 100644 --- a/cmake/stm32f3.cmake +++ b/cmake/stm32f3.cmake @@ -61,6 +61,11 @@ set(STM32F303_DEFINITIONS function(target_stm32f3xx name startup ldscript) # F3 targets don't support MSC target_stm32(${name} ${startup} ${ldscript} DISABLE_MSC ${ARGN}) + # F3 targets don't use -O2 to save size + if (IS_RELEASE_BUILD) + target_compile_options(${name} PRIVATE "-Os") + target_link_options(${name} PRIVATE "-Os") + endif() target_sources(${name} PRIVATE ${STM32_STDPERIPH_SRC} ${STM32F3_STDPERIPH_SRC} ${STM32F3_SRC}) target_compile_options(${name} PRIVATE ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_COMPILE_OPTIONS}) target_include_directories(${name} PRIVATE ${STM32F3_INCLUDE_DIRS}) diff --git a/cmake/stm32f4.cmake b/cmake/stm32f4.cmake index 3e76e7801fd..d87995522c6 100644 --- a/cmake/stm32f4.cmake +++ b/cmake/stm32f4.cmake @@ -77,6 +77,10 @@ set(STM32F4_DEFINITIONS function(target_stm32f4xx name startup ldscript) target_stm32(${name} ${startup} ${ldscript} ${ARGN}) + if (IS_RELEASE_BUILD) + target_compile_options(${name} PRIVATE "-O2") + target_link_options(${name} PRIVATE "-O2") + endif() target_sources(${name} PRIVATE ${STM32_STDPERIPH_SRC} ${STM32F4_SRC}) target_compile_options(${name} PRIVATE ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_COMPILE_OPTIONS}) target_include_directories(${name} PRIVATE ${STM32F4_INCLUDE_DIRS}) diff --git a/cmake/stm32f7.cmake b/cmake/stm32f7.cmake index 7627fd4334e..af6b8328030 100644 --- a/cmake/stm32f7.cmake +++ b/cmake/stm32f7.cmake @@ -84,6 +84,10 @@ set(STM32F7_DEFINITIONS function(target_stm32f7xx name startup ldscript) target_stm32(${name} ${startup} ${ldscript} ${ARGN}) + if (IS_RELEASE_BUILD) + target_compile_options(${name} PRIVATE "-O2") + target_link_options(${name} PRIVATE "-O2") + endif() target_sources(${name} PRIVATE ${STM32F7_HAL_SRC} ${STM32F7_SRC}) target_compile_options(${name} PRIVATE ${CORTEX_M7_COMMON_OPTIONS} ${CORTEX_M7_COMPILE_OPTIONS}) target_include_directories(${name} PRIVATE ${STM32F7_INCLUDE_DIRS}) From d6177e6933e349a1d20ea0a59c1ff65eb3729a7c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 13 Jul 2020 21:25:23 +0100 Subject: [PATCH 148/248] [BUILD] Add support for openocd helpers with cmake - Add openocd_: runs openocd for the target - Add openocd_flash_: flashes the target using openocd. It works with both an already running openocd instance as well as launching its own one. Uses a helper tool that requires python. - Add openocd_cfg_: generates openocd config for target. Used for generating an openocd config automatically when launching a debug session from an IDE. --- .gitignore | 1 + CMakeLists.txt | 1 + cmake/main.cmake | 13 ++++-- cmake/openocd.cmake | 84 +++++++++++++++++++++++++++++++++++++ cmake/openocd_cfg.cmake | 20 +++++++++ cmake/stm32.cmake | 11 +++-- cmake/stm32f3.cmake | 2 +- cmake/stm32f4.cmake | 2 +- cmake/stm32f7.cmake | 2 +- src/utils/openocd_flash.py | 86 ++++++++++++++++++++++++++++++++++++++ 10 files changed, 211 insertions(+), 11 deletions(-) create mode 100644 cmake/openocd.cmake create mode 100644 cmake/openocd_cfg.cmake create mode 100755 src/utils/openocd_flash.py diff --git a/.gitignore b/.gitignore index f4edd67c172..cc71acb9c4d 100644 --- a/.gitignore +++ b/.gitignore @@ -8,6 +8,7 @@ .project .settings .cproject +__pycache__ startup_stm32f10x_md_gcc.s .vagrant/ .vscode/ diff --git a/CMakeLists.txt b/CMakeLists.txt index e1619e176a8..bbf476e2d1a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -47,6 +47,7 @@ list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake") set(FIRMWARE_VERSION ${PROJECT_VERSION}) include(settings) +include(openocd) include(main) include(stm32) diff --git a/cmake/main.cmake b/cmake/main.cmake index 977c97f1093..2755e91c176 100644 --- a/cmake/main.cmake +++ b/cmake/main.cmake @@ -53,6 +53,14 @@ function(setup_firmware_target name) ) get_property(targets GLOBAL PROPERTY VALID_TARGETS) set_property(GLOBAL PROPERTY VALID_TARGETS "${targets} ${name}") + setup_openocd(${name}) +endfunction() + +function(exclude_from_all target) + set_property(TARGET ${target} PROPERTY + TARGET_MESSAGES OFF + EXCLUDE_FROM_ALL 1 + EXCLUDE_FROM_DEFAULT_BUILD 1) endfunction() function(collect_targets) @@ -61,8 +69,5 @@ function(collect_targets) set(list_target_name "targets") add_custom_target(${list_target_name} COMMAND cmake -E echo "Valid targets: ${targets}") - set_property(TARGET ${list_target_name} PROPERTY - TARGET_MESSAGES OFF - EXCLUDE_FROM_ALL 1 - EXCLUDE_FROM_DEFAULT_BUILD 1) + exclude_from_all(${list_target_name}) endfunction() diff --git a/cmake/openocd.cmake b/cmake/openocd.cmake new file mode 100644 index 00000000000..bfb09806159 --- /dev/null +++ b/cmake/openocd.cmake @@ -0,0 +1,84 @@ +set(OPENOCD "" CACHE STRING "path to openocd (default: search for it)") +set(OPENOCD_CFG "" CACHE STRING "path to openocd configuration (default: generate automatically)") +set(OPENOCD_INTERFACE "" CACHE STRING "openocd interface name (default: automatic depending on target)") + +if (OPENOCD) + set(OPENOCD_PATH ${OPENOCD}) +else() + find_program(OPENOCD_FOUND_PATH NAMES openocd openocd.exe) + if (NOT OPENOCD_FOUND_PATH) + message(STATUS "Could not find openocd, debugging won't be available") + else() + set(OPENOCD_PATH ${OPENOCD_FOUND_PATH}) + endif() +endif() + +if(OPENOCD_PATH) + # Retrieve version number as a sanity check + execute_process(COMMAND ${OPENOCD_PATH} -v + OUTPUT_QUIET + ERROR_VARIABLE OPENOCD_HELP + RESULT_VARIABLE OPENOCD_RESULT) + + string(REPLACE "\n" ";" OPENOCD_HELP_LINES ${OPENOCD_HELP}) + list(GET OPENOCD_HELP_LINES 0 OPENOCD_FIRST_HELP_LINE) + string(REPLACE "\r" "" OPENOCD_HELP_LINE ${OPENOCD_FIRST_HELP_LINE}) + if (NOT OPENOCD_RESULT EQUAL 0) + # User provided an incorrect path + message(FATAL_ERROR "error executing ${OPENOCD_PATH} (${OPENOCD_RESULT})") + endif() + message(STATUS "using openocd: ${OPENOCD_HELP_LINE}") + add_custom_target(openocd ${OPENOCD_PATH} -f ${OPENOCD_CFG} + COMMENT "Run openocd using OPENOCD_CFG=(${OPENOCD_CFG}) as configuration" + USES_TERMINAL + ) +endif() + +function(setup_openocd target_name) + if(OPENOCD_INTERFACE) + set(openocd_interface ${OPENOCD_INTERFACE}) + else() + get_property(openocd_interface TARGET ${target_name} PROPERTY OPENOCD_DEFAULT_INTERFACE) + endif() + get_property(openocd_target TARGET ${target_name} PROPERTY OPENOCD_TARGET) + if(OPENOCD_CFG OR (openocd_target AND openocd_interface)) + set(openocd_run_target "openocd_${target_name}") + if (OPENOCD_CFG AND NOT OPENOCD_CFG STREQUAL "") + get_filename_component(openocd_cfg_path ${OPENOCD_CFG} + ABSOLUTE + BASE_DIR ${CMAKE_BINARY_DIR}) + else() + set(openocd_cfg_path ${CMAKE_BINARY_DIR}/openocd/${target_name}.cfg) + add_custom_command( + OUTPUT ${openocd_cfg_path} + COMMENT "Generating openocd configuration for ${openocd_target} via ${openocd_interface}" + COMMAND ${CMAKE_COMMAND} -P ${MAIN_DIR}/cmake/openocd_cfg.cmake + ${openocd_target} ${openocd_interface} ${openocd_cfg_path} + ) + endif() + + # Target for openocd configuration + set(openocd_cfg_target "openocd_cfg_${target_name}") + add_custom_target(${openocd_cfg_target} DEPENDS ${openocd_cfg_path}) + exclude_from_all(${openocd_cfg_target}) + + # Target for running openocd + add_custom_target(${openocd_run_target} ${OPENOCD_PATH} -f ${openocd_cfg_path} + COMMENT "Running openocd for target ${target_name} via ${openocd_interface}" + DEPENDS ${openocd_cfg_path} + USES_TERMINAL + ) + exclude_from_all(${openocd_run_target}) + # Target for flashing via openocd + set(openocd_flash_target "openocd_flash_${target_name}") + add_custom_target(${openocd_flash_target} ${CMAKE_COMMAND} -E env + OPENOCD_CMD=${OPENOCD_PATH} + ${MAIN_UTILS_DIR}/openocd_flash.py -f + ${openocd_cfg_path} $ + + COMMENT "Flashing ${target_name} with openocd" + DEPENDS ${openocd_cfg_path} ${target_name} + ) + exclude_from_all(${openocd_flash_target}) + endif() +endfunction() diff --git a/cmake/openocd_cfg.cmake b/cmake/openocd_cfg.cmake new file mode 100644 index 00000000000..9c2ca220003 --- /dev/null +++ b/cmake/openocd_cfg.cmake @@ -0,0 +1,20 @@ +# This is called from the targets that build the +# openocd.cfg file +if(NOT CMAKE_ARGC EQUAL 6) + message(FATAL_ERROR "usage: cmake -P openocd_cfg.cmake ") +endif() + +set(OPENOCD_TARGET ${CMAKE_ARGV3}) +set(OPENOCD_INTERFACE ${CMAKE_ARGV4}) +set(OUTPUT ${CMAKE_ARGV5}) + +set(opencd_cfg) +list(APPEND openocd_cfg "source [find interface/${OPENOCD_INTERFACE}.cfg]") +list(APPEND openocd_cfg "source [find target/${OPENOCD_TARGET}.cfg]") +list(APPEND openocd_cfg "init") +list(APPEND openocd_cfg "arm semihosting enable") +list(APPEND openocd_cfg "reset halt") +list(JOIN openocd_cfg "\n" contents) +set(contents "${contents}\n") + +file(WRITE ${OUTPUT} ${contents}) \ No newline at end of file diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake index bed6af3e019..fc7d9392ee8 100644 --- a/cmake/stm32.cmake +++ b/cmake/stm32.cmake @@ -157,11 +157,12 @@ function(target_stm32 name startup ldscript) # Parse keyword arguments cmake_parse_arguments( PARSED_ARGS - "DISABLE_MSC" # Boolean arguments - "HSE_MHZ" # Single value arguments - "DEFINITIONS" # Multi-value arguments - ${ARGN} # Start parsing after the known arguments + "DISABLE_MSC" # Boolean arguments + "HSE_MHZ;OPENOCD_TARGET" # Single value arguments + "DEFINITIONS" # Multi-value arguments + ${ARGN} # Start parsing after the known arguments ) + if (PARSED_ARGS_HSE_MHZ) set(hse_mhz ${PARSED_ARGS_HSE_MHZ}) else() @@ -210,6 +211,8 @@ function(target_stm32 name startup ldscript) endif() endif() endif() + set_property(TARGET ${name} PROPERTY OPENOCD_TARGET ${PARSED_ARGS_OPENOCD_TARGET}) + set_property(TARGET ${name} PROPERTY OPENOCD_DEFAULT_INTERFACE stlink) # Generate .hex # XXX: Generator expressions are not supported for add_custom_command() # OUTPUT nor BYPRODUCTS, so we can't rely of them. Instead, build the filename diff --git a/cmake/stm32f3.cmake b/cmake/stm32f3.cmake index 2634fcb2377..4aa8248c21b 100644 --- a/cmake/stm32f3.cmake +++ b/cmake/stm32f3.cmake @@ -60,7 +60,7 @@ set(STM32F303_DEFINITIONS function(target_stm32f3xx name startup ldscript) # F3 targets don't support MSC - target_stm32(${name} ${startup} ${ldscript} DISABLE_MSC ${ARGN}) + target_stm32(${name} ${startup} ${ldscript} DISABLE_MSC OPENOCD_TARGET stm32f3x ${ARGN}) # F3 targets don't use -O2 to save size if (IS_RELEASE_BUILD) target_compile_options(${name} PRIVATE "-Os") diff --git a/cmake/stm32f4.cmake b/cmake/stm32f4.cmake index d87995522c6..a0e7429e336 100644 --- a/cmake/stm32f4.cmake +++ b/cmake/stm32f4.cmake @@ -76,7 +76,7 @@ set(STM32F4_DEFINITIONS ) function(target_stm32f4xx name startup ldscript) - target_stm32(${name} ${startup} ${ldscript} ${ARGN}) + target_stm32(${name} ${startup} ${ldscript} OPENOCD_TARGET stm32f4x ${ARGN}) if (IS_RELEASE_BUILD) target_compile_options(${name} PRIVATE "-O2") target_link_options(${name} PRIVATE "-O2") diff --git a/cmake/stm32f7.cmake b/cmake/stm32f7.cmake index af6b8328030..a452eaff362 100644 --- a/cmake/stm32f7.cmake +++ b/cmake/stm32f7.cmake @@ -83,7 +83,7 @@ set(STM32F7_DEFINITIONS ) function(target_stm32f7xx name startup ldscript) - target_stm32(${name} ${startup} ${ldscript} ${ARGN}) + target_stm32(${name} ${startup} ${ldscript} OPENOCD_TARGET stm32f7x ${ARGN}) if (IS_RELEASE_BUILD) target_compile_options(${name} PRIVATE "-O2") target_link_options(${name} PRIVATE "-O2") diff --git a/src/utils/openocd_flash.py b/src/utils/openocd_flash.py new file mode 100755 index 00000000000..f2dc2391df9 --- /dev/null +++ b/src/utils/openocd_flash.py @@ -0,0 +1,86 @@ +#!/usr/bin/env python + +from __future__ import print_function + +import os +import socket +import subprocess +import sys + +def openocd_telnet_await_prompt(s): + prev = None + while True: + b = s.recv(1) + if b == '': + # Closed + return False + if prev == '>' and b == ' ': + # Prompt for next command + return True + prev = b + print(b, end='') + +def openocd_telnet_command(s, cmd): + s.send(cmd + '\n') + openocd_telnet_await_prompt(s) + +def openocd_flash_telnet(port, filename): + try: + s = socket.create_connection(('localhost', port)) + except socket.error: + return False + + openocd_telnet_await_prompt(s) + openocd_telnet_command(s, 'halt') + openocd_telnet_command(s, 'program {} verify reset\n'.format(filename)) + openocd_telnet_command(s, 'exit') + s.close() + return True + +def openocd_flash_cmd(openocd, args, filename): + cmd = [openocd] + cmd.extend(args) + cmd.extend(('-c', 'program {} verify reset exit'.format(filename))) + status = subprocess.call(cmd) + return status == 0 + +def usage(): + print('Usage: {} '.format(sys.argv[0])) + print('Environment variables: OPENOCD_CMD = path to openocd') + sys.exit(1) + +def main(): + import sys + + # Default openocd telnet port + # TODO: Parse arguments and check if we + # should use a non-default port + port = 4444 + openocd = os.environ.get('OPENOCD_CMD') or 'openocd' + + openocd_args = [] + flag = None + elf = None + for arg in sys.argv[1:]: + if flag: + openocd_args.append(arg) + flag = None + else: + if arg.startswith('-'): + openocd_args.append(arg) + flag = arg + elif elf is None: + elf = arg + else: + usage() + + if len(openocd_args) == 0 or elf is None: + usage() + + if not openocd_flash_telnet(port, elf): + if not openocd_flash_cmd(openocd, openocd_args, elf): + print('could not flash') + sys.exit(1) + +if __name__ == '__main__': + main() From 93723d0ad0e159df8fa2ec0cfdfc5f5aa5ff9fd4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 13 Jul 2020 21:29:15 +0100 Subject: [PATCH 149/248] [BUILD] Add support for svd generation with cmake Used for IDE-based debugging --- CMakeLists.txt | 2 ++ cmake/main.cmake | 1 + cmake/stm32.cmake | 3 ++- cmake/stm32f3.cmake | 2 +- cmake/stm32f4.cmake | 6 +++--- cmake/svd.cmake | 16 ++++++++++++++++ 6 files changed, 25 insertions(+), 5 deletions(-) create mode 100644 cmake/svd.cmake diff --git a/CMakeLists.txt b/CMakeLists.txt index bbf476e2d1a..08e4bbbaf94 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -41,6 +41,7 @@ set(MAIN_DIR "${CMAKE_CURRENT_SOURCE_DIR}") set(MAIN_LIB_DIR "${CMAKE_CURRENT_SOURCE_DIR}/lib") set(MAIN_UTILS_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src/utils") set(MAIN_SRC_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src/main") +set(SVD_DIR "${CMAKE_CURRENT_SOURCE_DIR}/dev/svd") list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake") @@ -48,6 +49,7 @@ set(FIRMWARE_VERSION ${PROJECT_VERSION}) include(settings) include(openocd) +include(svd) include(main) include(stm32) diff --git a/cmake/main.cmake b/cmake/main.cmake index 2755e91c176..54033ba2551 100644 --- a/cmake/main.cmake +++ b/cmake/main.cmake @@ -54,6 +54,7 @@ function(setup_firmware_target name) get_property(targets GLOBAL PROPERTY VALID_TARGETS) set_property(GLOBAL PROPERTY VALID_TARGETS "${targets} ${name}") setup_openocd(${name}) + setup_svd(${name}) endfunction() function(exclude_from_all target) diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake index fc7d9392ee8..1f21be20258 100644 --- a/cmake/stm32.cmake +++ b/cmake/stm32.cmake @@ -158,7 +158,7 @@ function(target_stm32 name startup ldscript) cmake_parse_arguments( PARSED_ARGS "DISABLE_MSC" # Boolean arguments - "HSE_MHZ;OPENOCD_TARGET" # Single value arguments + "HSE_MHZ;OPENOCD_TARGET;SVD" # Single value arguments "DEFINITIONS" # Multi-value arguments ${ARGN} # Start parsing after the known arguments ) @@ -213,6 +213,7 @@ function(target_stm32 name startup ldscript) endif() set_property(TARGET ${name} PROPERTY OPENOCD_TARGET ${PARSED_ARGS_OPENOCD_TARGET}) set_property(TARGET ${name} PROPERTY OPENOCD_DEFAULT_INTERFACE stlink) + set_property(TARGET ${name} PROPERTY SVD ${PARSED_ARGS_SVD}) # Generate .hex # XXX: Generator expressions are not supported for add_custom_command() # OUTPUT nor BYPRODUCTS, so we can't rely of them. Instead, build the filename diff --git a/cmake/stm32f3.cmake b/cmake/stm32f3.cmake index 4aa8248c21b..39279fa6227 100644 --- a/cmake/stm32f3.cmake +++ b/cmake/stm32f3.cmake @@ -80,7 +80,7 @@ function(target_stm32f3xx name startup ldscript) endfunction() function(target_stm32f303 name) - target_stm32f3xx(${name} startup_stm32f30x_md_gcc.S stm32_flash_f303_256k.ld ${ARGN}) + target_stm32f3xx(${name} startup_stm32f30x_md_gcc.S stm32_flash_f303_256k.ld SVD STM32F303 ${ARGN}) target_compile_definitions(${name} PRIVATE ${STM32F303_DEFINITIONS}) setup_firmware_target(${name}) endfunction() diff --git a/cmake/stm32f4.cmake b/cmake/stm32f4.cmake index a0e7429e336..ba6ab602dd4 100644 --- a/cmake/stm32f4.cmake +++ b/cmake/stm32f4.cmake @@ -104,7 +104,7 @@ set(STM32F405_COMPILE_DEFINITIONS ) function(target_stm32f405 name) - target_stm32f4xx(${name} startup_stm32f40xx.s stm32_flash_f405.ld ${ARGN}) + target_stm32f4xx(${name} startup_stm32f40xx.s stm32_flash_f405.ld SVD STM32F405 ${ARGN}) target_sources(${name} PRIVATE ${STM32F4_STDPERIPH_SRC}) target_compile_definitions(${name} PRIVATE ${STM32F405_COMPILE_DEFINITIONS}) setup_firmware_target(${name}) @@ -120,7 +120,7 @@ set(STM32F411_COMPILE_DEFINITIONS ) function(target_stm32f411 name) - target_stm32f4xx(${name} startup_stm32f411xe.s stm32_flash_f411.ld) + target_stm32f4xx(${name} startup_stm32f411xe.s stm32_flash_f411.ld SVD STM32F411 ${ARGN}) target_sources(${name} PRIVATE ${STM32F411_OR_F427_STDPERIPH_SRC}) target_compile_definitions(${name} PRIVATE ${STM32F411_COMPILE_DEFINITIONS}) setup_firmware_target(${name}) @@ -131,7 +131,7 @@ set(STM32F427_COMPILE_DEFINITIONS FLASH_SIZE=1024 ) function(target_stm32f427 name) - target_stm32f4xx(${name} startup_stm32f427xx.s stm32_flash_f427.ld ${ARGN}) + target_stm32f4xx(${name} startup_stm32f427xx.s stm32_flash_f427.ld SVD STM32F427 ${ARGN}) target_sources(${name} PRIVATE ${STM32F411_OR_F427_STDPERIPH_SRC}) target_compile_definitions(${name} PRIVATE ${STM32F427_COMPILE_DEFINITIONS}) setup_firmware_target(${name}) diff --git a/cmake/svd.cmake b/cmake/svd.cmake new file mode 100644 index 00000000000..06be82c394c --- /dev/null +++ b/cmake/svd.cmake @@ -0,0 +1,16 @@ +function(setup_svd target_name) + get_property(svd_name TARGET ${target_name} PROPERTY SVD) + set(svd_target_name "svd_${target_name}") + if (svd_name AND NOT svd_name STREQUAL "") + add_custom_target(${svd_target_name} + COMMAND ${CMAKE_COMMAND} -E copy + ${SVD_DIR}/${svd_name}.svd + ${CMAKE_BINARY_DIR}/svd/${target_name}.svd + ) + else() + add_custom_target(${svd_target_name} + cmake -E echo "target ${target_name} does not declare an SVD filename" + COMMAND cmake -E false) + endif() + exclude_from_all(${svd_target_name}) +endfunction() \ No newline at end of file From 9d054d1be7af9c63cafabf6df31612274e3d32eb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 13 Jul 2020 21:32:48 +0100 Subject: [PATCH 150/248] [DEVELOPMENT] Update vscode config templates for inav development --- dev/vscode/launch.json | 13 +++++++++---- dev/vscode/tasks.json | 33 +++++++-------------------------- 2 files changed, 16 insertions(+), 30 deletions(-) diff --git a/dev/vscode/launch.json b/dev/vscode/launch.json index 55af041e7da..501625722da 100644 --- a/dev/vscode/launch.json +++ b/dev/vscode/launch.json @@ -2,22 +2,27 @@ // Use IntelliSense to learn about possible attributes. // Hover to view descriptions of existing attributes. // For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387 + + // ******* INAV ******** + // Define the following values in settings.json + // - BUILD_DIR: Relative path to the build directory + // - TARGET: Target name that you want to launch + "version": "0.2.0", "configurations": [ { "name": "Cortex Debug", "cwd": "${workspaceRoot}", - "executable": "./obj/main/INAV_${config:TARGET}.elf", + "executable": "${config:BUILD_DIR}/bin/${config:TARGET}.elf", "request": "launch", "type": "cortex-debug", "servertype": "openocd", "device": "${config:TARGET}", "configFiles": [ - "./obj/main/${config:TARGET}/openocd.cfg" + "${config:BUILD_DIR}/openocd/${config:TARGET}.cfg" ], - "preLaunchCommands": ["monitor arm semihosting enable"], "preLaunchTask": "openocd-debug-prepare", - "svdFile": "./obj/main/${config:TARGET}/svd.svd", + "svdFile": "${config:BUILD_DIR}/svd/${config:TARGET}.svd", } ] } diff --git a/dev/vscode/tasks.json b/dev/vscode/tasks.json index 449719d48c9..768145e7bb8 100644 --- a/dev/vscode/tasks.json +++ b/dev/vscode/tasks.json @@ -5,14 +5,13 @@ "options": { "env": { "TARGET": "${config:TARGET}", - "SEMIHOSTING": "${config:SEMIHOSTING}" } }, "tasks": [ { - "label": "hex", + "label": "target", "type": "shell", - "command": "make", "args": ["hex"], + "command": "make", "args": ["-C", "${config:BUILD_DIR}", "${config:TARGET}"], "problemMatcher": "$gcc", "group": { "kind": "build", @@ -25,45 +24,27 @@ } }, { - "label": "elf", + "label": "flash", "type": "shell", - "command": "make", "args": ["elf"], - "problemMatcher": "$gcc", - "group": "build", - "presentation": { - "echo": true, - "reveal": "always", - "focus": false, - } - }, - { - "label": "openocd-flash", - "type": "shell", - "command": "make", "args": ["openocd-flash"], + "command": "make", "args": ["-C", "${config:BUILD_DIR}", "openocd_flash_${config:TARGET}"], "dependsOn": "elf" }, - { - "label": "clean", - "type": "shell", - "command": "make", "args": ["clean"], - "problemMatcher": [] - }, { "label": "svd", "type": "shell", - "command": "make", "args": ["svd"], + "command": "make", "args": ["-C", "${config:BUILD_DIR}", "svd_${config:TARGET}"], "problemMatcher": [] }, { "label": "openocd-cfg", "type": "shell", - "command": "make", "args": ["openocd-cfg"], + "command": "make", "args": ["-C", "${config:BUILD_DIR}", "openocd_cfg_${config:TARGET}"], "problemMatcher": [] }, { "label": "openocd-debug-prepare", "type": "shell", - "dependsOn": ["svd", "openocd-cfg", "openocd-flash"], + "dependsOn": ["svd", "openocd-cfg", "flash"], "problemMatcher": [] } ] From b9a5f95df9832bfea0d710a506edacd8ea361bb2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sat, 25 Jul 2020 21:40:31 +0100 Subject: [PATCH 151/248] [BUILD] Add missing targets to cmake FLYWOOF411, FLYWOOF72DUAL, FOXEERF722V2 and IFLIGHTF4_SUCCEXD --- src/main/target/FLYWOOF411/CMakeLists.txt | 1 + src/main/target/FLYWOOF7DUAL/CMakeLists.txt | 1 + src/main/target/FOXEERF722DUAL/CMakeLists.txt | 3 ++- src/main/target/HGLRCF722/CMakeLists.txt | 1 + src/main/target/IFLIGHTF4_SUCCEXD/CMakeLists.txt | 1 + 5 files changed, 6 insertions(+), 1 deletion(-) create mode 100644 src/main/target/FLYWOOF411/CMakeLists.txt create mode 100644 src/main/target/FLYWOOF7DUAL/CMakeLists.txt create mode 100644 src/main/target/HGLRCF722/CMakeLists.txt create mode 100644 src/main/target/IFLIGHTF4_SUCCEXD/CMakeLists.txt diff --git a/src/main/target/FLYWOOF411/CMakeLists.txt b/src/main/target/FLYWOOF411/CMakeLists.txt new file mode 100644 index 00000000000..ef56491f3b5 --- /dev/null +++ b/src/main/target/FLYWOOF411/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f411(FLYWOOF411) diff --git a/src/main/target/FLYWOOF7DUAL/CMakeLists.txt b/src/main/target/FLYWOOF7DUAL/CMakeLists.txt new file mode 100644 index 00000000000..00373c55d39 --- /dev/null +++ b/src/main/target/FLYWOOF7DUAL/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722(FLYWOOF7DUAL) \ No newline at end of file diff --git a/src/main/target/FOXEERF722DUAL/CMakeLists.txt b/src/main/target/FOXEERF722DUAL/CMakeLists.txt index bc00522e869..560189ff1ba 100644 --- a/src/main/target/FOXEERF722DUAL/CMakeLists.txt +++ b/src/main/target/FOXEERF722DUAL/CMakeLists.txt @@ -1 +1,2 @@ -target_stm32f722(FOXEERF722DUAL) \ No newline at end of file +target_stm32f722(FOXEERF722DUAL) +target_stm32f722(FOXEERF722V2) \ No newline at end of file diff --git a/src/main/target/HGLRCF722/CMakeLists.txt b/src/main/target/HGLRCF722/CMakeLists.txt new file mode 100644 index 00000000000..3015c57d0a8 --- /dev/null +++ b/src/main/target/HGLRCF722/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722(HGLRCF722) \ No newline at end of file diff --git a/src/main/target/IFLIGHTF4_SUCCEXD/CMakeLists.txt b/src/main/target/IFLIGHTF4_SUCCEXD/CMakeLists.txt new file mode 100644 index 00000000000..7c0d18cb3fe --- /dev/null +++ b/src/main/target/IFLIGHTF4_SUCCEXD/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f411(IFLIGHTF4_SUCCEXD) \ No newline at end of file From bc327ea31366f665c53dea64762edbb793cf433c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sat, 25 Jul 2020 21:41:31 +0100 Subject: [PATCH 152/248] [BUILD] Add missing/renamed sources to cmake sources list --- src/main/CMakeLists.txt | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 71eed6f906d..c1a749648ea 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -16,9 +16,6 @@ main_sources(COMMON_SRC common/filter.c common/gps_conversion.c common/log.c - common/logic_condition.c - common/global_functions.c - common/global_variables.c common/maths.c common/memory.c common/olc.c @@ -81,6 +78,8 @@ main_sources(COMMON_SRC drivers/barometer/barometer_bmp280.h drivers/barometer/barometer_bmp388.c drivers/barometer/barometer_bmp388.h + drivers/barometer/barometer_dps310.c + drivers/barometer/barometer_dps310.h drivers/barometer/barometer_fake.c drivers/barometer/barometer_fake.h drivers/barometer/barometer_lps25h.c @@ -121,12 +120,15 @@ main_sources(COMMON_SRC drivers/display.c drivers/display_canvas.c drivers/display_font_metadata.c + drivers/display_widgets.c drivers/display_ug2864hsweg01.c drivers/exti.c drivers/flash.c drivers/flash_m25p16.c drivers/io.c drivers/io_pca9685.c + drivers/io_pcf8574.c + drivers/io_port_expander.c drivers/irlock.c drivers/light_led.c drivers/light_ws2811strip.c @@ -193,6 +195,7 @@ main_sources(COMMON_SRC flight/failsafe.c flight/hil.c flight/imu.c + flight/kalman.c flight/mixer.c flight/pid.c flight/pid_autotune.c @@ -221,6 +224,10 @@ main_sources(COMMON_SRC msp/msp_serial.c + programming/logic_condition.c + programming/global_variables.c + programming/programming_task.c + rx/crsf.c rx/eleres.c rx/fport.c From b9d3bc5ef744b86b21c053fc2ff4a2ab20d467a6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sat, 25 Jul 2020 22:31:22 +0100 Subject: [PATCH 153/248] [BUILD] Add missing headers to main sources list --- src/main/CMakeLists.txt | 234 ++++++++++++++++++++++++++++++++++++++-- 1 file changed, 227 insertions(+), 7 deletions(-) diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index c1a749648ea..d9c4123055c 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -4,37 +4,66 @@ main_sources(COMMON_SRC target/common_hardware.c build/assert.c + build/assert.h build/build_config.c + build/build_config.h build/debug.c + build/debug.h build/version.c + build/version.h common/bitarray.c + common/bitarray.h common/calibration.c + common/calibration.h common/colorconversion.c + common/colorconversion.h common/crc.c + common/crc.h common/encoding.c + common/encoding.h common/filter.c + common/filter.h common/gps_conversion.c + common/gps_conversion.h common/log.c + common/log.h common/maths.c + common/maths.h common/memory.c + common/memory.h common/olc.c + common/olc.h common/printf.c + common/printf.h common/streambuf.c + common/streambuf.h common/string_light.c + common/string_light.h common/time.c + common/time.h common/typeconversion.c + common/typeconversion.h common/uvarint.c + common/uvarint.h config/config_eeprom.c + config/config_eeprom.h config/config_streamer.c + config/config_streamer.h config/feature.c + config/feature.h config/parameter_group.c + config/parameter_group.h config/general_settings.c + config/general_settings.h drivers/1-wire.c + drivers/1-wire.h drivers/1-wire/ds_crc.c + drivers/1-wire/ds_crc.h drivers/1-wire/ds2482.c + drivers/1-wire/ds2482.h drivers/accgyro/accgyro.c drivers/accgyro/accgyro.h @@ -70,6 +99,7 @@ main_sources(COMMON_SRC drivers/accgyro/accgyro_mpu9250.h drivers/adc.c + drivers/adc.h drivers/barometer/barometer.h drivers/barometer/barometer_bmp085.c @@ -90,7 +120,9 @@ main_sources(COMMON_SRC drivers/barometer/barometer_spl06.h drivers/buf_writer.c + drivers/buf_writer.h drivers/bus.c + drivers/bus.h drivers/bus_busdev_i2c.c drivers/bus_busdev_spi.c drivers/bus_i2c_soft.c @@ -118,229 +150,417 @@ main_sources(COMMON_SRC drivers/compass/compass_qmc5883l.h drivers/display.c + drivers/display.h drivers/display_canvas.c + drivers/display_canvas.h drivers/display_font_metadata.c + drivers/display_font_metadata.h drivers/display_widgets.c + drivers/display_widgets.h drivers/display_ug2864hsweg01.c + drivers/display_ug2864hsweg01.h drivers/exti.c + drivers/exti.h drivers/flash.c + drivers/flash.h drivers/flash_m25p16.c + drivers/flash_m25p16.h drivers/io.c + drivers/io.h drivers/io_pca9685.c + drivers/io_pca9685.h drivers/io_pcf8574.c + drivers/io_pcf8574.h drivers/io_port_expander.c + drivers/io_port_expander.h drivers/irlock.c + drivers/irlock.h drivers/light_led.c + drivers/light_led.h drivers/light_ws2811strip.c + drivers/light_ws2811strip.h drivers/lights_io.c + drivers/lights_io.h drivers/max7456.c + drivers/max7456.h drivers/serial_softserial.c + drivers/serial_softserial.h drivers/opflow/opflow_fake.c + drivers/opflow/opflow_fake.h drivers/opflow/opflow_virtual.c + drivers/opflow/opflow_virtual.h drivers/osd.c + drivers/osd.h drivers/persistent.c + drivers/persistent.h drivers/pitotmeter_adc.c + drivers/pitotmeter_adc.h drivers/pitotmeter_ms4525.c + drivers/pitotmeter_ms4525.h drivers/pitotmeter_virtual.c + drivers/pitotmeter_virtual.h drivers/pwm_esc_detect.c + drivers/pwm_esc_detect.h drivers/pwm_mapping.c + drivers/pwm_mapping.h drivers/pwm_output.c + drivers/pwm_output.h drivers/pinio.c + drivers/pinio.h drivers/rangefinder/rangefinder_hcsr04.c + drivers/rangefinder/rangefinder_hcsr04.h drivers/rangefinder/rangefinder_hcsr04_i2c.c + drivers/rangefinder/rangefinder_hcsr04_i2c.h drivers/rangefinder/rangefinder_srf10.c + drivers/rangefinder/rangefinder_srf10.h drivers/rangefinder/rangefinder_vl53l0x.c + drivers/rangefinder/rangefinder_vl53l0x.h drivers/rangefinder/rangefinder_virtual.c + drivers/rangefinder/rangefinder_virtual.h drivers/resource.c + drivers/resource.h drivers/rcc.c + drivers/rcc.h drivers/rx_nrf24l01.c + drivers/rx_nrf24l01.h drivers/rx_pwm.c + drivers/rx_pwm.h drivers/rx_spi.c + drivers/rx_spi.h drivers/rx_xn297.c + drivers/rx_xn297.h drivers/serial.c + drivers/serial.h drivers/sound_beeper.c + drivers/sound_beeper.h drivers/stack_check.c + drivers/stack_check.h drivers/system.c + drivers/system.h drivers/temperature/ds18b20.c + drivers/temperature/ds18b20.h drivers/temperature/lm75.c + drivers/temperature/lm75.h drivers/time.c + drivers/time.h drivers/timer.c + drivers/timer.h drivers/usb_msc.c + drivers/usb_msc.h drivers/vtx_common.c + drivers/vtx_common.h fc/cli.c + fc/cli.h fc/config.c + fc/config.h fc/controlrate_profile.c + fc/controlrate_profile.h fc/fc_core.c + fc/fc_core.h fc/fc_init.c + fc/fc_init.h fc/fc_tasks.c + fc/fc_tasks.h fc/fc_hardfaults.c fc/fc_msp.c + fc/fc_msp.h fc/fc_msp_box.c + fc/fc_msp_box.h fc/rc_smoothing.c + fc/rc_smoothing.h fc/rc_adjustments.c + fc/rc_adjustments.h fc/rc_controls.c + fc/rc_controls.h fc/rc_curves.c + fc/rc_curves.h fc/rc_modes.c + fc/rc_modes.h fc/runtime_config.c + fc/runtime_config.h fc/settings.c + fc/settings.h fc/stats.c + fc/stats.h flight/failsafe.c + flight/failsafe.h flight/hil.c + flight/hil.h flight/imu.c + flight/imu.h flight/kalman.c + flight/kalman.h flight/mixer.c + flight/mixer.h flight/pid.c + flight/pid.h flight/pid_autotune.c flight/rth_estimator.c + flight/rth_estimator.h flight/servos.c + flight/servos.h flight/wind_estimator.c + flight/wind_estimator.h flight/gyroanalyse.c + flight/gyroanalyse.h flight/rpm_filter.c + flight/rpm_filter.h flight/dynamic_gyro_notch.c + flight/dynamic_gyro_notch.h io/beeper.c + io/beeper.h io/esc_serialshot.c + io/esc_serialshot.h io/servo_sbus.c + io/servo_sbus.h io/frsky_osd.c + io/frsky_osd.h io/osd_dji_hd.c + io/osd_dji_hd.h io/lights.c + io/lights.h io/piniobox.c + io/piniobox.h io/pwmdriver_i2c.c + io/pwmdriver_i2c.h io/serial.c + io/serial.h io/serial_4way.c + io/serial_4way.h io/serial_4way_avrootloader.c + io/serial_4way_avrootloader.h io/serial_4way_stk500v2.c + io/serial_4way_stk500v2.h io/statusindicator.c + io/statusindicator.h io/rcdevice.c + io/rcdevice.h io/rcdevice_cam.c + io/rcdevice_cam.h msp/msp_serial.c + msp/msp_serial.h programming/logic_condition.c + programming/logic_condition.h programming/global_variables.c + programming/global_variables.h programming/programming_task.c + programming/programming_task.h rx/crsf.c + rx/crsf.h rx/eleres.c + rx/eleres.h rx/fport.c + rx/fport.h rx/ibus.c + rx/ibus.h rx/jetiexbus.c + rx/jetiexbus.h rx/msp.c + rx/msp.h rx/msp_override.c + rx/msp_override.h rx/nrf24_cx10.c + rx/nrf24_cx10.h rx/nrf24_inav.c + rx/nrf24_inav.h rx/nrf24_h8_3d.c + rx/nrf24_h8_3d.h rx/nrf24_syma.c + rx/nrf24_syma.h rx/nrf24_v202.c + rx/nrf24_v202.h rx/pwm.c + rx/pwm.h rx/frsky_crc.c + rx/frsky_crc.h rx/rx.c + rx/rx.h rx/rx_spi.c + rx/rx_spi.h rx/sbus.c + rx/sbus.h rx/sbus_channels.c + rx/sbus_channels.h rx/spektrum.c + rx/spektrum.h rx/sumd.c + rx/sumd.h rx/sumh.c + rx/sumh.h rx/uib_rx.c + rx/uib_rx.h rx/xbus.c + rx/xbus.h scheduler/scheduler.c + scheduler/scheduler.h sensors/acceleration.c + sensors/acceleration.h sensors/battery.c + sensors/battery.h sensors/boardalignment.c + sensors/boardalignment.h sensors/compass.c + sensors/compass.h sensors/diagnostics.c + sensors/diagnostics.h sensors/gyro.c + sensors/gyro.h sensors/initialisation.c + sensors/initialisation.h sensors/esc_sensor.c + sensors/esc_sensor.h sensors/irlock.c + sensors/irlock.h sensors/temperature.c + sensors/temperature.h + uav_interconnect/uav_interconnect.h uav_interconnect/uav_interconnect_bus.c uav_interconnect/uav_interconnect_rangefinder.c blackbox/blackbox.c + blackbox/blackbox.h blackbox/blackbox_encoding.c + blackbox/blackbox_encoding.h blackbox/blackbox_io.c + blackbox/blackbox_io.h cms/cms.c + cms/cms.h cms/cms_menu_battery.c + cms/cms_menu_battery.h cms/cms_menu_blackbox.c + cms/cms_menu_blackbox.h cms/cms_menu_builtin.c + cms/cms_menu_builtin.h cms/cms_menu_imu.c + cms/cms_menu_imu.h cms/cms_menu_ledstrip.c + cms/cms_menu_ledstrip.h cms/cms_menu_misc.c + cms/cms_menu_misc.h cms/cms_menu_mixer_servo.c + cms/cms_menu_mixer_servo.h cms/cms_menu_navigation.c + cms/cms_menu_navigation.h cms/cms_menu_osd.c + cms/cms_menu_osd.h cms/cms_menu_saveexit.c + cms/cms_menu_saveexit.h cms/cms_menu_vtx.c + cms/cms_menu_vtx.h + io/rangefinder.h io/rangefinder_msp.c io/rangefinder_benewake.c + io/opflow.h io/opflow_cxof.c io/opflow_msp.c io/dashboard.c + io/dashboard.h io/displayport_frsky_osd.c + io/displayport_frsky_osd.h io/displayport_max7456.c + io/displayport_max7456.h io/displayport_msp.c + io/displayport_msp.h io/displayport_oled.c + io/displayport_oled.h io/displayport_hott.c + io/displayport_hott.h io/flashfs.c + io/flashfs.h io/gps.c + io/gps.h io/gps_ublox.c io/gps_nmea.c io/gps_naza.c + io/gps_private.h io/ledstrip.c + io/ledstrip.h io/osd.c + io/osd.h io/osd_canvas.c + io/osd_canvas.h io/osd_common.c + io/osd_common.h io/osd_grid.c + io/osd_grid.h io/osd_hud.c + io/osd_hud.h + io/vtx.c + io/vtx.h + io/vtx_string.c + io/vtx_string.h + io/vtx_smartaudio.c + io/vtx_smartaudio.h + io/vtx_tramp.c + io/vtx_tramp.h + io/vtx_ffpv24g.c + io/vtx_ffpv24g.h + io/vtx_control.c + io/vtx_control.h navigation/navigation.c + navigation/navigation.h navigation/navigation_fixedwing.c navigation/navigation_fw_launch.c navigation/navigation_geo.c navigation/navigation_multicopter.c navigation/navigation_pos_estimator.c + navigation/navigation_pos_estimator_private.h navigation/navigation_pos_estimator_agl.c navigation/navigation_pos_estimator_flow.c + navigation/navigation_private.h navigation/navigation_rover_boat.c sensors/barometer.c + sensors/barometer.h sensors/pitotmeter.c + sensors/pitotmeter.h sensors/rangefinder.c + sensors/rangefinder.h sensors/opflow.c + sensors/opflow.h telemetry/crsf.c + telemetry/crsf.h telemetry/frsky.c + telemetry/frsky.h telemetry/frsky_d.c + telemetry/frsky_d.h telemetry/hott.c + telemetry/hott.h telemetry/ibus_shared.c + telemetry/ibus_shared.h telemetry/ibus.c + telemetry/ibus.h telemetry/ltm.c + telemetry/ltm.h telemetry/mavlink.c + telemetry/mavlink.h telemetry/msp_shared.c + telemetry/msp_shared.h telemetry/smartport.c + telemetry/smartport.h telemetry/sim.c + telemetry/sim.h telemetry/telemetry.c - - io/vtx.c - io/vtx_string.c - io/vtx_smartaudio.c - io/vtx_tramp.c - io/vtx_ffpv24g.c - io/vtx_control.c + telemetry/telemetry.h ) add_subdirectory(target) From 49b9347b106ba984e17d2f7854a772f3f12495e2 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 27 Jul 2020 22:06:59 +0100 Subject: [PATCH 154/248] [BUILD] Print the number of targets for the current toolchain with cmake --- cmake/main.cmake | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/cmake/main.cmake b/cmake/main.cmake index 54033ba2551..ccf39b8514b 100644 --- a/cmake/main.cmake +++ b/cmake/main.cmake @@ -52,7 +52,8 @@ function(setup_firmware_target name) RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin" ) get_property(targets GLOBAL PROPERTY VALID_TARGETS) - set_property(GLOBAL PROPERTY VALID_TARGETS "${targets} ${name}") + list(APPEND targets ${name}) + set_property(GLOBAL PROPERTY VALID_TARGETS "${targets}") setup_openocd(${name}) setup_svd(${name}) endfunction() @@ -67,8 +68,11 @@ endfunction() function(collect_targets) get_property(targets GLOBAL PROPERTY VALID_TARGETS) list(SORT targets) + list(JOIN targets " " target_names) set(list_target_name "targets") add_custom_target(${list_target_name} - COMMAND cmake -E echo "Valid targets: ${targets}") + COMMAND cmake -E echo "Valid targets: ${target_names}") exclude_from_all(${list_target_name}) + list(LENGTH targets target_count) + message("-- ${target_count} targets found for toolchain ${TOOLCHAIN}") endfunction() From fd42e03f04ca7ea9ac7b4c69cbb2c57007c89f8d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 27 Jul 2020 22:07:36 +0100 Subject: [PATCH 155/248] [BUILD] Add more compile options for stm32 WARNIGNS_AS_ERRORS, DEBUG_HARDFAULTS and SEMIHOSTING can now be turned on/off --- CMakeLists.txt | 3 +++ cmake/stm32.cmake | 28 +++++++++++++++++++++------- 2 files changed, 24 insertions(+), 7 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 08e4bbbaf94..384edba5629 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -47,6 +47,9 @@ list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake") set(FIRMWARE_VERSION ${PROJECT_VERSION}) +option(WARNINGS_AS_ERRORS "Make all warnings into errors") +message("-- toolchain: ${TOOLCHAIN}, WARNINGS_AS_ERRORS: ${WARNINGS_AS_ERRORS}") + include(settings) include(openocd) include(svd) diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake index 1f21be20258..213f3819d22 100644 --- a/cmake/stm32.cmake +++ b/cmake/stm32.cmake @@ -5,6 +5,11 @@ include(stm32f7) include(CMakeParseArguments) +option(DEBUG_HARDFAULTS "Enable debugging of hard faults via custom handler") +option(SEMIHOSTING "Enable semihosting") + +message("-- DEBUG_HARDFAULTS: ${DEBUG_HARDFAULTS}, SEMIHOSTING: ${SEMIHOSTING}") + set(CMSIS_DIR "${MAIN_LIB_DIR}/main/CMSIS") set(CMSIS_INCLUDE_DIR "${CMSIS_DIR}/Core/Include") set(CMSIS_DSP_DIR "${MAIN_LIB_DIR}/main/CMSIS/DSP") @@ -70,12 +75,14 @@ set(STM32_INCLUDE_DIRS set(STM32_DEFINITIONS ) - set(STM32_DEFAULT_HSE_MHZ 8) - set(STM32_LINKER_DIR "${MAIN_SRC_DIR}/target/link") +set(STM32_COMPILE_OPTIONS + -ffunction-sections + -fdata-sections + -fno-common +) -set(STM32_LIBS lnosys) #if(SEMIHOSTING) # set(SEMIHOSTING_DEFINITIONS "SEMIHOSTING") # set(SEMIHOSTING_LDFLAGS @@ -170,16 +177,20 @@ function(target_stm32 name startup ldscript) endif() # Main .elf target - add_executable(${name} ${COMMON_SRC} ${CMSIS_DSP_SRC}) + add_executable(${name}) + target_sources(${name} PRIVATE "${STM32_STARTUP_DIR}/${startup}" ${COMMON_SRC} ${CMSIS_DSP_SRC}) file(GLOB target_c_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.c") file(GLOB target_h_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.h") target_sources(${name} PRIVATE ${target_c_sources} ${target_h_sources}) - target_sources(${name} PRIVATE "${STM32_STARTUP_DIR}/${startup}") - target_link_options(${name} PRIVATE "-T${STM32_LINKER_DIR}/${ldscript}") - target_link_options(${name} PRIVATE "-Wl,-Map,$.map") target_include_directories(${name} PRIVATE . ${STM32_INCLUDE_DIRS}) + target_compile_options(${name} PRIVATE ${STM32_COMPILE_OPTIONS}) + if(WARNINGS_AS_ERRORS) + target_compile_options(${name} PRIVATE -Werror) + endif() target_link_libraries(${name} PRIVATE ${STM32_LINK_LIBRARIES}) target_link_options(${name} PRIVATE ${STM32_LINK_OPTIONS}) + target_link_options(${name} PRIVATE "-T${STM32_LINKER_DIR}/${ldscript}") + target_link_options(${name} PRIVATE "-Wl,-Map,$.map") set(target_definitions ${STM32_DEFINITIONS}) math(EXPR hse_value "${hse_mhz} * 1000000") @@ -187,6 +198,9 @@ function(target_stm32 name startup ldscript) if(PARSED_ARGS_DEFINITIONS) list(APPEND target_definitions ${PARSED_ARGS_DEFINITIONS}) endif() + if(DEBUG_HARDFAULTS) + list(APPEND target_definitions DEBUG_HARDFAULTS) + endif() target_compile_definitions(${name} PRIVATE ${target_definitions}) get_stm32_target_features(features "${CMAKE_CURRENT_SOURCE_DIR}" ${name}) From d0938cc21f740647819d5a9381b6488b1864a98a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sun, 9 Aug 2020 21:42:47 +0100 Subject: [PATCH 156/248] [CMAKE] Add support for bootloader targets - Rename function for target name definitions to include full MCU names, so we can support multiple size variants of the same MCU cleanly - Add cmake targets for .bin/.hex files from .elf files - Add targets for bootloader generation - Add targets for combining the bootloader with the main firmware --- CMakeLists.txt | 1 + cmake/arm-none-eabi.cmake | 20 +- cmake/main.cmake | 27 +- cmake/openocd.cmake | 10 +- cmake/settings.cmake | 14 +- cmake/stm32-bootloader.cmake | 30 ++ cmake/stm32.cmake | 306 ++++++++++++++---- cmake/stm32f3.cmake | 52 +-- cmake/stm32f4-usb.cmake | 4 + cmake/stm32f4.cmake | 84 +++-- cmake/stm32f7.cmake | 68 ++-- cmake/svd.cmake | 4 +- src/main/CMakeLists.txt | 4 + src/main/startup/startup_stm32f427xx.s | 0 src/main/target/AIKONF4/CMakeLists.txt | 2 +- src/main/target/AIRBOTF4/CMakeLists.txt | 2 +- src/main/target/AIRBOTF7/CMakeLists.txt | 4 +- src/main/target/AIRHEROF3/CMakeLists.txt | 4 +- .../target/ALIENFLIGHTNGF7/CMakeLists.txt | 2 +- src/main/target/ANYFC/CMakeLists.txt | 2 +- src/main/target/ANYFCF7/CMakeLists.txt | 4 +- src/main/target/ASGARD32F4/CMakeLists.txt | 2 +- src/main/target/ASGARD32F7/CMakeLists.txt | 2 +- src/main/target/BEEROTORF4/CMakeLists.txt | 2 +- src/main/target/BETAFLIGHTF3/CMakeLists.txt | 2 +- src/main/target/BETAFLIGHTF4/CMakeLists.txt | 2 +- src/main/target/BLUEJAYF4/CMakeLists.txt | 2 +- src/main/target/CLRACINGF4AIR/CMakeLists.txt | 6 +- src/main/target/COLIBRI/CMakeLists.txt | 4 +- src/main/target/DALRCF405/CMakeLists.txt | 2 +- src/main/target/DALRCF722DUAL/CMakeLists.txt | 2 +- src/main/target/F4BY/CMakeLists.txt | 2 +- src/main/target/FALCORE/CMakeLists.txt | 2 +- .../target/FF_F35_LIGHTNING/CMakeLists.txt | 4 +- src/main/target/FF_FORTINIF4/CMakeLists.txt | 2 +- src/main/target/FF_PIKOF4/CMakeLists.txt | 4 +- src/main/target/FIREWORKSV2/CMakeLists.txt | 4 +- src/main/target/FISHDRONEF4/CMakeLists.txt | 2 +- src/main/target/FLYWOOF411/CMakeLists.txt | 2 +- src/main/target/FLYWOOF7DUAL/CMakeLists.txt | 2 +- src/main/target/FOXEERF405/CMakeLists.txt | 2 +- src/main/target/FOXEERF722DUAL/CMakeLists.txt | 4 +- src/main/target/FRSKYF3/CMakeLists.txt | 2 +- src/main/target/FRSKYF4/CMakeLists.txt | 2 +- src/main/target/FURYF3/CMakeLists.txt | 4 +- src/main/target/FURYF4OSD/CMakeLists.txt | 4 +- src/main/target/HGLRCF722/CMakeLists.txt | 2 +- .../target/IFLIGHTF4_SUCCEXD/CMakeLists.txt | 2 +- .../target/IFLIGHTF4_TWING/CMakeLists.txt | 2 +- .../target/IFLIGHTF7_TWING/CMakeLists.txt | 2 +- src/main/target/KAKUTEF4/CMakeLists.txt | 4 +- src/main/target/KAKUTEF7/CMakeLists.txt | 6 +- src/main/target/KFC32F3_INAV/CMakeLists.txt | 2 +- src/main/target/LUX_RACE/CMakeLists.txt | 2 +- src/main/target/MAMBAF405US/CMakeLists.txt | 2 +- src/main/target/MAMBAF722/CMakeLists.txt | 2 +- src/main/target/MATEKF405/CMakeLists.txt | 6 +- src/main/target/MATEKF405SE/CMakeLists.txt | 2 +- src/main/target/MATEKF411/CMakeLists.txt | 8 +- src/main/target/MATEKF411SE/CMakeLists.txt | 2 +- src/main/target/MATEKF722/CMakeLists.txt | 4 +- src/main/target/MATEKF722PX/CMakeLists.txt | 2 +- src/main/target/MATEKF722SE/CMakeLists.txt | 4 +- src/main/target/MATEKF765/CMakeLists.txt | 2 +- src/main/target/MOTOLAB/CMakeLists.txt | 2 +- src/main/target/NOX/CMakeLists.txt | 2 +- src/main/target/OMNIBUS/CMakeLists.txt | 2 +- src/main/target/OMNIBUSF4/CMakeLists.txt | 18 +- src/main/target/OMNIBUSF7/CMakeLists.txt | 4 +- src/main/target/OMNIBUSF7NXT/CMakeLists.txt | 2 +- src/main/target/PIKOBLX/CMakeLists.txt | 2 +- src/main/target/PIXRACER/CMakeLists.txt | 2 +- src/main/target/RCEXPLORERF3/CMakeLists.txt | 2 +- src/main/target/REVO/CMakeLists.txt | 2 +- src/main/target/RMDO/CMakeLists.txt | 2 +- src/main/target/SPARKY/CMakeLists.txt | 2 +- src/main/target/SPARKY2/CMakeLists.txt | 2 +- src/main/target/SPEEDYBEEF4/CMakeLists.txt | 6 +- src/main/target/SPRACINGF3/CMakeLists.txt | 2 +- src/main/target/SPRACINGF3EVO/CMakeLists.txt | 4 +- src/main/target/SPRACINGF3MINI/CMakeLists.txt | 2 +- src/main/target/SPRACINGF4EVO/CMakeLists.txt | 2 +- src/main/target/SPRACINGF7DUAL/CMakeLists.txt | 2 +- src/main/target/YUPIF7/CMakeLists.txt | 2 +- src/main/target/ZEEZF7/CMakeLists.txt | 2 +- src/main/target/link/stm32_flash_F427.ld | 0 src/main/target/link/stm32_flash_F7_split.ld | 4 +- src/main/target/link/stm32_flash_f303xc.ld | 30 ++ src/main/target/link/stm32_flash_f405xg.ld | 40 +++ src/main/target/link/stm32_flash_f405xg_bl.ld | 43 +++ .../target/link/stm32_flash_f405xg_for_bl.ld | 42 +++ src/main/target/link/stm32_flash_f411xe.ld | 40 +++ src/main/target/link/stm32_flash_f427xg.ld | 59 ++++ src/main/target/link/stm32_flash_f446xe.ld | 40 +++ src/main/target/link/stm32_flash_f722xe.ld | 48 +++ src/main/target/link/stm32_flash_f722xe_bl.ld | 50 +++ .../target/link/stm32_flash_f722xe_for_bl.ld | 50 +++ src/main/target/link/stm32_flash_f745xg.ld | 48 +++ src/main/target/link/stm32_flash_f745xg_bl.ld | 50 +++ .../target/link/stm32_flash_f745xg_for_bl.ld | 50 +++ 100 files changed, 1144 insertions(+), 284 deletions(-) create mode 100644 cmake/stm32-bootloader.cmake mode change 100755 => 100644 src/main/startup/startup_stm32f427xx.s mode change 100755 => 100644 src/main/target/link/stm32_flash_F427.ld create mode 100644 src/main/target/link/stm32_flash_f303xc.ld create mode 100644 src/main/target/link/stm32_flash_f405xg.ld create mode 100644 src/main/target/link/stm32_flash_f405xg_bl.ld create mode 100644 src/main/target/link/stm32_flash_f405xg_for_bl.ld create mode 100644 src/main/target/link/stm32_flash_f411xe.ld create mode 100644 src/main/target/link/stm32_flash_f427xg.ld create mode 100644 src/main/target/link/stm32_flash_f446xe.ld create mode 100644 src/main/target/link/stm32_flash_f722xe.ld create mode 100644 src/main/target/link/stm32_flash_f722xe_bl.ld create mode 100644 src/main/target/link/stm32_flash_f722xe_for_bl.ld create mode 100644 src/main/target/link/stm32_flash_f745xg.ld create mode 100644 src/main/target/link/stm32_flash_f745xg_bl.ld create mode 100644 src/main/target/link/stm32_flash_f745xg_for_bl.ld diff --git a/CMakeLists.txt b/CMakeLists.txt index 384edba5629..781c0726532 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -11,6 +11,7 @@ set(CMAKE_TOOLCHAIN_FILE "${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}.cmake") if(CMAKE_BUILD_TYPE STREQUAL "Release" OR CMAKE_BUILD_TYPE STREQUAL "RelWithDebInfo") set(IS_RELEASE_BUILD ON) + set(CMAKE_INTERPROCEDURAL_OPTIMIZATION ON) endif() project(INAV VERSION 2.5.0) diff --git a/cmake/arm-none-eabi.cmake b/cmake/arm-none-eabi.cmake index 83cbe322b07..e86cb6a5076 100644 --- a/cmake/arm-none-eabi.cmake +++ b/cmake/arm-none-eabi.cmake @@ -51,17 +51,17 @@ set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS ${CMAKE_CONFIGURATION_TYPES set(arm_none_eabi_debug "-Og -g") # We set -Os or -O2 depending on the MCU family -set(arm_none_eabi_release "-DNDEBUG -flto -fuse-linker-plugin") +set(arm_none_eabi_release "-DNDEBUG") set(arm_none_eabi_relwithdebinfo "-ggdb3 ${arm_none_eabi_release}") -SET(CMAKE_C_FLAGS_DEBUG ${arm_none_eabi_debug} CACHE INTERNAL "c compiler flags debug") -SET(CMAKE_CXX_FLAGS_DEBUG ${arm_none_eabi_debug} CACHE INTERNAL "c++ compiler flags debug") -SET(CMAKE_ASM_FLAGS_DEBUG ${arm_none_eabi_debug} CACHE INTERNAL "asm compiler flags debug") +set(CMAKE_C_FLAGS_DEBUG ${arm_none_eabi_debug} CACHE INTERNAL "c compiler flags debug") +set(CMAKE_CXX_FLAGS_DEBUG ${arm_none_eabi_debug} CACHE INTERNAL "c++ compiler flags debug") +set(CMAKE_ASM_FLAGS_DEBUG ${arm_none_eabi_debug} CACHE INTERNAL "asm compiler flags debug") -SET(CMAKE_C_FLAGS_RELEASE ${arm_none_eabi_release} CACHE INTERNAL "c compiler flags release") -SET(CMAKE_CXX_FLAGS_RELEASE ${arm_none_eabi_release} CACHE INTERNAL "cxx compiler flags release") -SET(CMAKE_ASM_FLAGS_RELEASE ${arm_none_eabi_release} CACHE INTERNAL "asm compiler flags release") +set(CMAKE_C_FLAGS_RELEASE ${arm_none_eabi_release} CACHE INTERNAL "c compiler flags release") +set(CMAKE_CXX_FLAGS_RELEASE ${arm_none_eabi_release} CACHE INTERNAL "cxx compiler flags release") +set(CMAKE_ASM_FLAGS_RELEASE ${arm_none_eabi_release} CACHE INTERNAL "asm compiler flags release") -SET(CMAKE_C_FLAGS_RELWITHDEBINFO ${arm_none_eabi_relwithdebinfo} CACHE INTERNAL "c compiler flags release") -SET(CMAKE_CXX_FLAGS_RELWITHDEBINFO ${arm_none_eabi_relwithdebinfo} CACHE INTERNAL "cxx compiler flags release") -SET(CMAKE_ASM_FLAGS_RELWITHDEBINFO ${arm_none_eabi_relwithdebinfo} CACHE INTERNAL "asm compiler flags release") +set(CMAKE_C_FLAGS_RELWITHDEBINFO ${arm_none_eabi_relwithdebinfo} CACHE INTERNAL "c compiler flags release") +set(CMAKE_CXX_FLAGS_RELWITHDEBINFO ${arm_none_eabi_relwithdebinfo} CACHE INTERNAL "cxx compiler flags release") +set(CMAKE_ASM_FLAGS_RELWITHDEBINFO ${arm_none_eabi_relwithdebinfo} CACHE INTERNAL "asm compiler flags release") diff --git a/cmake/main.cmake b/cmake/main.cmake index ccf39b8514b..b5f43099ed4 100644 --- a/cmake/main.cmake +++ b/cmake/main.cmake @@ -39,23 +39,32 @@ macro(glob_except) # var-name pattern excludes-var exclude_basenames(${ARGV0} ${ARGV2}) endmacro() -function(setup_firmware_target name) - target_compile_options(${name} PRIVATE ${MAIN_COMPILE_OPTIONS}) - target_include_directories(${name} PRIVATE ${MAIN_INCLUDE_DIRS}) - target_compile_definitions(${name} PRIVATE ${MAIN_DEFINITIONS} __TARGET__="${name}" ${name}) - enable_settings(${name}) +function(get_generated_files_dir output target_name) + set(${output} ${CMAKE_CURRENT_BINARY_DIR}/${target_name} PARENT_SCOPE) +endfunction() + +function(setup_executable exe name) + get_generated_files_dir(generated_dir ${name}) + target_compile_options(${exe} PRIVATE ${MAIN_COMPILE_OPTIONS}) + target_include_directories(${exe} PRIVATE ${generated_dir} ${MAIN_INCLUDE_DIRS}) + target_compile_definitions(${exe} PRIVATE ${MAIN_DEFINITIONS} __TARGET__="${name}" ${name}) # XXX: Don't make SETTINGS_GENERATED_C part of the build, # since it's compiled via #include in settings.c. This will # change once we move off PGs - target_sources(${name} PRIVATE "${CMAKE_CURRENT_BINARY_DIR}/${name}/${SETTINGS_GENERATED_H}") - set_target_properties(${name} PROPERTIES + target_sources(${exe} PRIVATE "${CMAKE_CURRENT_BINARY_DIR}/${name}/${SETTINGS_GENERATED_H}") + set_target_properties(${exe} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin" ) +endfunction() + +function(setup_firmware_target exe name) + setup_executable(${exe} ${name}) + enable_settings(${exe} ${name}) get_property(targets GLOBAL PROPERTY VALID_TARGETS) list(APPEND targets ${name}) set_property(GLOBAL PROPERTY VALID_TARGETS "${targets}") - setup_openocd(${name}) - setup_svd(${name}) + setup_openocd(${exe} ${name}) + setup_svd(${exe} ${name}) endfunction() function(exclude_from_all target) diff --git a/cmake/openocd.cmake b/cmake/openocd.cmake index bfb09806159..a43a502c2ad 100644 --- a/cmake/openocd.cmake +++ b/cmake/openocd.cmake @@ -34,13 +34,13 @@ if(OPENOCD_PATH) ) endif() -function(setup_openocd target_name) +function(setup_openocd target_exe target_name) if(OPENOCD_INTERFACE) set(openocd_interface ${OPENOCD_INTERFACE}) else() - get_property(openocd_interface TARGET ${target_name} PROPERTY OPENOCD_DEFAULT_INTERFACE) + get_property(openocd_interface TARGET ${target_exe} PROPERTY OPENOCD_DEFAULT_INTERFACE) endif() - get_property(openocd_target TARGET ${target_name} PROPERTY OPENOCD_TARGET) + get_property(openocd_target TARGET ${target_exe} PROPERTY OPENOCD_TARGET) if(OPENOCD_CFG OR (openocd_target AND openocd_interface)) set(openocd_run_target "openocd_${target_name}") if (OPENOCD_CFG AND NOT OPENOCD_CFG STREQUAL "") @@ -74,10 +74,10 @@ function(setup_openocd target_name) add_custom_target(${openocd_flash_target} ${CMAKE_COMMAND} -E env OPENOCD_CMD=${OPENOCD_PATH} ${MAIN_UTILS_DIR}/openocd_flash.py -f - ${openocd_cfg_path} $ + ${openocd_cfg_path} $ COMMENT "Flashing ${target_name} with openocd" - DEPENDS ${openocd_cfg_path} ${target_name} + DEPENDS ${openocd_cfg_path} ${target_exe} ) exclude_from_all(${openocd_flash_target}) endif() diff --git a/cmake/settings.cmake b/cmake/settings.cmake index 1521fbc8b9a..d3e3db8f3ad 100644 --- a/cmake/settings.cmake +++ b/cmake/settings.cmake @@ -4,13 +4,13 @@ set(SETTINGS_GENERATED_H "${SETTINGS_GENERATED}.h") set(SETTINGS_FILE "${MAIN_SRC_DIR}/fc/settings.yaml") set(SETTINGS_GENERATOR "${MAIN_UTILS_DIR}/settings.rb") -function(enable_settings target) - set(dir "${CMAKE_CURRENT_BINARY_DIR}/${target}") - target_include_directories(${target} PRIVATE ${dir}) - get_target_property(options ${target} COMPILE_OPTIONS) - get_target_property(includes ${target} INCLUDE_DIRECTORIES) + +function(enable_settings exe name) + get_generated_files_dir(dir ${name}) + get_target_property(options ${exe} COMPILE_OPTIONS) + get_target_property(includes ${exe} INCLUDE_DIRECTORIES) list(TRANSFORM includes PREPEND "-I") - get_target_property(defs ${target} COMPILE_DEFINITIONS) + get_target_property(defs ${exe} COMPILE_DEFINITIONS) list(TRANSFORM defs PREPEND "-D") list(APPEND cflags ${options}) list(APPEND cflags ${includes}) @@ -18,7 +18,7 @@ function(enable_settings target) add_custom_command( OUTPUT ${dir}/${SETTINGS_GENERATED_H} ${dir}/${SETTINGS_GENERATED_C} COMMAND - ${CMAKE_COMMAND} -E env CFLAGS="${cflags}" TARGET=${target} + ${CMAKE_COMMAND} -E env CFLAGS="${cflags}" TARGET=${name} ${RUBY_EXECUTABLE} ${SETTINGS_GENERATOR} ${MAIN_DIR} ${SETTINGS_FILE} -o "${dir}" DEPENDS ${SETTINGS_GENERATOR} ${SETTINGS_FILE} ) diff --git a/cmake/stm32-bootloader.cmake b/cmake/stm32-bootloader.cmake new file mode 100644 index 00000000000..3bb13ae1bf8 --- /dev/null +++ b/cmake/stm32-bootloader.cmake @@ -0,0 +1,30 @@ +main_sources(BOOTLOADER_SOURCES + common/log.c + common/log.h + common/printf.c + common/printf.h + common/string_light.c + common/string_light.h + common/typeconversion.c + common/typeconversion.h + + drivers/bus.c + drivers/bus_busdev_i2c.c + drivers/bus_busdev_spi.c + drivers/bus_i2c_soft.c + drivers/io.c + drivers/light_led.c + drivers/persistent.c + drivers/rcc.c + drivers/serial.c + drivers/system.c + drivers/time.c + drivers/timer.c + + fc/firmware_update_common.c + fc/firmware_update_common.h + + target/common_hardware.c +) + +list(APPEND BOOTLOADER_SOURCES ${MAIN_DIR}/src/bl/bl_main.c) diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake index 213f3819d22..46c47f74de9 100644 --- a/cmake/stm32.cmake +++ b/cmake/stm32.cmake @@ -1,4 +1,5 @@ include(arm-none-eabi) +include(stm32-bootloader) include(stm32f3) include(stm32f4) include(stm32f7) @@ -49,7 +50,6 @@ main_sources(STM32_ASYNCFATFS_SRC ) main_sources(STM32_MSC_SRC - msc/usbd_msc_desc.c msc/usbd_storage.c ) @@ -159,90 +159,284 @@ macro(get_stm32_target_features output_var dir target_name) endif() endmacro() -function(target_stm32 name startup ldscript) - set(target_definitions) +function(get_stm32_flash_size out size) + # 4: 16, 6: 32, 8: 64, B: 128, C: 256, D: 384, E: 512, F: 768, G: 1024, H: 1536, I: 2048 KiB + string(TOUPPER ${size} s) + if(${s} STREQUAL "4") + set(${out} 16 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "6") + set(${out} 32 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "8") + set(${out} 64 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "8") + set(${out} 64 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "B") + set(${out} 128 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "C") + set(${out} 256 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "D") + set(${out} 384 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "E") + set(${out} 512 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "F") + set(${out} 768 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "G") + set(${out} 1024 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "H") + set(${out} 1536 PARENT_SCOPE) + return() + endif() + if(${s} STREQUAL "I") + set(${out} 2048 PARENT_SCOPE) + return() + endif() +endfunction() + +function(add_hex_target name exe hex) + add_custom_target(${name} ALL + ${CMAKE_OBJCOPY} -Oihex $ ${hex} + BYPRODUCTS ${hex} + ) +endfunction() + +function(add_bin_target name exe bin) + add_custom_target(${name} ALL + ${CMAKE_OBJCOPY} -Obinary $ ${bin} + BYPRODUCTS ${bin} + ) +endfunction() + +function(generate_map_file target) + target_link_options(${target} PRIVATE "-Wl,-Map,$/$.map") +endfunction() + +function(set_linker_script target script) + set(script_path ${STM32_LINKER_DIR}/${args_LINKER_SCRIPT}.ld) + if(NOT EXISTS ${script_path}) + message(FATAL_ERROR "linker script ${script_path} doesn't exist") + endif() + set_target_properties(${target} PROPERTIES LINK_DEPENDS ${script_path}) + target_link_options(${elf_target} PRIVATE -T${script_path}) +endfunction() + +function(add_stm32_executable) + cmake_parse_arguments( + args + # Boolean arguments + "" + # Single value arguments + "FILENAME;NAME;OPTIMIZATION;OUTPUT_BIN_FILENAME;OUTPUT_HEX_FILENAME;OUTPUT_TARGET_NAME" + # Multi-value arguments + "COMPILE_DEFINITIONS;COMPILE_OPTIONS;INCLUDE_DIRECTORIES;LINK_OPTIONS;LINKER_SCRIPT;SOURCES" + # Start parsing after the known arguments + ${ARGN} + ) + set(elf_target ${args_NAME}.elf) + add_executable(${elf_target}) + set_target_properties(${elf_target} PROPERTIES OUTPUT_NAME ${args_NAME}) + target_sources(${elf_target} PRIVATE ${args_SOURCES}) + target_include_directories(${elf_target} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR} ${args_INCLUDE_DIRECTORIES} ${STM32_INCLUDE_DIRS}) + target_compile_definitions(${elf_target} PRIVATE ${args_COMPILE_DEFINITIONS}) + target_compile_options(${elf_target} PRIVATE ${STM32_COMPILE_OPTIONS} ${args_COMPILE_OPTIONS}) + if(WARNINGS_AS_ERRORS) + target_compile_options(${elf_target} PRIVATE -Werror) + endif() + if (IS_RELEASE_BUILD) + target_compile_options(${elf_target} PRIVATE ${args_OPTIMIZATION}) + target_link_options(${elf_target} PRIVATE ${args_OPTIMIZATION}) + endif() + target_link_libraries(${elf_target} PRIVATE ${STM32_LINK_LIBRARIES}) + target_link_options(${elf_target} PRIVATE ${STM32_LINK_OPTIONS} ${args_LINK_OPTIONS}) + generate_map_file(${elf_target}) + set_linker_script(${elf_target} ${args_LINKER_SCRIPT}) + if(args_FILENAME) + set(basename ${CMAKE_BINARY_DIR}/${args_FILENAME}) + set(hex_filename ${basename}.hex) + add_hex_target(${args_NAME} ${elf_target} ${hex_filename}) + set(bin_filename ${basename}.bin) + add_bin_target(${args_NAME}.bin ${elf_target} ${bin_filename}) + endif() + if(args_OUTPUT_BIN_FILENAME) + set(${args_OUTPUT_BIN_FILENAME} ${bin_filename} PARENT_SCOPE) + endif() + if(args_OUTPUT_TARGET_NAME) + set(${args_OUTPUT_TARGET_NAME} ${elf_target} PARENT_SCOPE) + endif() + if(args_OUTPUT_HEX_FILENAME) + set(${args_OUTPUT_HEX_FILENAME} ${hex_filename} PARENT_SCOPE) + endif() +endfunction() + +function(target_stm32) # Parse keyword arguments cmake_parse_arguments( - PARSED_ARGS - "DISABLE_MSC" # Boolean arguments - "HSE_MHZ;OPENOCD_TARGET;SVD" # Single value arguments - "DEFINITIONS" # Multi-value arguments - ${ARGN} # Start parsing after the known arguments + args + # Boolean arguments + "DISABLE_MSC;BOOTLOADER" + # Single value arguments + "HSE_MHZ;LINKER_SCRIPT;NAME;OPENOCD_TARGET;OPTIMIZATION;STARTUP;SVD" + # Multi-value arguments + "COMPILE_DEFINITIONS;COMPILE_OPTIONS;INCLUDE_DIRECTORIES;LINK_OPTIONS;SOURCES;MSC_SOURCES;MSC_INCLUDE_DIRECTORIES;VCP_SOURCES;VCP_INCLUDE_DIRECTORIES" + # Start parsing after the known arguments + ${ARGN} ) + set(name ${args_NAME}) - if (PARSED_ARGS_HSE_MHZ) - set(hse_mhz ${PARSED_ARGS_HSE_MHZ}) + if (args_HSE_MHZ) + set(hse_mhz ${args_HSE_MHZ}) else() set(hse_mhz ${STM32_DEFAULT_HSE_MHZ}) endif() - # Main .elf target - add_executable(${name}) - target_sources(${name} PRIVATE "${STM32_STARTUP_DIR}/${startup}" ${COMMON_SRC} ${CMSIS_DSP_SRC}) + set(target_sources ${STM32_STARTUP_DIR}/${args_STARTUP}) + list(APPEND target_sources ${args_SOURCES}) file(GLOB target_c_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.c") file(GLOB target_h_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.h") - target_sources(${name} PRIVATE ${target_c_sources} ${target_h_sources}) - target_include_directories(${name} PRIVATE . ${STM32_INCLUDE_DIRS}) - target_compile_options(${name} PRIVATE ${STM32_COMPILE_OPTIONS}) - if(WARNINGS_AS_ERRORS) - target_compile_options(${name} PRIVATE -Werror) - endif() - target_link_libraries(${name} PRIVATE ${STM32_LINK_LIBRARIES}) - target_link_options(${name} PRIVATE ${STM32_LINK_OPTIONS}) - target_link_options(${name} PRIVATE "-T${STM32_LINKER_DIR}/${ldscript}") - target_link_options(${name} PRIVATE "-Wl,-Map,$.map") + list(APPEND target_sources ${target_c_sources} ${target_h_sources}) + + set(target_include_directories ${args_INCLUDE_DIRECTORIES}) set(target_definitions ${STM32_DEFINITIONS}) - math(EXPR hse_value "${hse_mhz} * 1000000") - list(APPEND target_definitions "HSE_VALUE=${hse_value}") - if(PARSED_ARGS_DEFINITIONS) - list(APPEND target_definitions ${PARSED_ARGS_DEFINITIONS}) - endif() - if(DEBUG_HARDFAULTS) - list(APPEND target_definitions DEBUG_HARDFAULTS) - endif() - target_compile_definitions(${name} PRIVATE ${target_definitions}) get_stm32_target_features(features "${CMAKE_CURRENT_SOURCE_DIR}" ${name}) - set_property(TARGET ${name} PROPERTY FEATURES ${features}) + set_property(TARGET ${elf_target} PROPERTY FEATURES ${features}) + if(VCP IN_LIST features) - target_sources(${name} PRIVATE ${STM32_VCP_SRC}) + list(APPEND target_sources ${STM32_VCP_SRC} ${args_VCP_SOURCES}) + list(APPEND target_include_directories ${args_VCP_INCLUDE_DIRECTORIES}) endif() if(SDCARD IN_LIST features) - target_sources(${name} PRIVATE ${STM32_SDCARD_SRC} ${STM32_ASYNCFATFS_SRC}) + list(APPEND target_sources ${STM32_SDCARD_SRC} ${STM32_ASYNCFATFS_SRC}) endif() - if(NOT PARSED_ARGS_DISABLE_MSC AND MSC IN_LIST features) - target_sources(${name} PRIVATE ${STM32_MSC_SRC}) - target_compile_definitions(${name} PRIVATE USE_USB_MSC) - if (FLASHFS IN_LIST features) - target_sources(${name} PRIVATE ${STM32_MSC_FLASH_SRC}) + + set(msc_sources) + if(NOT args_DISABLE_MSC AND MSC IN_LIST features) + list(APPEND target_include_directories ${args_MSC_INCLUDE_DIRECTORIES}) + list(APPEND msc_sources ${STM32_MSC_SRC} ${args_MSC_SOURCES}) + list(APPEND target_definitions USE_USB_MSC) + if(FLASHFS IN_LIST features) + list(APPEND msc_sources ${STM32_MSC_FLASH_SRC}) endif() if (SDCARD IN_LIST features) if (SDIO IN_LIST features) - target_sources(${name} PRIVATE ${STM32_MSC_SDCARD_SDIO_SRC}) + list(APPEND msc_sources ${STM32_MSC_SDCARD_SDIO_SRC}) else() - target_sources(${name} PRIVATE ${STM32_MSC_SDCARD_SPI_SRC}) + list(APPEND msc_sources ${STM32_MSC_SDCARD_SPI_SRC}) endif() endif() endif() - set_property(TARGET ${name} PROPERTY OPENOCD_TARGET ${PARSED_ARGS_OPENOCD_TARGET}) - set_property(TARGET ${name} PROPERTY OPENOCD_DEFAULT_INTERFACE stlink) - set_property(TARGET ${name} PROPERTY SVD ${PARSED_ARGS_SVD}) - # Generate .hex - # XXX: Generator expressions are not supported for add_custom_command() - # OUTPUT nor BYPRODUCTS, so we can't rely of them. Instead, build the filename - # for the .hex from the target name - set(hexdir "${CMAKE_BINARY_DIR}/hex") - set(hex "${hexdir}/${PROJECT_NAME}_${name}_${FIRMWARE_VERSION}.hex") - add_custom_command(TARGET ${name} POST_BUILD - COMMAND ${CMAKE_COMMAND} -E make_directory ${hexdir} - COMMAND ${CMAKE_OBJCOPY} -Oihex $ ${hex} - BYPRODUCTS ${hex} + + math(EXPR hse_value "${hse_mhz} * 1000000") + list(APPEND target_definitions "HSE_VALUE=${hse_value}") + if(args_COMPILE_DEFINITIONS) + list(APPEND target_definitions ${args_COMPILE_DEFINITIONS}) + endif() + if(DEBUG_HARDFAULTS) + list(APPEND target_definitions DEBUG_HARDFAULTS) + endif() + + string(TOLOWER ${PROJECT_NAME} lowercase_project_name) + set(binary_name ${lowercase_project_name}_${FIRMWARE_VERSION}_${name}) + + # Main firmware + add_stm32_executable( + NAME ${name} + FILENAME ${binary_name} + SOURCES ${target_sources} ${msc_sources} ${CMSIS_DSP_SRC} ${COMMON_SRC} + COMPILE_DEFINITIONS ${target_definitions} + COMPILE_OPTIONS ${args_COMPILE_OPTIONS} + INCLUDE_DIRECTORIES ${target_include_directories} + LINK_OPTIONS ${args_LINK_OPTIONS} + LINKER_SCRIPT ${args_LINKER_SCRIPT} + OPTIMIZATION ${args_OPTIMIZATION} + + OUTPUT_HEX_FILENAME main_hex_filename + OUTPUT_TARGET_NAME main_target_name ) + + set_property(TARGET ${main_target_name} PROPERTY OPENOCD_TARGET ${args_OPENOCD_TARGET}) + set_property(TARGET ${main_target_name} PROPERTY OPENOCD_DEFAULT_INTERFACE stlink) + set_property(TARGET ${main_target_name} PROPERTY SVD ${args_SVD}) + + setup_firmware_target(${main_target_name} ${name}) + + if(args_BOOTLOADER) + # Bootloader for the target + set(bl_suffix _bl) + add_stm32_executable( + NAME ${name}${bl_suffix} + FILENAME ${binary_name}${bl_suffix} + SOURCES ${target_sources} ${BOOTLOADER_SOURCES} + COMPILE_DEFINITIONS ${target_definitions} BOOTLOADER MSP_FIRMWARE_UPDATE + COMPILE_OPTIONS ${args_COMPILE_OPTIONS} + INCLUDE_DIRECTORIES ${target_include_directories} + LINK_OPTIONS ${args_LINK_OPTIONS} + LINKER_SCRIPT ${args_LINKER_SCRIPT}${bl_suffix} + OPTIMIZATION ${args_OPTIMIZATION} + + OUTPUT_BIN_FILENAME bl_bin_filename + OUTPUT_HEX_FILENAME bl_hex_filename + OUTPUT_TARGET_NAME bl_target_name + ) + setup_executable(${bl_target_name} ${name}) + + # Main firmware, but for running with the bootloader + set(for_bl_suffix _for_bl) + add_stm32_executable( + NAME ${name}${for_bl_suffix} + FILENAME ${binary_name}${for_bl_suffix} + SOURCES ${target_sources} ${msc_sources} ${CMSIS_DSP_SRC} ${COMMON_SRC} + COMPILE_DEFINITIONS ${target_definitions} MSP_FIRMWARE_UPDATE + COMPILE_OPTIONS ${args_COMPILE_OPTIONS} + INCLUDE_DIRECTORIES ${target_include_directories} + LINK_OPTIONS ${args_LINK_OPTIONS} + LINKER_SCRIPT ${args_LINKER_SCRIPT}${for_bl_suffix} + OPTIMIZATION ${args_OPTIMIZATION} + + OUTPUT_BIN_FILENAME for_bl_bin_filename + OUTPUT_HEX_FILENAME for_bl_hex_filename + OUTPUT_TARGET_NAME for_bl_target_name + ) + setup_executable(${for_bl_target_name} ${name}) + + # Combined with bootloader and main firmware + set(with_bl_suffix _with_bl) + set(combined_hex ${CMAKE_BINARY_DIR}/${binary_name}${with_bl_suffix}.hex) + add_custom_target(${name}${with_bl_suffix} + ${CMAKE_SOURCE_DIR}/src/utils/combine_tool ${bl_bin_filename} ${for_bl_bin_filename} ${combined_hex} + DEPENDS ${bl_bin_filename} ${for_bl_bin_filename} + BYPRODUCTS ${combined_hex} + ) + endif() + # clean_ set(clean_target "clean_${name}") add_custom_target(${clean_target} - COMMAND cmake -E rm -r "${CMAKE_CURRENT_BINARY_DIR}" + WORKING_DIRECTORY ${CMAKE_BINARY_DIR} + COMMAND ${CMAKE_COMMAND} -E rm -r "${CMAKE_CURRENT_BINARY_DIR}" + COMMAND ${CMAKE_COMMAND} -E rm ${main_hex_filename} + COMMAND ${CMAKE_COMMAND} -E rm ${bl_hex_filename} + COMMAND ${CMAKE_COMMAND} -E rm ${main_hex_filename} COMMENT "Removing intermediate files for ${name}") set_property(TARGET ${clean_target} PROPERTY TARGET_MESSAGES OFF diff --git a/cmake/stm32f3.cmake b/cmake/stm32f3.cmake index 39279fa6227..0e4dc764e38 100644 --- a/cmake/stm32f3.cmake +++ b/cmake/stm32f3.cmake @@ -52,35 +52,41 @@ set(STM32F3_DEFINITIONS USE_STDPERIPH_DRIVER ) -set(STM32F303_DEFINITIONS +set(STM32F303CC_DEFINITIONS STM32F303 STM32F303xC FLASH_SIZE=256 ) -function(target_stm32f3xx name startup ldscript) - # F3 targets don't support MSC - target_stm32(${name} ${startup} ${ldscript} DISABLE_MSC OPENOCD_TARGET stm32f3x ${ARGN}) - # F3 targets don't use -O2 to save size - if (IS_RELEASE_BUILD) - target_compile_options(${name} PRIVATE "-Os") - target_link_options(${name} PRIVATE "-Os") - endif() - target_sources(${name} PRIVATE ${STM32_STDPERIPH_SRC} ${STM32F3_STDPERIPH_SRC} ${STM32F3_SRC}) - target_compile_options(${name} PRIVATE ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_COMPILE_OPTIONS}) - target_include_directories(${name} PRIVATE ${STM32F3_INCLUDE_DIRS}) - target_compile_definitions(${name} PRIVATE ${STM32F3_DEFINITIONS}) - target_link_options(${name} PRIVATE ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_LINK_OPTIONS}) +function(target_stm32f3xx) + # F3 targets don't support MSC and use -Os instead of -O2 to save size + target_stm32( + SOURCES ${STM32_STDPERIPH_SRC} ${STM32F3_STDPERIPH_SRC} ${STM32F3_SRC} + COMPILE_DEFINITIONS ${STM32F3_DEFINITIONS} + COMPILE_OPTIONS ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_COMPILE_OPTIONS} + INCLUDE_DIRECTORIES ${STM32F3_INCLUDE_DIRS} + LINK_OPTIONS ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_LINK_OPTIONS} - get_property(features TARGET ${name} PROPERTY FEATURES) - if(VCP IN_LIST features) - target_include_directories(${name} PRIVATE ${STM32F3_USB_INCLUDE_DIRS}) - target_sources(${name} PRIVATE ${STM32F3_USB_SRC} ${STM32F3_VCP_SRC}) - endif() + VCP_SOURCES ${STM32F3_USB_SRC} ${STM32F3_VCP_SRC} + VCP_INCLUDE_DIRECTORIES ${STM32F3_USB_INCLUDE_DIRS} + + DISABLE_MSC + + OPTIMIZATION -Os + + OPENOCD_TARGET stm32f3x + + ${ARGN} + ) endfunction() -function(target_stm32f303 name) - target_stm32f3xx(${name} startup_stm32f30x_md_gcc.S stm32_flash_f303_256k.ld SVD STM32F303 ${ARGN}) - target_compile_definitions(${name} PRIVATE ${STM32F303_DEFINITIONS}) - setup_firmware_target(${name}) +function(target_stm32f303xc name) + target_stm32f3xx( + NAME ${name} + STARTUP startup_stm32f30x_md_gcc.S + COMPILE_DEFINITIONS ${STM32F303CC_DEFINITIONS} + LINKER_SCRIPT stm32_flash_f303xc + SVD STM32F303 + ${ARGN} + ) endfunction() diff --git a/cmake/stm32f4-usb.cmake b/cmake/stm32f4-usb.cmake index 177d5322df7..8c30f0e554c 100644 --- a/cmake/stm32f4-usb.cmake +++ b/cmake/stm32f4-usb.cmake @@ -46,7 +46,11 @@ set(STM32F4_USBMSC_SRC usbd_msc_data.c usbd_msc_scsi.c ) +main_sources(STM32F4_MSC_SRC + msc/usbd_msc_desc.c +) list(TRANSFORM STM32F4_USBMSC_SRC PREPEND "${STM32_USBMSC_DIR}/src/") +list(APPEND STM32F4_USBMSC_SRC ${STM32F4_MSC_SRC}) list(APPEND STM32F4_USB_SRC ${STM32_USBOTG_SRC}) list(APPEND STM32F4_USB_SRC ${STM32_USBCORE_SRC}) diff --git a/cmake/stm32f4.cmake b/cmake/stm32f4.cmake index ba6ab602dd4..8beb83e4de2 100644 --- a/cmake/stm32f4.cmake +++ b/cmake/stm32f4.cmake @@ -75,26 +75,24 @@ set(STM32F4_DEFINITIONS USE_STDPERIPH_DRIVER ) -function(target_stm32f4xx name startup ldscript) - target_stm32(${name} ${startup} ${ldscript} OPENOCD_TARGET stm32f4x ${ARGN}) - if (IS_RELEASE_BUILD) - target_compile_options(${name} PRIVATE "-O2") - target_link_options(${name} PRIVATE "-O2") - endif() - target_sources(${name} PRIVATE ${STM32_STDPERIPH_SRC} ${STM32F4_SRC}) - target_compile_options(${name} PRIVATE ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_COMPILE_OPTIONS}) - target_include_directories(${name} PRIVATE ${STM32F4_INCLUDE_DIRS}) - target_compile_definitions(${name} PRIVATE ${STM32F4_DEFINITIONS}) - target_link_options(${name} PRIVATE ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_LINK_OPTIONS}) - - get_property(features TARGET ${name} PROPERTY FEATURES) - if(VCP IN_LIST features) - target_include_directories(${name} PRIVATE ${STM32F4_USB_INCLUDE_DIRS}) - target_sources(${name} PRIVATE ${STM32F4_USB_SRC} ${STM32F4_VCP_SRC}) - endif() - if(MSC IN_LIST features) - target_sources(${name} PRIVATE ${STM32F4_USBMSC_SRC} ${STM32F4_MSC_SRC}) - endif() +function(target_stm32f4xx) + target_stm32( + SOURCES ${STM32_STDPERIPH_SRC} ${STM32F4_SRC} + COMPILE_DEFINITIONS ${STM32F4_DEFINITIONS} + COMPILE_OPTIONS ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_COMPILE_OPTIONS} + INCLUDE_DIRECTORIES ${STM32F4_INCLUDE_DIRS} + LINK_OPTIONS ${CORTEX_M4F_COMMON_OPTIONS} ${CORTEX_M4F_LINK_OPTIONS} + + MSC_SOURCES ${STM32F4_USBMSC_SRC} ${STM32F4_MSC_SRC} + VCP_SOURCES ${STM32F4_USB_SRC} ${STM32F4_VCP_SRC} + VCP_INCLUDE_DIRECTORIES ${STM32F4_USB_INCLUDE_DIRS} + + OPTIMIZATION -O2 + + OPENOCD_TARGET stm32f4x + + ${ARGN} + ) endfunction() set(STM32F405_COMPILE_DEFINITIONS @@ -103,11 +101,17 @@ set(STM32F405_COMPILE_DEFINITIONS FLASH_SIZE=1024 ) -function(target_stm32f405 name) - target_stm32f4xx(${name} startup_stm32f40xx.s stm32_flash_f405.ld SVD STM32F405 ${ARGN}) - target_sources(${name} PRIVATE ${STM32F4_STDPERIPH_SRC}) - target_compile_definitions(${name} PRIVATE ${STM32F405_COMPILE_DEFINITIONS}) - setup_firmware_target(${name}) +function(target_stm32f405xg name) + target_stm32f4xx( + NAME ${name} + STARTUP startup_stm32f40xx.s + SOURCES ${STM32F4_STDPERIPH_SRC} + COMPILE_DEFINITIONS ${STM32F405_COMPILE_DEFINITIONS} + LINKER_SCRIPT stm32_flash_f405xg + SVD STM32F405 + BOOTLOADER + ${ARGN} + ) endfunction() set(STM32F411_OR_F427_STDPERIPH_SRC ${STM32F4_STDPERIPH_SRC}) @@ -119,20 +123,30 @@ set(STM32F411_COMPILE_DEFINITIONS FLASH_SIZE=512 ) -function(target_stm32f411 name) - target_stm32f4xx(${name} startup_stm32f411xe.s stm32_flash_f411.ld SVD STM32F411 ${ARGN}) - target_sources(${name} PRIVATE ${STM32F411_OR_F427_STDPERIPH_SRC}) - target_compile_definitions(${name} PRIVATE ${STM32F411_COMPILE_DEFINITIONS}) - setup_firmware_target(${name}) +function(target_stm32f411xe name) + target_stm32f4xx( + NAME ${name} + STARTUP startup_stm32f411xe.s + SOURCES ${STM32F411_OR_F427_STDPERIPH_SRC} + COMPILE_DEFINITIONS ${STM32F411_COMPILE_DEFINITIONS} + LINKER_SCRIPT stm32_flash_f411xe + SVD STM32F411 + ${ARGN} + ) endfunction() set(STM32F427_COMPILE_DEFINITIONS STM32F427_437xx FLASH_SIZE=1024 ) -function(target_stm32f427 name) - target_stm32f4xx(${name} startup_stm32f427xx.s stm32_flash_f427.ld SVD STM32F427 ${ARGN}) - target_sources(${name} PRIVATE ${STM32F411_OR_F427_STDPERIPH_SRC}) - target_compile_definitions(${name} PRIVATE ${STM32F427_COMPILE_DEFINITIONS}) - setup_firmware_target(${name}) +function(target_stm32f427xg name) + target_stm32f4xx( + NAME ${name} + STARTUP startup_stm32f427xx.s + SOURCES ${STM32F411_OR_F427_STDPERIPH_SRC} + COMPILE_DEFINITIONS ${STM32F427_COMPILE_DEFINITIONS} + LINKER_SCRIPT stm32_flash_f427xg + SVD STM32F411 + ${ARGN} + ) endfunction() diff --git a/cmake/stm32f7.cmake b/cmake/stm32f7.cmake index a452eaff362..1ce5d8c459e 100644 --- a/cmake/stm32f7.cmake +++ b/cmake/stm32f7.cmake @@ -82,42 +82,50 @@ set(STM32F7_DEFINITIONS USE_FULL_LL_DRIVER ) -function(target_stm32f7xx name startup ldscript) - target_stm32(${name} ${startup} ${ldscript} OPENOCD_TARGET stm32f7x ${ARGN}) - if (IS_RELEASE_BUILD) - target_compile_options(${name} PRIVATE "-O2") - target_link_options(${name} PRIVATE "-O2") - endif() - target_sources(${name} PRIVATE ${STM32F7_HAL_SRC} ${STM32F7_SRC}) - target_compile_options(${name} PRIVATE ${CORTEX_M7_COMMON_OPTIONS} ${CORTEX_M7_COMPILE_OPTIONS}) - target_include_directories(${name} PRIVATE ${STM32F7_INCLUDE_DIRS}) - target_compile_definitions(${name} PRIVATE ${STM32F7_DEFINITIONS}) - target_link_options(${name} PRIVATE ${CORTEX_M7_COMMON_OPTIONS} ${CORTEX_M7_LINK_OPTIONS}) - - get_property(features TARGET ${name} PROPERTY FEATURES) - if(VCP IN_LIST features) - target_include_directories(${name} PRIVATE ${STM32F7_USB_INCLUDE_DIRS} ${STM32F7_VCP_DIR}) - target_sources(${name} PRIVATE ${STM32F7_USB_SRC} ${STM32F7_VCP_SRC}) - endif() - if(MSC IN_LIST features) - target_sources(${name} PRIVATE ${STM32F7_USBMSC_SRC} ${STM32F7_MSC_SRC}) - endif() +function(target_stm32f7xx) + target_stm32( + SOURCES ${STM32F7_HAL_SRC} ${STM32F7_SRC} + COMPILE_DEFINITIONS ${STM32F7_DEFINITIONS} + COMPILE_OPTIONS ${CORTEX_M7_COMMON_OPTIONS} ${CORTEX_M7_COMPILE_OPTIONS} + INCLUDE_DIRECTORIES ${STM32F7_INCLUDE_DIRS} + LINK_OPTIONS ${CORTEX_M7_COMMON_OPTIONS} ${CORTEX_M7_LINK_OPTIONS} + + MSC_SOURCES ${STM32F7_USBMSC_SRC} ${STM32F7_MSC_SRC} + VCP_SOURCES ${STM32F7_USB_SRC} ${STM32F7_VCP_SRC} + VCP_INCLUDE_DIRECTORIES ${STM32F7_USB_INCLUDE_DIRS} ${STM32F7_VCP_DIR} + + OPTIMIZATION -O2 + + OPENOCD_TARGET stm32f7x + + BOOTLOADER + + ${ARGN} + ) endfunction() -macro(define_target_stm32f7 suffix flash_size) - function(target_stm32f7${suffix} name) - target_stm32f7xx(${name} startup_stm32f7${suffix}xx.s stm32_flash_f7${suffix}.ld ${ARGN}) +macro(define_target_stm32f7 subfamily size) + function(target_stm32f7${subfamily}x${size} name) + string(TOUPPER ${size} upper_size) + get_stm32_flash_size(flash_size ${size}) set(definitions STM32F7 - STM32F7${suffix}xx + STM32F7${subfamily}xx + STM32F7${subfamily}x${upper_size} FLASH_SIZE=${flash_size} ) - target_compile_definitions(${name} PRIVATE ${definitions}) - setup_firmware_target(${name}) + target_stm32f7xx( + NAME ${name} + STARTUP startup_stm32f7${subfamily}xx.s + COMPILE_DEFINITIONS ${definitions} + LINKER_SCRIPT stm32_flash_f7${subfamily}x${size} + ${ARGN} + ) endfunction() endmacro() -define_target_stm32f7("22" 512) -define_target_stm32f7("45" 2048) -define_target_stm32f7("46" 2048) -define_target_stm32f7("65" 2048) \ No newline at end of file +define_target_stm32f7(22 e) +define_target_stm32f7(45 g) +define_target_stm32f7(46 g) +define_target_stm32f7(65 g) +define_target_stm32f7(65 i) \ No newline at end of file diff --git a/cmake/svd.cmake b/cmake/svd.cmake index 06be82c394c..d6efdc783b6 100644 --- a/cmake/svd.cmake +++ b/cmake/svd.cmake @@ -1,5 +1,5 @@ -function(setup_svd target_name) - get_property(svd_name TARGET ${target_name} PROPERTY SVD) +function(setup_svd target_exe target_name) + get_property(svd_name TARGET ${target_exe} PROPERTY SVD) set(svd_target_name "svd_${target_name}") if (svd_name AND NOT svd_name STREQUAL "") add_custom_target(${svd_target_name} diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index d9c4123055c..77dfc54c20f 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -273,6 +273,10 @@ main_sources(COMMON_SRC fc/fc_msp.h fc/fc_msp_box.c fc/fc_msp_box.h + fc/firmware_update.c + fc/firmware_update.h + fc/firmware_update_common.c + fc/firmware_update_common.h fc/rc_smoothing.c fc/rc_smoothing.h fc/rc_adjustments.c diff --git a/src/main/startup/startup_stm32f427xx.s b/src/main/startup/startup_stm32f427xx.s old mode 100755 new mode 100644 diff --git a/src/main/target/AIKONF4/CMakeLists.txt b/src/main/target/AIKONF4/CMakeLists.txt index 483f54efbbc..4f415fd1af9 100644 --- a/src/main/target/AIKONF4/CMakeLists.txt +++ b/src/main/target/AIKONF4/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405(AIKONF4) +target_stm32f405xg(AIKONF4) diff --git a/src/main/target/AIRBOTF4/CMakeLists.txt b/src/main/target/AIRBOTF4/CMakeLists.txt index b86030b6e8f..5d69f7a6aad 100644 --- a/src/main/target/AIRBOTF4/CMakeLists.txt +++ b/src/main/target/AIRBOTF4/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405(AIRBOTF4) +target_stm32f405xg(AIRBOTF4) diff --git a/src/main/target/AIRBOTF7/CMakeLists.txt b/src/main/target/AIRBOTF7/CMakeLists.txt index 17d2773f098..1915ffc91c8 100644 --- a/src/main/target/AIRBOTF7/CMakeLists.txt +++ b/src/main/target/AIRBOTF7/CMakeLists.txt @@ -1,2 +1,2 @@ -target_stm32f722(AIRBOTF7) -target_stm32f722(OMNIBUSF7NANOV7) \ No newline at end of file +target_stm32f722xe(AIRBOTF7) +target_stm32f722xe(OMNIBUSF7NANOV7) diff --git a/src/main/target/AIRHEROF3/CMakeLists.txt b/src/main/target/AIRHEROF3/CMakeLists.txt index f18202b6487..35634a62bd1 100644 --- a/src/main/target/AIRHEROF3/CMakeLists.txt +++ b/src/main/target/AIRHEROF3/CMakeLists.txt @@ -1,2 +1,2 @@ -target_stm32f303(AIRHEROF3 HSE_MHZ 12) -target_stm32f303(AIRHEROF3_QUAD HSE_MHZ 12) \ No newline at end of file +target_stm32f303xc(AIRHEROF3 HSE_MHZ 12) +target_stm32f303xc(AIRHEROF3_QUAD HSE_MHZ 12) diff --git a/src/main/target/ALIENFLIGHTNGF7/CMakeLists.txt b/src/main/target/ALIENFLIGHTNGF7/CMakeLists.txt index 8ad2eb2cca0..16288f4b846 100644 --- a/src/main/target/ALIENFLIGHTNGF7/CMakeLists.txt +++ b/src/main/target/ALIENFLIGHTNGF7/CMakeLists.txt @@ -1 +1 @@ -target_stm32f722(ALIENFLIGHTNGF7) \ No newline at end of file +target_stm32f722xe(ALIENFLIGHTNGF7) diff --git a/src/main/target/ANYFC/CMakeLists.txt b/src/main/target/ANYFC/CMakeLists.txt index 88ab8c97f75..4a04e0f69b4 100644 --- a/src/main/target/ANYFC/CMakeLists.txt +++ b/src/main/target/ANYFC/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405(ANYFC) \ No newline at end of file +target_stm32f405xg(ANYFC) diff --git a/src/main/target/ANYFCF7/CMakeLists.txt b/src/main/target/ANYFCF7/CMakeLists.txt index 28cd0006c85..8b9a150c9e6 100644 --- a/src/main/target/ANYFCF7/CMakeLists.txt +++ b/src/main/target/ANYFCF7/CMakeLists.txt @@ -1,2 +1,2 @@ -target_stm32f745(ANYFCF7) -target_stm32f745(ANYFCF7_EXTERNAL_BARO) \ No newline at end of file +target_stm32f745xg(ANYFCF7) +target_stm32f745xg(ANYFCF7_EXTERNAL_BARO) diff --git a/src/main/target/ASGARD32F4/CMakeLists.txt b/src/main/target/ASGARD32F4/CMakeLists.txt index ec7bd4458e8..4a2d3bbed25 100644 --- a/src/main/target/ASGARD32F4/CMakeLists.txt +++ b/src/main/target/ASGARD32F4/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405(ASGARD32F4) +target_stm32f405xg(ASGARD32F4) diff --git a/src/main/target/ASGARD32F7/CMakeLists.txt b/src/main/target/ASGARD32F7/CMakeLists.txt index 1a219728094..711c638e7e1 100644 --- a/src/main/target/ASGARD32F7/CMakeLists.txt +++ b/src/main/target/ASGARD32F7/CMakeLists.txt @@ -1 +1 @@ -target_stm32f722(ASGARD32F7) \ No newline at end of file +target_stm32f722xe(ASGARD32F7) \ No newline at end of file diff --git a/src/main/target/BEEROTORF4/CMakeLists.txt b/src/main/target/BEEROTORF4/CMakeLists.txt index a30103b89dd..295e6369de5 100644 --- a/src/main/target/BEEROTORF4/CMakeLists.txt +++ b/src/main/target/BEEROTORF4/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405(BEEROTORF4) +target_stm32f405xg(BEEROTORF4) diff --git a/src/main/target/BETAFLIGHTF3/CMakeLists.txt b/src/main/target/BETAFLIGHTF3/CMakeLists.txt index 728fff1e743..e27e7e5e7ac 100644 --- a/src/main/target/BETAFLIGHTF3/CMakeLists.txt +++ b/src/main/target/BETAFLIGHTF3/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303(BETAFLIGHTF3 DEFINITIONS "SPRACINGF3") \ No newline at end of file +target_stm32f303xc(BETAFLIGHTF3 COMPILE_DEFINITIONS "SPRACINGF3") diff --git a/src/main/target/BETAFLIGHTF4/CMakeLists.txt b/src/main/target/BETAFLIGHTF4/CMakeLists.txt index 0160a3c7efd..a76bd04734d 100644 --- a/src/main/target/BETAFLIGHTF4/CMakeLists.txt +++ b/src/main/target/BETAFLIGHTF4/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405(BETAFLIGHTF4) +target_stm32f405xg(BETAFLIGHTF4) diff --git a/src/main/target/BLUEJAYF4/CMakeLists.txt b/src/main/target/BLUEJAYF4/CMakeLists.txt index ba93ee7b423..2c93878cffb 100644 --- a/src/main/target/BLUEJAYF4/CMakeLists.txt +++ b/src/main/target/BLUEJAYF4/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405(BLUEJAYF4) +target_stm32f405xg(BLUEJAYF4) diff --git a/src/main/target/CLRACINGF4AIR/CMakeLists.txt b/src/main/target/CLRACINGF4AIR/CMakeLists.txt index b2566244c30..3b4ceb65adb 100644 --- a/src/main/target/CLRACINGF4AIR/CMakeLists.txt +++ b/src/main/target/CLRACINGF4AIR/CMakeLists.txt @@ -1,3 +1,3 @@ -target_stm32f405(CLRACINGF4AIR) -target_stm32f405(CLRACINGF4AIRV2) -target_stm32f405(CLRACINGF4AIRV3) +target_stm32f405xg(CLRACINGF4AIR) +target_stm32f405xg(CLRACINGF4AIRV2) +target_stm32f405xg(CLRACINGF4AIRV3) diff --git a/src/main/target/COLIBRI/CMakeLists.txt b/src/main/target/COLIBRI/CMakeLists.txt index 355c8d3e025..e8568b8281b 100644 --- a/src/main/target/COLIBRI/CMakeLists.txt +++ b/src/main/target/COLIBRI/CMakeLists.txt @@ -1,2 +1,2 @@ -target_stm32f405(COLIBRI HSE_MHZ 16) -target_stm32f405(QUANTON HSE_MHZ 16) +target_stm32f405xg(COLIBRI HSE_MHZ 16) +target_stm32f405xg(QUANTON HSE_MHZ 16) diff --git a/src/main/target/DALRCF405/CMakeLists.txt b/src/main/target/DALRCF405/CMakeLists.txt index 43f7c6c669d..d3de7d6f883 100644 --- a/src/main/target/DALRCF405/CMakeLists.txt +++ b/src/main/target/DALRCF405/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405(DALRCF405) +target_stm32f405xg(DALRCF405) diff --git a/src/main/target/DALRCF722DUAL/CMakeLists.txt b/src/main/target/DALRCF722DUAL/CMakeLists.txt index ea04ea8ea6f..3e9fe9a4f09 100644 --- a/src/main/target/DALRCF722DUAL/CMakeLists.txt +++ b/src/main/target/DALRCF722DUAL/CMakeLists.txt @@ -1 +1 @@ -target_stm32f722(DALRCF722DUAL) \ No newline at end of file +target_stm32f722xe(DALRCF722DUAL) diff --git a/src/main/target/F4BY/CMakeLists.txt b/src/main/target/F4BY/CMakeLists.txt index 532ae1bfd40..09b695702b7 100644 --- a/src/main/target/F4BY/CMakeLists.txt +++ b/src/main/target/F4BY/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405(F4BY) +target_stm32f405xg(F4BY) diff --git a/src/main/target/FALCORE/CMakeLists.txt b/src/main/target/FALCORE/CMakeLists.txt index f792193dd66..fb2436238ed 100644 --- a/src/main/target/FALCORE/CMakeLists.txt +++ b/src/main/target/FALCORE/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303(FALCORE HSE_MHZ 12) \ No newline at end of file +target_stm32f303xc(FALCORE HSE_MHZ 12) diff --git a/src/main/target/FF_F35_LIGHTNING/CMakeLists.txt b/src/main/target/FF_F35_LIGHTNING/CMakeLists.txt index d575693d719..15380146f56 100644 --- a/src/main/target/FF_F35_LIGHTNING/CMakeLists.txt +++ b/src/main/target/FF_F35_LIGHTNING/CMakeLists.txt @@ -1,2 +1,2 @@ -target_stm32f405(FF_F35_LIGHTNING) -target_stm32f405(WINGFC) +target_stm32f405xg(FF_F35_LIGHTNING) +target_stm32f405xg(WINGFC) diff --git a/src/main/target/FF_FORTINIF4/CMakeLists.txt b/src/main/target/FF_FORTINIF4/CMakeLists.txt index 51eb0287a89..a78703f69cf 100644 --- a/src/main/target/FF_FORTINIF4/CMakeLists.txt +++ b/src/main/target/FF_FORTINIF4/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405(FF_FORTINIF4) +target_stm32f405xg(FF_FORTINIF4) diff --git a/src/main/target/FF_PIKOF4/CMakeLists.txt b/src/main/target/FF_PIKOF4/CMakeLists.txt index d439ef8febe..9a1c349de1c 100644 --- a/src/main/target/FF_PIKOF4/CMakeLists.txt +++ b/src/main/target/FF_PIKOF4/CMakeLists.txt @@ -1,2 +1,2 @@ -target_stm32f405(FF_PIKOF4) -target_stm32f405(FF_PIKOF4OSD) +target_stm32f405xg(FF_PIKOF4) +target_stm32f405xg(FF_PIKOF4OSD) diff --git a/src/main/target/FIREWORKSV2/CMakeLists.txt b/src/main/target/FIREWORKSV2/CMakeLists.txt index 8ed374297ff..c057816a90a 100644 --- a/src/main/target/FIREWORKSV2/CMakeLists.txt +++ b/src/main/target/FIREWORKSV2/CMakeLists.txt @@ -1,2 +1,2 @@ -target_stm32f405(FIREWORKSV2) -target_stm32f405(OMNIBUSF4V6) +target_stm32f405xg(FIREWORKSV2) +target_stm32f405xg(OMNIBUSF4V6) diff --git a/src/main/target/FISHDRONEF4/CMakeLists.txt b/src/main/target/FISHDRONEF4/CMakeLists.txt index 468386fc689..1f431194d7d 100644 --- a/src/main/target/FISHDRONEF4/CMakeLists.txt +++ b/src/main/target/FISHDRONEF4/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405(FISHDRONEF4) +target_stm32f405xg(FISHDRONEF4) diff --git a/src/main/target/FLYWOOF411/CMakeLists.txt b/src/main/target/FLYWOOF411/CMakeLists.txt index ef56491f3b5..ca3e384913b 100644 --- a/src/main/target/FLYWOOF411/CMakeLists.txt +++ b/src/main/target/FLYWOOF411/CMakeLists.txt @@ -1 +1 @@ -target_stm32f411(FLYWOOF411) +target_stm32f411xe(FLYWOOF411) diff --git a/src/main/target/FLYWOOF7DUAL/CMakeLists.txt b/src/main/target/FLYWOOF7DUAL/CMakeLists.txt index 00373c55d39..7db7e352474 100644 --- a/src/main/target/FLYWOOF7DUAL/CMakeLists.txt +++ b/src/main/target/FLYWOOF7DUAL/CMakeLists.txt @@ -1 +1 @@ -target_stm32f722(FLYWOOF7DUAL) \ No newline at end of file +target_stm32f722xe(FLYWOOF7DUAL) diff --git a/src/main/target/FOXEERF405/CMakeLists.txt b/src/main/target/FOXEERF405/CMakeLists.txt index e9136cf0f4e..f6337a96ee6 100644 --- a/src/main/target/FOXEERF405/CMakeLists.txt +++ b/src/main/target/FOXEERF405/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405(FOXEERF405) +target_stm32f405xg(FOXEERF405) diff --git a/src/main/target/FOXEERF722DUAL/CMakeLists.txt b/src/main/target/FOXEERF722DUAL/CMakeLists.txt index 560189ff1ba..9af4d4ef095 100644 --- a/src/main/target/FOXEERF722DUAL/CMakeLists.txt +++ b/src/main/target/FOXEERF722DUAL/CMakeLists.txt @@ -1,2 +1,2 @@ -target_stm32f722(FOXEERF722DUAL) -target_stm32f722(FOXEERF722V2) \ No newline at end of file +target_stm32f722xe(FOXEERF722DUAL) +target_stm32f722xe(FOXEERF722V2) diff --git a/src/main/target/FRSKYF3/CMakeLists.txt b/src/main/target/FRSKYF3/CMakeLists.txt index ebd8e1a8b39..0ce40486850 100644 --- a/src/main/target/FRSKYF3/CMakeLists.txt +++ b/src/main/target/FRSKYF3/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303(FRSKYF3) \ No newline at end of file +target_stm32f303xc(FRSKYF3) diff --git a/src/main/target/FRSKYF4/CMakeLists.txt b/src/main/target/FRSKYF4/CMakeLists.txt index cb13fbed3ce..ef64ff2ded6 100644 --- a/src/main/target/FRSKYF4/CMakeLists.txt +++ b/src/main/target/FRSKYF4/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405(FRSKYF4) +target_stm32f405xg(FRSKYF4) diff --git a/src/main/target/FURYF3/CMakeLists.txt b/src/main/target/FURYF3/CMakeLists.txt index ed0e4238930..d4d60d306c2 100644 --- a/src/main/target/FURYF3/CMakeLists.txt +++ b/src/main/target/FURYF3/CMakeLists.txt @@ -1,2 +1,2 @@ -target_stm32f303(FURYF3) -target_stm32f303(FURYF3_SPIFLASH) \ No newline at end of file +target_stm32f303xc(FURYF3) +target_stm32f303xc(FURYF3_SPIFLASH) diff --git a/src/main/target/FURYF4OSD/CMakeLists.txt b/src/main/target/FURYF4OSD/CMakeLists.txt index 620d9f3a7bc..34025a1f90e 100644 --- a/src/main/target/FURYF4OSD/CMakeLists.txt +++ b/src/main/target/FURYF4OSD/CMakeLists.txt @@ -1,2 +1,2 @@ -target_stm32f405(FURYF4OSD) -target_stm32f405(MAMBAF405) +target_stm32f405xg(FURYF4OSD) +target_stm32f405xg(MAMBAF405) diff --git a/src/main/target/HGLRCF722/CMakeLists.txt b/src/main/target/HGLRCF722/CMakeLists.txt index 3015c57d0a8..7ea0539d651 100644 --- a/src/main/target/HGLRCF722/CMakeLists.txt +++ b/src/main/target/HGLRCF722/CMakeLists.txt @@ -1 +1 @@ -target_stm32f722(HGLRCF722) \ No newline at end of file +target_stm32f722xe(HGLRCF722) diff --git a/src/main/target/IFLIGHTF4_SUCCEXD/CMakeLists.txt b/src/main/target/IFLIGHTF4_SUCCEXD/CMakeLists.txt index 7c0d18cb3fe..1c0c46b8955 100644 --- a/src/main/target/IFLIGHTF4_SUCCEXD/CMakeLists.txt +++ b/src/main/target/IFLIGHTF4_SUCCEXD/CMakeLists.txt @@ -1 +1 @@ -target_stm32f411(IFLIGHTF4_SUCCEXD) \ No newline at end of file +target_stm32f411xe(IFLIGHTF4_SUCCEXD) diff --git a/src/main/target/IFLIGHTF4_TWING/CMakeLists.txt b/src/main/target/IFLIGHTF4_TWING/CMakeLists.txt index 048646799df..a7640915f33 100644 --- a/src/main/target/IFLIGHTF4_TWING/CMakeLists.txt +++ b/src/main/target/IFLIGHTF4_TWING/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405(IFLIGHTF4_TWING) +target_stm32f405xg(IFLIGHTF4_TWING) diff --git a/src/main/target/IFLIGHTF7_TWING/CMakeLists.txt b/src/main/target/IFLIGHTF7_TWING/CMakeLists.txt index 8ce43face71..cf8ca2b933b 100644 --- a/src/main/target/IFLIGHTF7_TWING/CMakeLists.txt +++ b/src/main/target/IFLIGHTF7_TWING/CMakeLists.txt @@ -1 +1 @@ -target_stm32f722(IFLIGHTF7_TWING) \ No newline at end of file +target_stm32f722xe(IFLIGHTF7_TWING) diff --git a/src/main/target/KAKUTEF4/CMakeLists.txt b/src/main/target/KAKUTEF4/CMakeLists.txt index 84419108726..074eb6cd354 100644 --- a/src/main/target/KAKUTEF4/CMakeLists.txt +++ b/src/main/target/KAKUTEF4/CMakeLists.txt @@ -1,2 +1,2 @@ -target_stm32f405(KAKUTEF4) -target_stm32f405(KAKUTEF4V2) +target_stm32f405xg(KAKUTEF4) +target_stm32f405xg(KAKUTEF4V2) diff --git a/src/main/target/KAKUTEF7/CMakeLists.txt b/src/main/target/KAKUTEF7/CMakeLists.txt index 78856cbd159..8f4702fcf47 100644 --- a/src/main/target/KAKUTEF7/CMakeLists.txt +++ b/src/main/target/KAKUTEF7/CMakeLists.txt @@ -1,3 +1,3 @@ -target_stm32f745(KAKUTEF7) -target_stm32f745(KAKUTEF7HDV) -target_stm32f745(KAKUTEF7MINI) \ No newline at end of file +target_stm32f745xg(KAKUTEF7) +target_stm32f745xg(KAKUTEF7HDV) +target_stm32f745xg(KAKUTEF7MINI) diff --git a/src/main/target/KFC32F3_INAV/CMakeLists.txt b/src/main/target/KFC32F3_INAV/CMakeLists.txt index 5f1543c39fd..c8bf5690a0e 100644 --- a/src/main/target/KFC32F3_INAV/CMakeLists.txt +++ b/src/main/target/KFC32F3_INAV/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303(KFC32F3_INAV) \ No newline at end of file +target_stm32f303xc(KFC32F3_INAV) diff --git a/src/main/target/LUX_RACE/CMakeLists.txt b/src/main/target/LUX_RACE/CMakeLists.txt index 797a42bbec6..d052694896a 100644 --- a/src/main/target/LUX_RACE/CMakeLists.txt +++ b/src/main/target/LUX_RACE/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303(LUX_RACE) \ No newline at end of file +target_stm32f303xc(LUX_RACE) diff --git a/src/main/target/MAMBAF405US/CMakeLists.txt b/src/main/target/MAMBAF405US/CMakeLists.txt index 270627d9138..d4565822bf8 100644 --- a/src/main/target/MAMBAF405US/CMakeLists.txt +++ b/src/main/target/MAMBAF405US/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405(MAMBAF405US) +target_stm32f405xg(MAMBAF405US) diff --git a/src/main/target/MAMBAF722/CMakeLists.txt b/src/main/target/MAMBAF722/CMakeLists.txt index 5494780c064..e893c246846 100644 --- a/src/main/target/MAMBAF722/CMakeLists.txt +++ b/src/main/target/MAMBAF722/CMakeLists.txt @@ -1 +1 @@ -target_stm32f722(MAMBAF722) \ No newline at end of file +target_stm32f722xe(MAMBAF722) diff --git a/src/main/target/MATEKF405/CMakeLists.txt b/src/main/target/MATEKF405/CMakeLists.txt index 8ffba845e58..c4f839c1c1d 100644 --- a/src/main/target/MATEKF405/CMakeLists.txt +++ b/src/main/target/MATEKF405/CMakeLists.txt @@ -1,3 +1,3 @@ -target_stm32f405(MATEKF405) -target_stm32f405(MATEKF405_SERVOS6) -target_stm32f405(MATEKF405OSD) +target_stm32f405xg(MATEKF405) +target_stm32f405xg(MATEKF405_SERVOS6) +target_stm32f405xg(MATEKF405OSD) diff --git a/src/main/target/MATEKF405SE/CMakeLists.txt b/src/main/target/MATEKF405SE/CMakeLists.txt index 4fedcde60a8..2c754ecea8c 100644 --- a/src/main/target/MATEKF405SE/CMakeLists.txt +++ b/src/main/target/MATEKF405SE/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405(MATEKF405SE) +target_stm32f405xg(MATEKF405SE) diff --git a/src/main/target/MATEKF411/CMakeLists.txt b/src/main/target/MATEKF411/CMakeLists.txt index 426c86cb5d2..5907460815f 100644 --- a/src/main/target/MATEKF411/CMakeLists.txt +++ b/src/main/target/MATEKF411/CMakeLists.txt @@ -1,4 +1,4 @@ -target_stm32f411(MATEKF411) -target_stm32f411(MATEKF411_FD_SFTSRL) -target_stm32f411(MATEKF411_RSSI) -target_stm32f411(MATEKF411_SFTSRL2) +target_stm32f411xe(MATEKF411) +target_stm32f411xe(MATEKF411_FD_SFTSRL) +target_stm32f411xe(MATEKF411_RSSI) +target_stm32f411xe(MATEKF411_SFTSRL2) diff --git a/src/main/target/MATEKF411SE/CMakeLists.txt b/src/main/target/MATEKF411SE/CMakeLists.txt index 0031ec68c21..df67c6f00b7 100644 --- a/src/main/target/MATEKF411SE/CMakeLists.txt +++ b/src/main/target/MATEKF411SE/CMakeLists.txt @@ -1 +1 @@ -target_stm32f411(MATEKF411SE) +target_stm32f411xe(MATEKF411SE) diff --git a/src/main/target/MATEKF722/CMakeLists.txt b/src/main/target/MATEKF722/CMakeLists.txt index cbafe79506b..eb384e12815 100644 --- a/src/main/target/MATEKF722/CMakeLists.txt +++ b/src/main/target/MATEKF722/CMakeLists.txt @@ -1,2 +1,2 @@ -target_stm32f722(MATEKF722) -target_stm32f722(MATEKF722_HEXSERVO) \ No newline at end of file +target_stm32f722xe(MATEKF722) +target_stm32f722xe(MATEKF722_HEXSERVO) diff --git a/src/main/target/MATEKF722PX/CMakeLists.txt b/src/main/target/MATEKF722PX/CMakeLists.txt index 9e53706f3f9..02489028469 100644 --- a/src/main/target/MATEKF722PX/CMakeLists.txt +++ b/src/main/target/MATEKF722PX/CMakeLists.txt @@ -1 +1 @@ -target_stm32f722(MATEKF722PX) \ No newline at end of file +target_stm32f722xe(MATEKF722PX) diff --git a/src/main/target/MATEKF722SE/CMakeLists.txt b/src/main/target/MATEKF722SE/CMakeLists.txt index 66c55b0fbfb..a541da229f2 100644 --- a/src/main/target/MATEKF722SE/CMakeLists.txt +++ b/src/main/target/MATEKF722SE/CMakeLists.txt @@ -1,2 +1,2 @@ -target_stm32f722(MATEKF722SE) -target_stm32f722(MATEKF722MINI) \ No newline at end of file +target_stm32f722xe(MATEKF722SE) +target_stm32f722xe(MATEKF722MINI) diff --git a/src/main/target/MATEKF765/CMakeLists.txt b/src/main/target/MATEKF765/CMakeLists.txt index ab9f4e7e77e..2461647ec00 100644 --- a/src/main/target/MATEKF765/CMakeLists.txt +++ b/src/main/target/MATEKF765/CMakeLists.txt @@ -1 +1 @@ -target_stm32f765(MATEKF765) \ No newline at end of file +target_stm32f765xi(MATEKF765) diff --git a/src/main/target/MOTOLAB/CMakeLists.txt b/src/main/target/MOTOLAB/CMakeLists.txt index d3372f5056a..44a615e98db 100644 --- a/src/main/target/MOTOLAB/CMakeLists.txt +++ b/src/main/target/MOTOLAB/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303(MOTOLAB) \ No newline at end of file +target_stm32f303xc(MOTOLAB) diff --git a/src/main/target/NOX/CMakeLists.txt b/src/main/target/NOX/CMakeLists.txt index 588b589c87b..b8189c76ec5 100644 --- a/src/main/target/NOX/CMakeLists.txt +++ b/src/main/target/NOX/CMakeLists.txt @@ -1 +1 @@ -target_stm32f411(NOX) +target_stm32f411xe(NOX) diff --git a/src/main/target/OMNIBUS/CMakeLists.txt b/src/main/target/OMNIBUS/CMakeLists.txt index a87b5286677..9b0d502da5b 100644 --- a/src/main/target/OMNIBUS/CMakeLists.txt +++ b/src/main/target/OMNIBUS/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303(OMNIBUS) \ No newline at end of file +target_stm32f303xc(OMNIBUS) diff --git a/src/main/target/OMNIBUSF4/CMakeLists.txt b/src/main/target/OMNIBUSF4/CMakeLists.txt index b6c2077d0f1..72f3bbeca87 100644 --- a/src/main/target/OMNIBUSF4/CMakeLists.txt +++ b/src/main/target/OMNIBUSF4/CMakeLists.txt @@ -1,12 +1,12 @@ -target_stm32f405(DYSF4PRO) -target_stm32f405(DYSF4PROV2) -target_stm32f405(OMNIBUSF4) +target_stm32f405xg(DYSF4PRO) +target_stm32f405xg(DYSF4PROV2) +target_stm32f405xg(OMNIBUSF4) # the OMNIBUSF4SD has an SDCARD instead of flash, a BMP280 baro and therefore a slightly different ppm/pwm and SPI mapping -target_stm32f405(OMNIBUSF4PRO) -target_stm32f405(OMNIBUSF4PRO_LEDSTRIPM5) -target_stm32f405(OMNIBUSF4V3_S5_S6_2SS) -target_stm32f405(OMNIBUSF4V3_S5S6_SS) -target_stm32f405(OMNIBUSF4V3_S6_SS) +target_stm32f405xg(OMNIBUSF4PRO) +target_stm32f405xg(OMNIBUSF4PRO_LEDSTRIPM5) +target_stm32f405xg(OMNIBUSF4V3_S5_S6_2SS) +target_stm32f405xg(OMNIBUSF4V3_S5S6_SS) +target_stm32f405xg(OMNIBUSF4V3_S6_SS) # OMNIBUSF4V3 is a (almost identical) variant of OMNIBUSF4PRO target, # except for an inverter on UART6. -target_stm32f405(OMNIBUSF4V3) +target_stm32f405xg(OMNIBUSF4V3) diff --git a/src/main/target/OMNIBUSF7/CMakeLists.txt b/src/main/target/OMNIBUSF7/CMakeLists.txt index 5f2f42d4c69..456c8632f66 100644 --- a/src/main/target/OMNIBUSF7/CMakeLists.txt +++ b/src/main/target/OMNIBUSF7/CMakeLists.txt @@ -1,2 +1,2 @@ -target_stm32f745(OMNIBUSF7) -target_stm32f745(OMNIBUSF7V2) \ No newline at end of file +target_stm32f745xg(OMNIBUSF7) +target_stm32f745xg(OMNIBUSF7V2) diff --git a/src/main/target/OMNIBUSF7NXT/CMakeLists.txt b/src/main/target/OMNIBUSF7NXT/CMakeLists.txt index d75488409b4..db1bd01c22a 100644 --- a/src/main/target/OMNIBUSF7NXT/CMakeLists.txt +++ b/src/main/target/OMNIBUSF7NXT/CMakeLists.txt @@ -1 +1 @@ -target_stm32f722(OMNIBUSF7NXT) \ No newline at end of file +target_stm32f722xe(OMNIBUSF7NXT) diff --git a/src/main/target/PIKOBLX/CMakeLists.txt b/src/main/target/PIKOBLX/CMakeLists.txt index 8ed14ef8757..b9357a9f98b 100644 --- a/src/main/target/PIKOBLX/CMakeLists.txt +++ b/src/main/target/PIKOBLX/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303(PIKOBLX) \ No newline at end of file +target_stm32f303xc(PIKOBLX) diff --git a/src/main/target/PIXRACER/CMakeLists.txt b/src/main/target/PIXRACER/CMakeLists.txt index d55ca6feffb..c2c06c5a673 100644 --- a/src/main/target/PIXRACER/CMakeLists.txt +++ b/src/main/target/PIXRACER/CMakeLists.txt @@ -1 +1 @@ -target_stm32f427(PIXRACER HSE_MHZ 24) +target_stm32f427xg(PIXRACER HSE_MHZ 24) diff --git a/src/main/target/RCEXPLORERF3/CMakeLists.txt b/src/main/target/RCEXPLORERF3/CMakeLists.txt index 2a069102f9e..cdb3b34ed0c 100644 --- a/src/main/target/RCEXPLORERF3/CMakeLists.txt +++ b/src/main/target/RCEXPLORERF3/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303(RCEXPLORERF3) \ No newline at end of file +target_stm32f303xc(RCEXPLORERF3) diff --git a/src/main/target/REVO/CMakeLists.txt b/src/main/target/REVO/CMakeLists.txt index 4b7a04fb539..e972aaf43e7 100644 --- a/src/main/target/REVO/CMakeLists.txt +++ b/src/main/target/REVO/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405(REVO) +target_stm32f405xg(REVO) diff --git a/src/main/target/RMDO/CMakeLists.txt b/src/main/target/RMDO/CMakeLists.txt index f3a2c36eeba..541927fed06 100644 --- a/src/main/target/RMDO/CMakeLists.txt +++ b/src/main/target/RMDO/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303(RMDO DEFINITIONS "SPRACINGF3") \ No newline at end of file +target_stm32f303xc(RMDO COMPILE_DEFINITIONS "SPRACINGF3") diff --git a/src/main/target/SPARKY/CMakeLists.txt b/src/main/target/SPARKY/CMakeLists.txt index 1a6f1f0e23e..10bb24b0abb 100644 --- a/src/main/target/SPARKY/CMakeLists.txt +++ b/src/main/target/SPARKY/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303(SPARKY) \ No newline at end of file +target_stm32f303xc(SPARKY) diff --git a/src/main/target/SPARKY2/CMakeLists.txt b/src/main/target/SPARKY2/CMakeLists.txt index ea3e9b15d8a..12985b381af 100644 --- a/src/main/target/SPARKY2/CMakeLists.txt +++ b/src/main/target/SPARKY2/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405(SPARKY2) +target_stm32f405xg(SPARKY2) diff --git a/src/main/target/SPEEDYBEEF4/CMakeLists.txt b/src/main/target/SPEEDYBEEF4/CMakeLists.txt index ed18e3403cf..1735fcb6c28 100644 --- a/src/main/target/SPEEDYBEEF4/CMakeLists.txt +++ b/src/main/target/SPEEDYBEEF4/CMakeLists.txt @@ -1,3 +1,3 @@ -target_stm32f405(SPEEDYBEEF4) -target_stm32f405(SPEEDYBEEF4_SFTSRL1) -target_stm32f405(SPEEDYBEEF4_SFTSRL2) +target_stm32f405xg(SPEEDYBEEF4) +target_stm32f405xg(SPEEDYBEEF4_SFTSRL1) +target_stm32f405xg(SPEEDYBEEF4_SFTSRL2) diff --git a/src/main/target/SPRACINGF3/CMakeLists.txt b/src/main/target/SPRACINGF3/CMakeLists.txt index dae18ee21fb..2840cbef85e 100644 --- a/src/main/target/SPRACINGF3/CMakeLists.txt +++ b/src/main/target/SPRACINGF3/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303(SPRACINGF3) \ No newline at end of file +target_stm32f303xc(SPRACINGF3) diff --git a/src/main/target/SPRACINGF3EVO/CMakeLists.txt b/src/main/target/SPRACINGF3EVO/CMakeLists.txt index c2dbd822b01..3833d8d59e3 100644 --- a/src/main/target/SPRACINGF3EVO/CMakeLists.txt +++ b/src/main/target/SPRACINGF3EVO/CMakeLists.txt @@ -1,2 +1,2 @@ -target_stm32f303(SPRACINGF3EVO) -target_stm32f303(SPRACINGF3EVO_1SS) \ No newline at end of file +target_stm32f303xc(SPRACINGF3EVO) +target_stm32f303xc(SPRACINGF3EVO_1SS) diff --git a/src/main/target/SPRACINGF3MINI/CMakeLists.txt b/src/main/target/SPRACINGF3MINI/CMakeLists.txt index d9518a0920a..e3b633a6d41 100644 --- a/src/main/target/SPRACINGF3MINI/CMakeLists.txt +++ b/src/main/target/SPRACINGF3MINI/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303(SPRACINGF3MINI) \ No newline at end of file +target_stm32f303xc(SPRACINGF3MINI) diff --git a/src/main/target/SPRACINGF4EVO/CMakeLists.txt b/src/main/target/SPRACINGF4EVO/CMakeLists.txt index 0b9e390d717..41dbc70ab02 100644 --- a/src/main/target/SPRACINGF4EVO/CMakeLists.txt +++ b/src/main/target/SPRACINGF4EVO/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405(SPRACINGF4EVO) +target_stm32f405xg(SPRACINGF4EVO) diff --git a/src/main/target/SPRACINGF7DUAL/CMakeLists.txt b/src/main/target/SPRACINGF7DUAL/CMakeLists.txt index 9f470b18e70..1fc19b7e12d 100644 --- a/src/main/target/SPRACINGF7DUAL/CMakeLists.txt +++ b/src/main/target/SPRACINGF7DUAL/CMakeLists.txt @@ -1 +1 @@ -target_stm32f722(SPRACINGF7DUAL) \ No newline at end of file +target_stm32f722xe(SPRACINGF7DUAL) diff --git a/src/main/target/YUPIF7/CMakeLists.txt b/src/main/target/YUPIF7/CMakeLists.txt index e1073f8d00c..289873afc08 100644 --- a/src/main/target/YUPIF7/CMakeLists.txt +++ b/src/main/target/YUPIF7/CMakeLists.txt @@ -1 +1 @@ -target_stm32f722(YUPIF7) \ No newline at end of file +target_stm32f722xe(YUPIF7) \ No newline at end of file diff --git a/src/main/target/ZEEZF7/CMakeLists.txt b/src/main/target/ZEEZF7/CMakeLists.txt index 8c1536bee4f..513e023060d 100644 --- a/src/main/target/ZEEZF7/CMakeLists.txt +++ b/src/main/target/ZEEZF7/CMakeLists.txt @@ -1 +1 @@ -target_stm32f722(ZEEZF7) \ No newline at end of file +target_stm32f722xe(ZEEZF7) diff --git a/src/main/target/link/stm32_flash_F427.ld b/src/main/target/link/stm32_flash_F427.ld old mode 100755 new mode 100644 diff --git a/src/main/target/link/stm32_flash_F7_split.ld b/src/main/target/link/stm32_flash_F7_split.ld index 42d8f0205ca..f3dde2e7f7e 100644 --- a/src/main/target/link/stm32_flash_F7_split.ld +++ b/src/main/target/link/stm32_flash_F7_split.ld @@ -1,9 +1,9 @@ /* ***************************************************************************** ** -** File : stm32_flash_split.ld +** File : stm32_flash_f7_split.ld ** -** Abstract : Common linker script for STM32 devices. +** Abstract : Common linker script for STM32F7 devices. ** ***************************************************************************** */ diff --git a/src/main/target/link/stm32_flash_f303xc.ld b/src/main/target/link/stm32_flash_f303xc.ld new file mode 100644 index 00000000000..1917843495d --- /dev/null +++ b/src/main/target/link/stm32_flash_f303xc.ld @@ -0,0 +1,30 @@ +/* +***************************************************************************** +** +** File : stm32_flash.ld +** +** Abstract : Linker script for STM32F30x Device with +** 256KByte FLASH and 40KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Specify the memory areas. */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 250K + FLASH_CONFIG (r) : ORIGIN = 0x0803E800, LENGTH = 6K + + RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 40K + CCM (xrw) : ORIGIN = 0x10000000, LENGTH = 8K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("STACKRAM", CCM) +REGION_ALIAS("FASTRAM", CCM) + +INCLUDE "stm32_flash.ld" diff --git a/src/main/target/link/stm32_flash_f405xg.ld b/src/main/target/link/stm32_flash_f405xg.ld new file mode 100644 index 00000000000..66721aee5ff --- /dev/null +++ b/src/main/target/link/stm32_flash_f405xg.ld @@ -0,0 +1,40 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f405.ld +** +** Abstract : Linker script for STM32F405RG Device with +** 1024KByte FLASH, 128KByte RAM 64KByte CCM (RAM) +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x08000000 to 0x08100000 1024K full flash, +0x08000000 to 0x080DFFFF 896K firmware, +0x080E0000 to 0x08100000 128K config, // FLASH_Sector_11 +*/ + +/* Specify the memory areas */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 896K + FLASH_CONFIG (r) : ORIGIN = 0x080E0000, LENGTH = 128K + + RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + CCM (rwx) : ORIGIN = 0x10000000, LENGTH = 64K + BACKUP_SRAM (rwx) : ORIGIN = 0x40024000, LENGTH = 4K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("STACKRAM", CCM) +REGION_ALIAS("FASTRAM", CCM) + +INCLUDE "stm32_flash.ld" diff --git a/src/main/target/link/stm32_flash_f405xg_bl.ld b/src/main/target/link/stm32_flash_f405xg_bl.ld new file mode 100644 index 00000000000..6ae82e6f8a7 --- /dev/null +++ b/src/main/target/link/stm32_flash_f405xg_bl.ld @@ -0,0 +1,43 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f405.ld +** +** Abstract : Linker script for STM32F405RG Device with +** 1024KByte FLASH, 128KByte RAM 64KByte CCM (RAM) +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x08000000 to 0x08100000 1024K full flash, +0x08000000 to 0x080DFFFF 896K firmware, +0x080E0000 to 0x08100000 128K config, // FLASH_Sector_11 +*/ + +/* Specify the memory areas */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K + FIRMWARE (rx) : ORIGIN = 0x08008000, LENGTH = 864K + FLASH_CONFIG (r) : ORIGIN = 0x080E0000, LENGTH = 128K + + RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + CCM (rwx) : ORIGIN = 0x10000000, LENGTH = 64K + BACKUP_SRAM (rwx) : ORIGIN = 0x40024000, LENGTH = 4K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("STACKRAM", CCM) +REGION_ALIAS("FASTRAM", CCM) + +__firmware_start = ORIGIN(FIRMWARE); + +INCLUDE "stm32_flash.ld" diff --git a/src/main/target/link/stm32_flash_f405xg_for_bl.ld b/src/main/target/link/stm32_flash_f405xg_for_bl.ld new file mode 100644 index 00000000000..c2a60a1429e --- /dev/null +++ b/src/main/target/link/stm32_flash_f405xg_for_bl.ld @@ -0,0 +1,42 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f405.ld +** +** Abstract : Linker script for STM32F405RG Device with +** 1024KByte FLASH, 128KByte RAM 64KByte CCM (RAM) +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x08000000 to 0x08100000 1024K full flash, +0x08000000 to 0x080DFFFF 896K firmware, +0x080E0000 to 0x08100000 128K config, // FLASH_Sector_11 +*/ + +/* Specify the memory areas */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08008000, LENGTH = 864K + FLASH_CONFIG (r) : ORIGIN = 0x080E0000, LENGTH = 128K + + RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + CCM (rwx) : ORIGIN = 0x10000000, LENGTH = 64K + BACKUP_SRAM (rwx) : ORIGIN = 0x40024000, LENGTH = 4K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("STACKRAM", CCM) +REGION_ALIAS("FASTRAM", CCM) + +__firmware_start = ORIGIN(FLASH); + +INCLUDE "stm32_flash.ld" diff --git a/src/main/target/link/stm32_flash_f411xe.ld b/src/main/target/link/stm32_flash_f411xe.ld new file mode 100644 index 00000000000..0326840b340 --- /dev/null +++ b/src/main/target/link/stm32_flash_f411xe.ld @@ -0,0 +1,40 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f411.ld +** +** Abstract : Linker script for STM32F11 Device with +** 512KByte FLASH, 128KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x08000000 to 0x0807FFFF 512K full flash, +0x08000000 to 0x08003FFF 16K isr vector, startup code, +0x08004000 to 0x08007FFF 16K config, // FLASH_Sector_1 +0x08008000 to 0x0807FFFF 480K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K + FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K + FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K + + RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("STACKRAM", RAM) +REGION_ALIAS("FASTRAM", RAM) + +INCLUDE "stm32_flash_split.ld" diff --git a/src/main/target/link/stm32_flash_f427xg.ld b/src/main/target/link/stm32_flash_f427xg.ld new file mode 100644 index 00000000000..8c080f38e7b --- /dev/null +++ b/src/main/target/link/stm32_flash_f427xg.ld @@ -0,0 +1,59 @@ +/* +***************************************************************************** +** +** File : stm32_flash.ld +** +** Abstract : Linker script for STM32F427 Device with +** 2048 KByte FLASH, 192KByte RAM +** +** Set heap size, stack size and stack location according +** to application requirements. +** +** Set memory bank area and size if external memory is used. +** +** Target : STMicroelectronics STM32 +** +** Environment : Atollic TrueSTUDIO(R) +** +** Distribution: The file is distributed as is, without any warranty +** of any kind. +** +** (c)Copyright Atollic AB. +** You may use this file as-is or modify it according to the needs of your +** project. Distribution of this file (unmodified or modified) is not +** permitted. Atollic AB permit registered Atollic TrueSTUDIO(R) users the +** rights to distribute the assembled, compiled & linked contents of this +** file as part of an application binary file, provided that it is built +** using the Atollic TrueSTUDIO(R) toolchain. +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x08000000 to 0x08100000 1024K full flash, +0x08000000 to 0x080DFFFF 896K firmware, +0x080E0000 to 0x08100000 128K config, // FLASH_Sector_11 +*/ + +/* Specify the memory areas */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 896K + FLASH_CONFIG (r) : ORIGIN = 0x080E0000, LENGTH = 128K + + RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + CCM (rwx) : ORIGIN = 0x10000000, LENGTH = 64K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("STACKRAM", CCM) +REGION_ALIAS("FASTRAM", CCM) + +INCLUDE "stm32_flash.ld" diff --git a/src/main/target/link/stm32_flash_f446xe.ld b/src/main/target/link/stm32_flash_f446xe.ld new file mode 100644 index 00000000000..1128fa3506e --- /dev/null +++ b/src/main/target/link/stm32_flash_f446xe.ld @@ -0,0 +1,40 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f411.ld +** +** Abstract : Linker script for STM32F11 Device with +** 512KByte FLASH, 128KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x08000000 to 0x0807FFFF 512K full flash, +0x08000000 to 0x08003FFF 16K isr vector, startup code, +0x08004000 to 0x08007FFF 16K config, // FLASH_Sector_1 +0x08008000 to 0x0807FFFF 480K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K + FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K + FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K + + RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("STACKRAM", RAM) +REGION_ALIAS("FASTRAM", RAM) + +INCLUDE "stm32_flash_split.ld" \ No newline at end of file diff --git a/src/main/target/link/stm32_flash_f722xe.ld b/src/main/target/link/stm32_flash_f722xe.ld new file mode 100644 index 00000000000..3a9094ed81f --- /dev/null +++ b/src/main/target/link/stm32_flash_f722xe.ld @@ -0,0 +1,48 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f722xe.ld +** +** Abstract : Linker script for STM32F722RETx Device with +** 512KByte FLASH, 256KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x08000000 to 0x0807FFFF 512K full flash, +0x08000000 to 0x08003FFF 16K isr vector, startup code, +0x08004000 to 0x08007FFF 16K config, // FLASH_Sector_1 +0x08008000 to 0x0807FFFF 480K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 16K + + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 16K + /* config occupies the entire flash sector 1 for the ease of erasure, 16K on F72x */ + ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00204000, LENGTH = 16K + ITCM_FLASH1 (rx) : ORIGIN = 0x00208000, LENGTH = 480K + + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K + FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K + FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K + + TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 192K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("STACKRAM", TCM) +REGION_ALIAS("FASTRAM", TCM) + +INCLUDE "stm32_flash_f7_split.ld" diff --git a/src/main/target/link/stm32_flash_f722xe_bl.ld b/src/main/target/link/stm32_flash_f722xe_bl.ld new file mode 100644 index 00000000000..1241562d055 --- /dev/null +++ b/src/main/target/link/stm32_flash_f722xe_bl.ld @@ -0,0 +1,50 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f722.ld +** +** Abstract : Linker script for STM32F722RETx Device with +** 512KByte FLASH, 256KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x08000000 to 0x0807FFFF 512K full flash, +0x08000000 to 0x08003FFF 16K isr vector, startup code, +0x08004000 to 0x08007FFF 16K config, // FLASH_Sector_1 +0x08008000 to 0x0807FFFF 480K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 16K + + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 16K + /* config occupies the entire flash sector 1 for the ease of erasure, 16K on F72x */ + ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00204000, LENGTH = 16K + ITCM_FLASH1 (rx) : ORIGIN = 0x00208000, LENGTH = 480K + + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K + FIRMWARE (rx) : ORIGIN = 0x08008000, LENGTH = 16K + FLASH_CONFIG (r) : ORIGIN = 0x0800c000, LENGTH = 16K + + TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 192K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("STACKRAM", TCM) +REGION_ALIAS("FASTRAM", TCM) + +__firmware_start = ORIGIN(FIRMWARE); + +INCLUDE "stm32_flash_F7.ld" diff --git a/src/main/target/link/stm32_flash_f722xe_for_bl.ld b/src/main/target/link/stm32_flash_f722xe_for_bl.ld new file mode 100644 index 00000000000..5ce5fb03774 --- /dev/null +++ b/src/main/target/link/stm32_flash_f722xe_for_bl.ld @@ -0,0 +1,50 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f722.ld +** +** Abstract : Linker script for STM32F722RETx Device with +** 512KByte FLASH, 256KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x08000000 to 0x0807FFFF 512K full flash, +0x08000000 to 0x08003FFF 16K isr vector, startup code, +0x08004000 to 0x08007FFF 16K config, // FLASH_Sector_1 +0x08008000 to 0x0807FFFF 480K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 16K + + /*ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 16K*/ + /* config occupies the entire flash sector 1 for the ease of erasure, 16K on F72x */ + /*ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00204000, LENGTH = 16K*/ + /*ITCM_FLASH1 (rx) : ORIGIN = 0x00208000, LENGTH = 480K*/ + + FLASH (rx) : ORIGIN = 0x08008000, LENGTH = 16K + FLASH_CONFIG (r) : ORIGIN = 0x0800c000, LENGTH = 16K + FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 448K + + TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 192K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("STACKRAM", TCM) +REGION_ALIAS("FASTRAM", TCM) + +__firmware_start = ORIGIN(FLASH); + +INCLUDE "stm32_flash_F7_split.ld" diff --git a/src/main/target/link/stm32_flash_f745xg.ld b/src/main/target/link/stm32_flash_f745xg.ld new file mode 100644 index 00000000000..161e3b5d583 --- /dev/null +++ b/src/main/target/link/stm32_flash_f745xg.ld @@ -0,0 +1,48 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f745xg.ld +** +** Abstract : Linker script for STM32F745xG Device with +** 1024KByte FLASH, 320KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x00003FFF 16K ITCM RAM, +0x08000000 to 0x080FFFFF 1024K full flash, +0x08000000 to 0x08007FFF 32K isr vector, startup code, +0x08008000 to 0x0800FFFF 32K config, // FLASH_Sector_1 +0x08010000 to 0x080FFFFF 960K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K + /* config occupies the entire flash sector 1 for the ease of erasure, 32K on F74x */ + ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00208000, LENGTH = 32K + ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 960K + + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K + FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 32K + FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 960K + + TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 256K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} +/* note CCM could be used for stack */ +REGION_ALIAS("STACKRAM", TCM) +REGION_ALIAS("FASTRAM", TCM) + +INCLUDE "stm32_flash_F7_split.ld" diff --git a/src/main/target/link/stm32_flash_f745xg_bl.ld b/src/main/target/link/stm32_flash_f745xg_bl.ld new file mode 100644 index 00000000000..6639776539b --- /dev/null +++ b/src/main/target/link/stm32_flash_f745xg_bl.ld @@ -0,0 +1,50 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f745.ld +** +** Abstract : Linker script for STM32F745VGTx Device with +** 1024KByte FLASH, 320KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x00003FFF 16K ITCM RAM, +0x08000000 to 0x080FFFFF 1024K full flash, +0x08000000 to 0x08007FFF 32K isr vector, startup code, +0x08008000 to 0x0800FFFF 32K config, // FLASH_Sector_1 +0x08010000 to 0x080FFFFF 960K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K + /* config occupies the entire flash sector 1 for the ease of erasure, 32K on F74x */ + ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00208000, LENGTH = 32K + ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 928K + + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K + FIRMWARE (rx) : ORIGIN = 0x08008000, LENGTH = 32K + FLASH_CONFIG (r) : ORIGIN = 0x08010000, LENGTH = 32K + + TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 256K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} +/* note CCM could be used for stack */ +REGION_ALIAS("STACKRAM", TCM) +REGION_ALIAS("FASTRAM", TCM) + +__firmware_start = ORIGIN(FIRMWARE); + +INCLUDE "stm32_flash_F7.ld" diff --git a/src/main/target/link/stm32_flash_f745xg_for_bl.ld b/src/main/target/link/stm32_flash_f745xg_for_bl.ld new file mode 100644 index 00000000000..4cfd76df20a --- /dev/null +++ b/src/main/target/link/stm32_flash_f745xg_for_bl.ld @@ -0,0 +1,50 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f745.ld +** +** Abstract : Linker script for STM32F745VGTx Device with +** 1024KByte FLASH, 320KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x00003FFF 16K ITCM RAM, +0x08000000 to 0x080FFFFF 1024K full flash, +0x08000000 to 0x08007FFF 32K isr vector, startup code, +0x08008000 to 0x0800FFFF 32K config, // FLASH_Sector_1 +0x08010000 to 0x080FFFFF 960K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K + /* config occupies the entire flash sector 1 for the ease of erasure, 32K on F74x */ + ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00208000, LENGTH = 32K + ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 960K + + FLASH (rx) : ORIGIN = 0x08008000, LENGTH = 32K + FLASH_CONFIG (r) : ORIGIN = 0x08010000, LENGTH = 32K + FLASH1 (rx) : ORIGIN = 0x08018000, LENGTH = 928K + + TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 256K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} +/* note CCM could be used for stack */ +REGION_ALIAS("STACKRAM", TCM) +REGION_ALIAS("FASTRAM", TCM) + +__firmware_start = ORIGIN(FLASH); + +INCLUDE "stm32_flash_F7_split.ld" From 0041cbcdcaba66cb6b48defe29d93185cec2a306 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sun, 9 Aug 2020 21:47:40 +0100 Subject: [PATCH 157/248] [MISC] Fix warnings found by -Werror --- src/main/io/displayport_hott.c | 2 +- src/main/io/vtx_tramp.c | 4 ++-- src/main/msc/usbd_storage_sd_spi.c | 2 +- src/main/target/system_stm32f4xx.c | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/main/io/displayport_hott.c b/src/main/io/displayport_hott.c index 85eed39164d..68aaed5d93d 100644 --- a/src/main/io/displayport_hott.c +++ b/src/main/io/displayport_hott.c @@ -60,7 +60,7 @@ static int hottClearScreen(displayPort_t *displayPort) { for (int row = 0; row < displayPort->rows; row++) { for (int col= 0; col < displayPort->cols; col++) { - hottWriteChar(displayPort, col, row, ' ', NULL); + hottWriteChar(displayPort, col, row, ' ', 0); } } return 0; diff --git a/src/main/io/vtx_tramp.c b/src/main/io/vtx_tramp.c index 4e22d35f2ff..7e501221138 100644 --- a/src/main/io/vtx_tramp.c +++ b/src/main/io/vtx_tramp.c @@ -276,7 +276,7 @@ static void impl_Process(vtxDevice_t *vtxDevice, timeUs_t currentTimeUs) UNUSED(currentTimeUs); if (!vtxState.port) { - return false; + return; } switch((int)vtxState.protoState) { @@ -411,7 +411,7 @@ static void impl_SetBandAndChannel(vtxDevice_t * vtxDevice, uint8_t band, uint8_ uint16_t newFreqMhz = vtx58_Bandchan2Freq(band, channel); if (newFreqMhz < vtxState.capabilities.freqMin || newFreqMhz > vtxState.capabilities.freqMax) { - return false; + return; } // Cache band and channel diff --git a/src/main/msc/usbd_storage_sd_spi.c b/src/main/msc/usbd_storage_sd_spi.c index 79c9bee225a..fc61cd6cef6 100644 --- a/src/main/msc/usbd_storage_sd_spi.c +++ b/src/main/msc/usbd_storage_sd_spi.c @@ -234,7 +234,7 @@ static int8_t STORAGE_Write (uint8_t lun, UNUSED(lun); LED1_ON; for (int i = 0; i < blk_len; i++) { - while (sdcard_writeBlock(blk_addr + i, buf + (i * 512), NULL, NULL) != SDCARD_OPERATION_IN_PROGRESS) { + while (sdcard_writeBlock(blk_addr + i, buf + (i * 512), NULL, 0) != SDCARD_OPERATION_IN_PROGRESS) { sdcard_poll(); } while (sdcard_poll() == 0); diff --git a/src/main/target/system_stm32f4xx.c b/src/main/target/system_stm32f4xx.c index be9b27ec3bb..5426503c25d 100644 --- a/src/main/target/system_stm32f4xx.c +++ b/src/main/target/system_stm32f4xx.c @@ -733,7 +733,7 @@ void SetSysClock(void) RCC->CFGR |= RCC_CFGR_SW_PLL; /* Wait till the main PLL is used as system clock source */ - while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL); + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL) { } } From 67974ef9ad4929a49e10efb2dca70c8405b07a51 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 10 Aug 2020 08:15:31 +0100 Subject: [PATCH 158/248] [BUILD] Fix linker errors when building with -O0 Build didn't fail with -Os or -O2 due to dead code elimination. Otherwise there were some undefined symbols when USE_OSD or USE_RX_NRF24 were not defined. --- src/main/drivers/rx_xn297.c | 2 ++ src/main/io/displayport_frsky_osd.c | 2 +- src/main/io/frsky_osd.c | 2 +- src/main/io/osd_common.c | 4 ++++ 4 files changed, 8 insertions(+), 2 deletions(-) diff --git a/src/main/drivers/rx_xn297.c b/src/main/drivers/rx_xn297.c index dccf39ba211..8a182b47b28 100644 --- a/src/main/drivers/rx_xn297.c +++ b/src/main/drivers/rx_xn297.c @@ -25,6 +25,7 @@ #include "rx_nrf24l01.h" #include "common/crc.h" +#if defined(USE_RX_NRF24) static const uint8_t xn297_data_scramble[30] = { 0xbc, 0xe5, 0x66, 0x0d, 0xae, 0x8c, 0x88, 0x12, @@ -88,3 +89,4 @@ uint8_t XN297_WritePayload(uint8_t *data, int len, const uint8_t *rxAddr) return NRF24L01_WritePayload(packet, RX_TX_ADDR_LEN + len + 2); } +#endif diff --git a/src/main/io/displayport_frsky_osd.c b/src/main/io/displayport_frsky_osd.c index b3571b85224..127ac449a89 100644 --- a/src/main/io/displayport_frsky_osd.c +++ b/src/main/io/displayport_frsky_osd.c @@ -20,7 +20,7 @@ #include "platform.h" -#if defined(USE_FRSKYOSD) +#if defined(USE_OSD) && defined(USE_FRSKYOSD) #include "common/maths.h" #include "common/utils.h" diff --git a/src/main/io/frsky_osd.c b/src/main/io/frsky_osd.c index 7486e1efbfa..a96453c01b7 100644 --- a/src/main/io/frsky_osd.c +++ b/src/main/io/frsky_osd.c @@ -4,7 +4,7 @@ #include "platform.h" -#if defined(USE_FRSKYOSD) +#if defined(USE_OSD) && defined(USE_FRSKYOSD) #include "common/crc.h" #include "common/log.h" diff --git a/src/main/io/osd_common.c b/src/main/io/osd_common.c index f5453f4ec64..c7975652650 100644 --- a/src/main/io/osd_common.c +++ b/src/main/io/osd_common.c @@ -36,6 +36,8 @@ #include "io/osd_common.h" #include "io/osd_grid.h" +#if defined(USE_OSD) + #define CANVAS_DEFAULT_GRID_ELEMENT_WIDTH OSD_CHAR_WIDTH #define CANVAS_DEFAULT_GRID_ELEMENT_HEIGHT OSD_CHAR_HEIGHT @@ -148,3 +150,5 @@ void osdDrawSidebars(displayPort_t *display, displayCanvas_t *canvas) #endif osdGridDrawSidebars(display); } + +#endif From 77e3040523b47200e9182388adc5bca26df98cfb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 10 Aug 2020 08:18:49 +0100 Subject: [PATCH 159/248] [F4] Remove invalid UTF-8 from system_stm32f4xx.c --- src/main/target/system_stm32f4xx.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/target/system_stm32f4xx.c b/src/main/target/system_stm32f4xx.c index 5426503c25d..7c50bbf879b 100644 --- a/src/main/target/system_stm32f4xx.c +++ b/src/main/target/system_stm32f4xx.c @@ -352,9 +352,9 @@ uint32_t hse_value = HSE_VALUE; through STLINK MCO pin of STM32F103 microcontroller. The frequency cannot be changed and is fixed at 8 MHz. Hardware configuration needed for Nucleo Board: - – SB54, SB55 OFF - – R35 removed - – SB16, SB50 ON */ + - SB54, SB55 OFF + - R35 removed + - SB16, SB50 ON */ /* #define USE_HSE_BYPASS */ #if defined(USE_HSE_BYPASS) From bd490a52f358592ac6a1e4cfdf2f302e5eb772d6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 10 Aug 2020 10:43:05 +0100 Subject: [PATCH 160/248] [CMAKE] Add support for having targets that are not part of the release Add a SKIP_RELEASES target argument --- cmake/main.cmake | 24 +++++++++++++++++++- cmake/stm32.cmake | 2 +- cmake/stm32f7.cmake | 3 ++- cmake/svd.cmake | 4 ++-- src/main/target/ALIENFLIGHTF3/CMakeLists.txt | 1 + src/main/target/ALIENFLIGHTF4/CMakeLists.txt | 1 + src/main/target/ANYFCM7/CMakeLists.txt | 1 + src/main/target/CHEBUZZF3/CMakeLists.txt | 1 + src/main/target/COLIBRI_RACE/CMakeLists.txt | 1 + src/main/target/FISHDRONEF4/CMakeLists.txt | 2 +- src/main/target/KISSFC/CMakeLists.txt | 1 + src/main/target/KROOZX/CMakeLists.txt | 1 + src/main/target/OMNIBUS/CMakeLists.txt | 2 +- src/main/target/SPEEDYBEEF4/CMakeLists.txt | 4 ++-- src/main/target/SPRACINGF3NEO/CMakeLists.txt | 1 + src/main/target/YUPIF4/CMakeLists.txt | 3 +++ 16 files changed, 43 insertions(+), 9 deletions(-) create mode 100644 src/main/target/ALIENFLIGHTF3/CMakeLists.txt create mode 100644 src/main/target/ALIENFLIGHTF4/CMakeLists.txt create mode 100644 src/main/target/ANYFCM7/CMakeLists.txt create mode 100644 src/main/target/CHEBUZZF3/CMakeLists.txt create mode 100644 src/main/target/COLIBRI_RACE/CMakeLists.txt create mode 100644 src/main/target/KISSFC/CMakeLists.txt create mode 100644 src/main/target/KROOZX/CMakeLists.txt create mode 100644 src/main/target/SPRACINGF3NEO/CMakeLists.txt create mode 100644 src/main/target/YUPIF4/CMakeLists.txt diff --git a/cmake/main.cmake b/cmake/main.cmake index b5f43099ed4..ccb1c1f51ed 100644 --- a/cmake/main.cmake +++ b/cmake/main.cmake @@ -65,6 +65,11 @@ function(setup_firmware_target exe name) set_property(GLOBAL PROPERTY VALID_TARGETS "${targets}") setup_openocd(${exe} ${name}) setup_svd(${exe} ${name}) + + cmake_parse_arguments(args "SKIP_RELEASES" "" "" ${ARGN}) + if(args_SKIP_RELEASES) + set_target_properties(${exe} ${name} PROPERTIES SKIP_RELEASES ON) + endif() endfunction() function(exclude_from_all target) @@ -77,11 +82,28 @@ endfunction() function(collect_targets) get_property(targets GLOBAL PROPERTY VALID_TARGETS) list(SORT targets) + set(release_targets) + foreach(target ${targets}) + get_target_property(skip_releases ${target} SKIP_RELEASES) + if(NOT skip_releases) + list(APPEND release_targets ${target}) + endif() + endforeach() + list(JOIN targets " " target_names) + list(JOIN release_targets " " release_targets_names) + set(list_target_name "targets") add_custom_target(${list_target_name} - COMMAND cmake -E echo "Valid targets: ${target_names}") + COMMAND ${CMAKE_COMMAND} -E echo "Valid targets: ${target_names}" + COMMAND ${CMAKE_COMMAND} -E echo "Release targets: ${release_targets_names}" + ) exclude_from_all(${list_target_name}) + set(release_target_name "release") + add_custom_target(${release_target_name} + ${CMAKE_COMMAND} -E true + DEPENDS ${release_targets} + ) list(LENGTH targets target_count) message("-- ${target_count} targets found for toolchain ${TOOLCHAIN}") endfunction() diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake index 46c47f74de9..38df6b36491 100644 --- a/cmake/stm32.cmake +++ b/cmake/stm32.cmake @@ -378,7 +378,7 @@ function(target_stm32) set_property(TARGET ${main_target_name} PROPERTY OPENOCD_DEFAULT_INTERFACE stlink) set_property(TARGET ${main_target_name} PROPERTY SVD ${args_SVD}) - setup_firmware_target(${main_target_name} ${name}) + setup_firmware_target(${main_target_name} ${name} ${ARGN}) if(args_BOOTLOADER) # Bootloader for the target diff --git a/cmake/stm32f7.cmake b/cmake/stm32f7.cmake index 1ce5d8c459e..8eeae97eb2d 100644 --- a/cmake/stm32f7.cmake +++ b/cmake/stm32f7.cmake @@ -106,6 +106,7 @@ endfunction() macro(define_target_stm32f7 subfamily size) function(target_stm32f7${subfamily}x${size} name) + set(func_ARGV ARGV) string(TOUPPER ${size} upper_size) get_stm32_flash_size(flash_size ${size}) set(definitions @@ -119,7 +120,7 @@ macro(define_target_stm32f7 subfamily size) STARTUP startup_stm32f7${subfamily}xx.s COMPILE_DEFINITIONS ${definitions} LINKER_SCRIPT stm32_flash_f7${subfamily}x${size} - ${ARGN} + ${${func_ARGV}} ) endfunction() endmacro() diff --git a/cmake/svd.cmake b/cmake/svd.cmake index d6efdc783b6..fd9b24348a2 100644 --- a/cmake/svd.cmake +++ b/cmake/svd.cmake @@ -9,8 +9,8 @@ function(setup_svd target_exe target_name) ) else() add_custom_target(${svd_target_name} - cmake -E echo "target ${target_name} does not declare an SVD filename" - COMMAND cmake -E false) + ${CMAKE_COMMAND} -E echo "target ${target_name} does not declare an SVD filename" + COMMAND ${CMAKE_COMMAND} -E false) endif() exclude_from_all(${svd_target_name}) endfunction() \ No newline at end of file diff --git a/src/main/target/ALIENFLIGHTF3/CMakeLists.txt b/src/main/target/ALIENFLIGHTF3/CMakeLists.txt new file mode 100644 index 00000000000..3932036a292 --- /dev/null +++ b/src/main/target/ALIENFLIGHTF3/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f303xc(ALIENFLIGHTF3 SKIP_RELEASES) \ No newline at end of file diff --git a/src/main/target/ALIENFLIGHTF4/CMakeLists.txt b/src/main/target/ALIENFLIGHTF4/CMakeLists.txt new file mode 100644 index 00000000000..dd707d192e1 --- /dev/null +++ b/src/main/target/ALIENFLIGHTF4/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405xg(ALIENFLIGHTF4 SKIP_RELEASES) \ No newline at end of file diff --git a/src/main/target/ANYFCM7/CMakeLists.txt b/src/main/target/ANYFCM7/CMakeLists.txt new file mode 100644 index 00000000000..4fbeb706c88 --- /dev/null +++ b/src/main/target/ANYFCM7/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722xe(ANYFCM7 SKIP_RELEASES) \ No newline at end of file diff --git a/src/main/target/CHEBUZZF3/CMakeLists.txt b/src/main/target/CHEBUZZF3/CMakeLists.txt new file mode 100644 index 00000000000..7cc65c9a5f3 --- /dev/null +++ b/src/main/target/CHEBUZZF3/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f303xc(CHEBUZZF3 SKIP_RELEASES) \ No newline at end of file diff --git a/src/main/target/COLIBRI_RACE/CMakeLists.txt b/src/main/target/COLIBRI_RACE/CMakeLists.txt new file mode 100644 index 00000000000..11b63f73351 --- /dev/null +++ b/src/main/target/COLIBRI_RACE/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f303xc(COLIBRI_RACE SKIP_RELEASES) \ No newline at end of file diff --git a/src/main/target/FISHDRONEF4/CMakeLists.txt b/src/main/target/FISHDRONEF4/CMakeLists.txt index 1f431194d7d..df981344206 100644 --- a/src/main/target/FISHDRONEF4/CMakeLists.txt +++ b/src/main/target/FISHDRONEF4/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405xg(FISHDRONEF4) +target_stm32f405xg(FISHDRONEF4 SKIP_RELEASES) diff --git a/src/main/target/KISSFC/CMakeLists.txt b/src/main/target/KISSFC/CMakeLists.txt new file mode 100644 index 00000000000..928051ba27e --- /dev/null +++ b/src/main/target/KISSFC/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f303xc(KISSFC SKIP_RELEASES) \ No newline at end of file diff --git a/src/main/target/KROOZX/CMakeLists.txt b/src/main/target/KROOZX/CMakeLists.txt new file mode 100644 index 00000000000..212f7a99825 --- /dev/null +++ b/src/main/target/KROOZX/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f405xg(KROOZX HSE_MHZ 16 SKIP_RELEASES) \ No newline at end of file diff --git a/src/main/target/OMNIBUS/CMakeLists.txt b/src/main/target/OMNIBUS/CMakeLists.txt index 9b0d502da5b..2334d933afc 100644 --- a/src/main/target/OMNIBUS/CMakeLists.txt +++ b/src/main/target/OMNIBUS/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303xc(OMNIBUS) +target_stm32f303xc(OMNIBUS SKIP_RELEASES) diff --git a/src/main/target/SPEEDYBEEF4/CMakeLists.txt b/src/main/target/SPEEDYBEEF4/CMakeLists.txt index 1735fcb6c28..cf55f428316 100644 --- a/src/main/target/SPEEDYBEEF4/CMakeLists.txt +++ b/src/main/target/SPEEDYBEEF4/CMakeLists.txt @@ -1,3 +1,3 @@ target_stm32f405xg(SPEEDYBEEF4) -target_stm32f405xg(SPEEDYBEEF4_SFTSRL1) -target_stm32f405xg(SPEEDYBEEF4_SFTSRL2) +target_stm32f405xg(SPEEDYBEEF4_SFTSRL1 SKIP_RELEASES) +target_stm32f405xg(SPEEDYBEEF4_SFTSRL2 SKIP_RELEASES) diff --git a/src/main/target/SPRACINGF3NEO/CMakeLists.txt b/src/main/target/SPRACINGF3NEO/CMakeLists.txt new file mode 100644 index 00000000000..a8fd8e50a24 --- /dev/null +++ b/src/main/target/SPRACINGF3NEO/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f303xc(SPRACINGF3NEO SKIP_RELEASES) \ No newline at end of file diff --git a/src/main/target/YUPIF4/CMakeLists.txt b/src/main/target/YUPIF4/CMakeLists.txt new file mode 100644 index 00000000000..4e64e13cd15 --- /dev/null +++ b/src/main/target/YUPIF4/CMakeLists.txt @@ -0,0 +1,3 @@ +target_stm32f405xg(YUPIF4 SKIP_RELEASES) +target_stm32f405xg(YUPIF4MINI SKIP_RELEASES) +target_stm32f405xg(YUPIF4R2 SKIP_RELEASES) \ No newline at end of file From 8f62efb43bf785ec00632243f5a9381b80275677 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 10 Aug 2020 11:13:29 +0100 Subject: [PATCH 161/248] [CMAKE] Cleanup semihosting support --- cmake/stm32.cmake | 23 +---------------------- 1 file changed, 1 insertion(+), 22 deletions(-) diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake index 38df6b36491..dada98b34d9 100644 --- a/cmake/stm32.cmake +++ b/cmake/stm32.cmake @@ -83,34 +83,13 @@ set(STM32_COMPILE_OPTIONS -fno-common ) -#if(SEMIHOSTING) -# set(SEMIHOSTING_DEFINITIONS "SEMIHOSTING") -# set(SEMIHOSTING_LDFLAGS -# --specs=rdimon.specs -# -lc -# -lrdimon -# ) -#else() -# set(SYS) -#endif() -#ifneq ($(SEMIHOSTING),) -#SEMIHOSTING_CFLAGS = -DSEMIHOSTING -#SEMIHOSTING_LDFLAGS = --specs=rdimon.specs -lc -lrdimon -#SYSLIB := -#else -#SEMIHOSTING_LDFLAGS = -#SEMIHOSTING_CFLAGS = -#SYSLIB := -lnosys -#endif - set(STM32_LINK_LIBRARIES -lm -lc ) if(SEMIHOSTING) - # TODO: Is -lc needed again here due to library order or can it be deleted? - list(APPEND STM32_LINK_LIBRARIES --specs=rdimon.specs -lc -lrdimon) + list(APPEND STM32_LINK_LIBRARIES --specs=rdimon.specs -lrdimon) list(APPEND STM32_DEFINITIONS SEMIHOSTING) else() list(APPEND STM32_LINK_LIBRARIES -lnosys) From 15777844acfbd82e2027b4758db82862f690ee66 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Wed, 12 Aug 2020 22:55:12 +0100 Subject: [PATCH 162/248] [CMAKE] Allow running tests from the main source build When no alternative toolchain is provided, we explicitely include the src/tests directory, so the check target (which builds and runs tests) is available from a main source build without having to build specifically the src/tests directory --- CMakeLists.txt | 14 ++++++++++---- cmake/main.cmake | 5 +++++ cmake/stm32.cmake | 4 +++- src/test/CMakeLists.txt | 1 - 4 files changed, 18 insertions(+), 6 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 781c0726532..adda4a079f2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,17 +1,23 @@ cmake_minimum_required(VERSION 3.17) -set(TOOLCHAIN_OPTIONS "arm-none-eabi") +set(TOOLCHAIN_OPTIONS none arm-none-eabi) set(TOOLCHAIN "arm-none-eabi" CACHE STRING "Toolchain to use. Available: ${TOOLCHAIN_OPTIONS}") set_property(CACHE TOOLCHAIN PROPERTY STRINGS ${TOOLCHAIN_OPTIONS}) +if("" STREQUAL TOOLCHAIN) + set(TOOLCHAIN none) +endif() if (NOT ${TOOLCHAIN} IN_LIST TOOLCHAIN_OPTIONS) - message(FATAL_ERROR "Invalid toolchain ${TOOLCHAIN}") + message(FATAL_ERROR "Invalid toolchain ${TOOLCHAIN}. Valid options are: ${TOOLCHAIN_OPTIONS}") endif() -set(CMAKE_TOOLCHAIN_FILE "${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}.cmake") +if(TOOLCHAIN STREQUAL none) + add_subdirectory(src/test) +else() + set(CMAKE_TOOLCHAIN_FILE "${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}.cmake") +endif() if(CMAKE_BUILD_TYPE STREQUAL "Release" OR CMAKE_BUILD_TYPE STREQUAL "RelWithDebInfo") set(IS_RELEASE_BUILD ON) - set(CMAKE_INTERPROCEDURAL_OPTIMIZATION ON) endif() project(INAV VERSION 2.5.0) diff --git a/cmake/main.cmake b/cmake/main.cmake index ccb1c1f51ed..d61783655c3 100644 --- a/cmake/main.cmake +++ b/cmake/main.cmake @@ -55,6 +55,11 @@ function(setup_executable exe name) set_target_properties(${exe} PROPERTIES RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin" ) + if(IS_RELEASE_BUILD) + set_target_properties(${exe} PROPERTIES + INTERPROCEDURAL_OPTIMIZATION ON + ) + endif() endfunction() function(setup_firmware_target exe name) diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake index dada98b34d9..23fb723333b 100644 --- a/cmake/stm32.cmake +++ b/cmake/stm32.cmake @@ -1,4 +1,3 @@ -include(arm-none-eabi) include(stm32-bootloader) include(stm32f3) include(stm32f4) @@ -267,6 +266,9 @@ function(add_stm32_executable) endfunction() function(target_stm32) + if(NOT arm-none-eabi STREQUAL TOOLCHAIN) + return() + endif() # Parse keyword arguments cmake_parse_arguments( args diff --git a/src/test/CMakeLists.txt b/src/test/CMakeLists.txt index 2c9adc21d89..4a659d0bc2f 100644 --- a/src/test/CMakeLists.txt +++ b/src/test/CMakeLists.txt @@ -13,5 +13,4 @@ include(cmake/gtest.cmake) enable_testing() include(GoogleTest) -#add_subdirectory(googletest) add_subdirectory(unit) From 7575cd44e83e676e7cdc0bfd2745beadf68294ba Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Fri, 14 Aug 2020 22:48:35 +0100 Subject: [PATCH 163/248] [CMAKE] Use GetGitRevisionDescription.cmake to retrieve git rev This way the git revision is automatically regenerated when the revision changes without having to re-run cmake's configuration step. --- CMakeLists.txt | 13 +- cmake/GetGitRevisionDescription.cmake | 172 +++++++++++++++++++++++ cmake/GetGitRevisionDescription.cmake.in | 41 ++++++ cmake/main.cmake | 2 +- 4 files changed, 219 insertions(+), 9 deletions(-) create mode 100644 cmake/GetGitRevisionDescription.cmake create mode 100644 cmake/GetGitRevisionDescription.cmake.in diff --git a/CMakeLists.txt b/CMakeLists.txt index adda4a079f2..0f20309e19d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -22,7 +22,7 @@ endif() project(INAV VERSION 2.5.0) -ENABLE_LANGUAGE(ASM) +enable_language(ASM) set(CMAKE_C_STANDARD 99) set(CMAKE_C_EXTENSIONS ON) @@ -36,13 +36,6 @@ if (NOT RUBY_EXECUTABLE) message(FATAL_ERROR "Could not find ruby") endif() -execute_process(COMMAND git rev-parse --short HEAD - OUTPUT_STRIP_TRAILING_WHITESPACE - RESULT_VARIABLE NO_GIT_HASH - OUTPUT_VARIABLE GIT_SHORT_HASH) -if (NO_GIT_HASH) - message(FATAL_ERROR "Could not find git revision. Is git installed?") -endif() set(MAIN_DIR "${CMAKE_CURRENT_SOURCE_DIR}") set(MAIN_LIB_DIR "${CMAKE_CURRENT_SOURCE_DIR}/lib") @@ -52,6 +45,10 @@ set(SVD_DIR "${CMAKE_CURRENT_SOURCE_DIR}/dev/svd") list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake") +include(GetGitRevisionDescription) +get_git_head_revision(GIT_REFSPEC GIT_SHA1) +string(SUBSTRING ${GIT_SHA1} 0 8 GIT_REV) + set(FIRMWARE_VERSION ${PROJECT_VERSION}) option(WARNINGS_AS_ERRORS "Make all warnings into errors") diff --git a/cmake/GetGitRevisionDescription.cmake b/cmake/GetGitRevisionDescription.cmake new file mode 100644 index 00000000000..7b2c705ed54 --- /dev/null +++ b/cmake/GetGitRevisionDescription.cmake @@ -0,0 +1,172 @@ +# - Returns a version string from Git +# +# These functions force a re-configure on each git commit so that you can +# trust the values of the variables in your build system. +# +# get_git_head_revision( [ ...]) +# +# Returns the refspec and sha hash of the current head revision +# +# git_describe( [ ...]) +# +# Returns the results of git describe on the source tree, and adjusting +# the output so that it tests false if an error occurs. +# +# git_get_exact_tag( [ ...]) +# +# Returns the results of git describe --exact-match on the source tree, +# and adjusting the output so that it tests false if there was no exact +# matching tag. +# +# git_local_changes() +# +# Returns either "CLEAN" or "DIRTY" with respect to uncommitted changes. +# Uses the return code of "git diff-index --quiet HEAD --". +# Does not regard untracked files. +# +# Requires CMake 2.6 or newer (uses the 'function' command) +# +# Original Author: +# 2009-2010 Ryan Pavlik +# http://academic.cleardefinition.com +# Iowa State University HCI Graduate Program/VRAC +# +# Copyright Iowa State University 2009-2010. +# Distributed under the Boost Software License, Version 1.0. +# (See accompanying file LICENSE_1_0.txt or copy at +# http://www.boost.org/LICENSE_1_0.txt) + +if(__get_git_revision_description) + return() +endif() +set(__get_git_revision_description YES) + +# We must run the following at "include" time, not at function call time, +# to find the path to this module rather than the path to a calling list file +get_filename_component(_gitdescmoddir ${CMAKE_CURRENT_LIST_FILE} PATH) + +function(get_git_head_revision _refspecvar _hashvar) + set(GIT_PARENT_DIR "${CMAKE_CURRENT_SOURCE_DIR}") + set(GIT_DIR "${GIT_PARENT_DIR}/.git") + while(NOT EXISTS "${GIT_DIR}") # .git dir not found, search parent directories + set(GIT_PREVIOUS_PARENT "${GIT_PARENT_DIR}") + get_filename_component(GIT_PARENT_DIR ${GIT_PARENT_DIR} PATH) + if(GIT_PARENT_DIR STREQUAL GIT_PREVIOUS_PARENT) + # We have reached the root directory, we are not in git + set(${_refspecvar} "GITDIR-NOTFOUND" PARENT_SCOPE) + set(${_hashvar} "GITDIR-NOTFOUND" PARENT_SCOPE) + return() + endif() + set(GIT_DIR "${GIT_PARENT_DIR}/.git") + endwhile() + # check if this is a submodule + if(NOT IS_DIRECTORY ${GIT_DIR}) + file(READ ${GIT_DIR} submodule) + string(REGEX REPLACE "gitdir: (.*)\n$" "\\1" GIT_DIR_RELATIVE ${submodule}) + get_filename_component(SUBMODULE_DIR ${GIT_DIR} PATH) + get_filename_component(GIT_DIR ${SUBMODULE_DIR}/${GIT_DIR_RELATIVE} ABSOLUTE) + endif() + if(NOT IS_DIRECTORY "${GIT_DIR}") + file(READ ${GIT_DIR} worktree) + string(REGEX REPLACE "gitdir: (.*)worktrees(.*)\n$" "\\1" GIT_DIR ${worktree}) + endif() + set(GIT_DATA "${CMAKE_CURRENT_BINARY_DIR}/CMakeFiles/git-data") + if(NOT EXISTS "${GIT_DATA}") + file(MAKE_DIRECTORY "${GIT_DATA}") + endif() + + if(NOT EXISTS "${GIT_DIR}/HEAD") + return() + endif() + set(HEAD_FILE "${GIT_DATA}/HEAD") + configure_file("${GIT_DIR}/HEAD" "${HEAD_FILE}" COPYONLY) + + configure_file("${_gitdescmoddir}/GetGitRevisionDescription.cmake.in" + "${GIT_DATA}/grabRef.cmake" + @ONLY) + include("${GIT_DATA}/grabRef.cmake") + + set(${_refspecvar} "${HEAD_REF}" PARENT_SCOPE) + set(${_hashvar} "${HEAD_HASH}" PARENT_SCOPE) +endfunction() + +function(git_describe _var) + if(NOT GIT_FOUND) + find_package(Git QUIET) + endif() + get_git_head_revision(refspec hash) + if(NOT GIT_FOUND) + set(${_var} "GIT-NOTFOUND" PARENT_SCOPE) + return() + endif() + if(NOT hash) + set(${_var} "HEAD-HASH-NOTFOUND" PARENT_SCOPE) + return() + endif() + + # TODO sanitize + #if((${ARGN}" MATCHES "&&") OR + # (ARGN MATCHES "||") OR + # (ARGN MATCHES "\\;")) + # message("Please report the following error to the project!") + # message(FATAL_ERROR "Looks like someone's doing something nefarious with git_describe! Passed arguments ${ARGN}") + #endif() + + #message(STATUS "Arguments to execute_process: ${ARGN}") + + execute_process(COMMAND + "${GIT_EXECUTABLE}" + describe + ${hash} + ${ARGN} + WORKING_DIRECTORY + "${CMAKE_CURRENT_SOURCE_DIR}" + RESULT_VARIABLE + res + OUTPUT_VARIABLE + out + ERROR_QUIET + OUTPUT_STRIP_TRAILING_WHITESPACE) + if(NOT res EQUAL 0) + set(out "${out}-${res}-NOTFOUND") + endif() + + set(${_var} "${out}" PARENT_SCOPE) +endfunction() + +function(git_get_exact_tag _var) + git_describe(out --exact-match ${ARGN}) + set(${_var} "${out}" PARENT_SCOPE) +endfunction() + +function(git_local_changes _var) + if(NOT GIT_FOUND) + find_package(Git QUIET) + endif() + get_git_head_revision(refspec hash) + if(NOT GIT_FOUND) + set(${_var} "GIT-NOTFOUND" PARENT_SCOPE) + return() + endif() + if(NOT hash) + set(${_var} "HEAD-HASH-NOTFOUND" PARENT_SCOPE) + return() + endif() + + execute_process(COMMAND + "${GIT_EXECUTABLE}" + diff-index --quiet HEAD -- + WORKING_DIRECTORY + "${CMAKE_CURRENT_SOURCE_DIR}" + RESULT_VARIABLE + res + OUTPUT_VARIABLE + out + ERROR_QUIET + OUTPUT_STRIP_TRAILING_WHITESPACE) + if(res EQUAL 0) + set(${_var} "CLEAN" PARENT_SCOPE) + else() + set(${_var} "DIRTY" PARENT_SCOPE) + endif() +endfunction() diff --git a/cmake/GetGitRevisionDescription.cmake.in b/cmake/GetGitRevisionDescription.cmake.in new file mode 100644 index 00000000000..6d8b708efe5 --- /dev/null +++ b/cmake/GetGitRevisionDescription.cmake.in @@ -0,0 +1,41 @@ +# +# Internal file for GetGitRevisionDescription.cmake +# +# Requires CMake 2.6 or newer (uses the 'function' command) +# +# Original Author: +# 2009-2010 Ryan Pavlik +# http://academic.cleardefinition.com +# Iowa State University HCI Graduate Program/VRAC +# +# Copyright Iowa State University 2009-2010. +# Distributed under the Boost Software License, Version 1.0. +# (See accompanying file LICENSE_1_0.txt or copy at +# http://www.boost.org/LICENSE_1_0.txt) + +set(HEAD_HASH) + +file(READ "@HEAD_FILE@" HEAD_CONTENTS LIMIT 1024) + +string(STRIP "${HEAD_CONTENTS}" HEAD_CONTENTS) +if(HEAD_CONTENTS MATCHES "ref") + # named branch + string(REPLACE "ref: " "" HEAD_REF "${HEAD_CONTENTS}") + if(EXISTS "@GIT_DIR@/${HEAD_REF}") + configure_file("@GIT_DIR@/${HEAD_REF}" "@GIT_DATA@/head-ref" COPYONLY) + else() + configure_file("@GIT_DIR@/packed-refs" "@GIT_DATA@/packed-refs" COPYONLY) + file(READ "@GIT_DATA@/packed-refs" PACKED_REFS) + if(${PACKED_REFS} MATCHES "([0-9a-z]*) ${HEAD_REF}") + set(HEAD_HASH "${CMAKE_MATCH_1}") + endif() + endif() +else() + # detached HEAD + configure_file("@GIT_DIR@/HEAD" "@GIT_DATA@/head-ref" COPYONLY) +endif() + +if(NOT HEAD_HASH) + file(READ "@GIT_DATA@/head-ref" HEAD_HASH LIMIT 1024) + string(STRIP "${HEAD_HASH}" HEAD_HASH) +endif() diff --git a/cmake/main.cmake b/cmake/main.cmake index d61783655c3..ef297cdda8f 100644 --- a/cmake/main.cmake +++ b/cmake/main.cmake @@ -6,7 +6,7 @@ set(MAIN_INCLUDE_DIRS set(MAIN_DEFINITIONS __FORKNAME__=inav - __REVISION__="${GIT_SHORT_HASH}" + __REVISION__="${GIT_REV}" ) set(MAIN_COMPILE_OPTIONS From e689bbef955fdda2ff1712ec70e95646d5028d8b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 24 Aug 2020 12:24:29 +0100 Subject: [PATCH 164/248] [CMAKE] Add support for automatically downloading the arm compiler --- CMakeLists.txt | 18 +++-- cmake/arm-none-eabi-checks.cmake | 110 +++++++++++++++++++++++++++++++ cmake/arm-none-eabi.cmake | 35 +++------- cmake/gcc.cmake | 34 ++++++++++ cmake/settings.cmake | 2 +- cmake/stm32.cmake | 4 +- 6 files changed, 167 insertions(+), 36 deletions(-) create mode 100644 cmake/arm-none-eabi-checks.cmake create mode 100644 cmake/gcc.cmake diff --git a/CMakeLists.txt b/CMakeLists.txt index 0f20309e19d..54679be4389 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,5 +1,15 @@ cmake_minimum_required(VERSION 3.17) +list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake") + +set(MAIN_DIR "${CMAKE_CURRENT_SOURCE_DIR}") +set(MAIN_LIB_DIR "${CMAKE_CURRENT_SOURCE_DIR}/lib") +set(MAIN_UTILS_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src/utils") +set(MAIN_SRC_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src/main") +set(SVD_DIR "${CMAKE_CURRENT_SOURCE_DIR}/dev/svd") +set(DOWNLOADS_DIR "${MAIN_DIR}/downloads") +set(TOOLS_DIR "${MAIN_DIR}/tools") + set(TOOLCHAIN_OPTIONS none arm-none-eabi) set(TOOLCHAIN "arm-none-eabi" CACHE STRING "Toolchain to use. Available: ${TOOLCHAIN_OPTIONS}") set_property(CACHE TOOLCHAIN PROPERTY STRINGS ${TOOLCHAIN_OPTIONS}) @@ -14,6 +24,7 @@ if(TOOLCHAIN STREQUAL none) add_subdirectory(src/test) else() set(CMAKE_TOOLCHAIN_FILE "${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}.cmake") + include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}-checks.cmake") endif() if(CMAKE_BUILD_TYPE STREQUAL "Release" OR CMAKE_BUILD_TYPE STREQUAL "RelWithDebInfo") @@ -37,13 +48,6 @@ if (NOT RUBY_EXECUTABLE) endif() -set(MAIN_DIR "${CMAKE_CURRENT_SOURCE_DIR}") -set(MAIN_LIB_DIR "${CMAKE_CURRENT_SOURCE_DIR}/lib") -set(MAIN_UTILS_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src/utils") -set(MAIN_SRC_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src/main") -set(SVD_DIR "${CMAKE_CURRENT_SOURCE_DIR}/dev/svd") - -list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake") include(GetGitRevisionDescription) get_git_head_revision(GIT_REFSPEC GIT_SHA1) diff --git a/cmake/arm-none-eabi-checks.cmake b/cmake/arm-none-eabi-checks.cmake new file mode 100644 index 00000000000..2faf08bc004 --- /dev/null +++ b/cmake/arm-none-eabi-checks.cmake @@ -0,0 +1,110 @@ +include(gcc) +set(arm_none_eabi_triplet "arm-none-eabi") + +# Keep version in sync with the distribution files below +set(arm_none_eabi_gcc_version "9.2.1") +set(arm_none_eabi_base_url "https://developer.arm.com/-/media/Files/downloads/gnu-rm/9-2019q4/gcc-arm-none-eabi-9-2019-q4-major") +# suffix and sha1 +set(arm_none_eabi_win32 "win32.zip" 60f364ecf2e8717a58d352db95b388eee508b727) +set(arm_none_eabi_linux_amd64 "x86_64-linux.tar.bz2" 3829ff61b2601c6cf061a5a275c2538a96a8d521) +set(arm_none_eabi_linux_aarch64 "aarch64-linux.tar.bz2" fdb6fe7058927ad897f63d2d245f825a9587a1c5) +set(arm_none_eabi_gcc_macos "mac.tar.bz2" 26fe33e0c25d9a2947c0373ea48c00ef46eacd58) + +function(arm_none_eabi_gcc_distname var) + string(REPLACE "/" ";" url_parts ${arm_none_eabi_base_url}) + list(LENGTH url_parts n) + math(EXPR last "${n} - 1") + list(GET url_parts ${last} basename) + set(${var} ${basename} PARENT_SCOPE) +endfunction() + +function(host_uname_machine var) + # We need to call uname -m manually, since at the point + # this file is included CMAKE_HOST_SYSTEM_PROCESSOR is + # empty because we haven't called project() yet. + execute_process(COMMAND uname -m + OUTPUT_STRIP_TRAILING_WHITESPACE + OUTPUT_VARIABLE machine) + + set(${var} ${machine} PARENT_SCOPE) +endfunction() + +function(arm_none_eabi_gcc_install) + set(dist "") + if(CMAKE_HOST_SYSTEM_NAME STREQUAL "Windows") + set(dist ${arm_none_eabi_win32}) + elseif(CMAKE_HOST_SYSTEM_NAME STREQUAL "Linux") + host_uname_machine(machine) + if(machine STREQUAL "x86_64") + set(dist ${arm_none_eabi_linux_amd64}) + elseif(machine STREQUAL "aarch64") + set(dist ${arm_none_eabi_linux_aarch64}) + else() + message("-- no precompiled ${arm_none_eabi_triplet} toolchain for machine ${machine}") + endif() + elseif(CMAKE_HOST_SYSTEM_NAME STREQUAL "Darwin") + set(dist ${arm_none_eabi_gcc_macos}) + endif() + + if(dist STREQUAL "") + message(FATAL_ERROR "could not install ${arm_none_eabi_triplet}-gcc automatically") + endif() + list(GET dist 0 dist_suffix) + list(GET dist 1 dist_sha1) + set(dist_url "${arm_none_eabi_base_url}-${dist_suffix}") + string(REPLACE "/" ";" url_parts ${dist_url}) + list(LENGTH url_parts n) + math(EXPR last "${n} - 1") + list(GET url_parts ${last} basename) + set(output "${DOWNLOADS_DIR}/${basename}") + message("-- downloading ${arm_none_eabi_triplet}-gcc ${arm_none_eabi_gcc_version} from ${dist_url}") + file(DOWNLOAD ${dist_url} ${output} + INACTIVITY_TIMEOUT 30 + STATUS status + SHOW_PROGRESS + EXPECTED_HASH SHA1=${dist_sha1} + TLS_VERIFY ON + ) + list(GET status 0 status_code) + if(NOT status_code EQUAL 0) + list(GET status 1 status_message) + message(FATAL_ERROR "error downloading ${basename}: ${status_message}") + endif() + message("-- extracting ${basename}") + execute_process(COMMAND ${CMAKE_COMMAND} -E make_directory ${TOOLS_DIR}) + execute_process(COMMAND ${CMAKE_COMMAND} -E tar xf ${output} + RESULT_VARIABLE status + WORKING_DIRECTORY ${TOOLS_DIR} + ) + if(NOT status EQUAL 0) + message(FATAL_ERROR "error extracting ${basename}: ${status}") + endif() +endfunction() + +function(arm_none_eabi_gcc_add_path) + arm_none_eabi_gcc_distname(dist_name) + set(gcc_path "${TOOLS_DIR}/${dist_name}/bin") + set(ENV{PATH} "$ENV{PATH}:${gcc_path}") +endfunction() + +function(arm_none_eabi_gcc_check) + gcc_get_version(version + TRIPLET ${arm_none_eabi_triplet} + PROGRAM_NAME prog + PROGRAM_PATH prog_path + ) + if(NOT version) + message("-- could not find ${prog}") + arm_none_eabi_gcc_install() + return() + endif() + message("-- found ${prog} ${version} at ${prog_path}") + if(NOT arm_none_eabi_gcc_version STREQUAL version) + message("-- expecting ${prog} version ${arm_none_eabi_gcc_version}, but got version ${version} instead") + arm_none_eabi_gcc_install() + return() + endif() +endfunction() + +arm_none_eabi_gcc_add_path() +arm_none_eabi_gcc_check() \ No newline at end of file diff --git a/cmake/arm-none-eabi.cmake b/cmake/arm-none-eabi.cmake index e86cb6a5076..eb7ddebabf7 100644 --- a/cmake/arm-none-eabi.cmake +++ b/cmake/arm-none-eabi.cmake @@ -6,35 +6,16 @@ if(WIN32) endif() set(TARGET_TRIPLET "arm-none-eabi") -set(gcc "${TARGET_TRIPLET}-gcc${TOOL_EXECUTABLE_SUFFIX}") - -find_program(GCC "${gcc}") -if (NOT GCC) - message(FATAL_ERROR "Could not find ${gcc}") -endif() - -set(ARM_NONE_EABI_GCC_VERSION 9.2.1) - -execute_process(COMMAND "${GCC}" -dumpversion - OUTPUT_STRIP_TRAILING_WHITESPACE - OUTPUT_VARIABLE GCC_VERSION) - -if (NOT ${ARM_NONE_EABI_GCC_VERSION} STREQUAL ${GCC_VERSION}) - # TODO: Show how to override on cmdline or install builtin compiler - message(FATAL_ERROR "Expecting gcc version ${ARM_NONE_EABI_GCC_VERSION}, but found ${GCC_VERSION}") -endif() - -get_filename_component(TOOLCHAIN_BIN_DIR "${GCC}" DIRECTORY) set(CMAKE_TRY_COMPILE_TARGET_TYPE STATIC_LIBRARY) -set(CMAKE_ASM_COMPILER "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-gcc${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "asm compiler") -set(CMAKE_C_COMPILER "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-gcc${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c compiler") -set(CMAKE_CXX_COMPILER "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-g++${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c++ compiler") -set(CMAKE_OBJCOPY "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-objcopy${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "objcopy tool") -set(CMAKE_OBJDUMP "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-objdump${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "objdump tool") -set(CMAKE_SIZE "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-size${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "size tool") -set(CMAKE_DEBUGGER "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-gdb${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "debugger") -set(CMAKE_CPPFILT "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-c++filt${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c++filt") +set(CMAKE_ASM_COMPILER "${TARGET_TRIPLET}-gcc${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "asm compiler") +set(CMAKE_C_COMPILER "${TARGET_TRIPLET}-gcc${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c compiler") +set(CMAKE_CXX_COMPILER "${TARGET_TRIPLET}-g++${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c++ compiler") +set(CMAKE_OBJCOPY "${TARGET_TRIPLET}-objcopy${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "objcopy tool") +set(CMAKE_OBJDUMP "${TARGET_TRIPLET}-objdump${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "objdump tool") +set(CMAKE_SIZE "${TARGET_TRIPLET}-size${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "size tool") +set(CMAKE_DEBUGGER "${TARGET_TRIPLET}-gdb${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "debugger") +set(CMAKE_CPPFILT "${TARGET_TRIPLET}-c++filt${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c++filt") set(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER) set(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY) set(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE ONLY) diff --git a/cmake/gcc.cmake b/cmake/gcc.cmake new file mode 100644 index 00000000000..cfe2ddf3dbc --- /dev/null +++ b/cmake/gcc.cmake @@ -0,0 +1,34 @@ +function(gcc_get_version var) + cmake_parse_arguments(args + "" + "TRIPLET;PROGRAM_NAME;PROGRAM_PATH" + "" + ${ARGN} + ) + set(prog "gcc") + if(args_TRIPLET) + set(prog "${args_TRIPLET}-${prog}") + endif() + if(args_PROGRAM_NAME) + set(${args_PROGRAM_NAME} ${prog} PARENT_SCOPE) + endif() + + find_program(gcc ${prog}) + if (NOT gcc) + set(${var} OFF PARENT_SCOPE) + endif() + + if(args_PROGRAM_PATH) + set(${args_PROGRAM_PATH} ${gcc} PARENT_SCOPE) + endif() + + execute_process(COMMAND "${gcc}" -dumpversion + OUTPUT_STRIP_TRAILING_WHITESPACE + OUTPUT_VARIABLE version) + + if("" STREQUAL version) + set(${var} OFF PARENT_SCOPE) + else() + set(${var} ${version} PARENT_SCOPE) + endif() +endfunction() diff --git a/cmake/settings.cmake b/cmake/settings.cmake index d3e3db8f3ad..17d48168b4f 100644 --- a/cmake/settings.cmake +++ b/cmake/settings.cmake @@ -18,7 +18,7 @@ function(enable_settings exe name) add_custom_command( OUTPUT ${dir}/${SETTINGS_GENERATED_H} ${dir}/${SETTINGS_GENERATED_C} COMMAND - ${CMAKE_COMMAND} -E env CFLAGS="${cflags}" TARGET=${name} + ${CMAKE_COMMAND} -E env CFLAGS="${cflags}" TARGET=${name} PATH=$ENV{PATH} ${RUBY_EXECUTABLE} ${SETTINGS_GENERATOR} ${MAIN_DIR} ${SETTINGS_FILE} -o "${dir}" DEPENDS ${SETTINGS_GENERATOR} ${SETTINGS_FILE} ) diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake index 23fb723333b..f028a3fdc29 100644 --- a/cmake/stm32.cmake +++ b/cmake/stm32.cmake @@ -192,13 +192,15 @@ endfunction() function(add_hex_target name exe hex) add_custom_target(${name} ALL + cmake -E env PATH=$ENV{PATH} ${CMAKE_OBJCOPY} -Oihex $ ${hex} BYPRODUCTS ${hex} ) endfunction() function(add_bin_target name exe bin) - add_custom_target(${name} ALL + add_custom_target(${name} + cmake -E env PATH=$ENV{PATH} ${CMAKE_OBJCOPY} -Obinary $ ${bin} BYPRODUCTS ${bin} ) From 9ac514c107deba896b5783e3f7a198a183cd23eb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 24 Aug 2020 12:38:25 +0100 Subject: [PATCH 165/248] [CMAKE] Run all CI jobs using CMake - Fix compilation on case sensitive filesystems - Fix case sensitive paths in F7 drivers - Fix warnings related to MSC redefinition - Fix invalid dual gyro definition in FOXEERF722V2 - Remove FURYF3, KFC32F3_INAV and SPRACINGF3EVO from releases - Always use usbd_storage_sd_spi.c for SDCARD + MSC - Add targets for SPEEDYBEEF7, FRSKYPILOT and FRSKY_ROVERF7 - Add BUILD_SUFFIX configure-time option - Add COMPILER_VERSION_CHECK boolean option defaulting to ON --- .github/workflows/ci.yml | 40 ++++------- CMakeLists.txt | 11 +-- cmake/arm-none-eabi-checks.cmake | 2 +- cmake/ci.cmake | 15 ++++ cmake/main.cmake | 31 ++++---- cmake/stm32.cmake | 15 ++-- cmake/stm32f3.cmake | 4 +- cmake/stm32f4.cmake | 6 +- cmake/stm32f7.cmake | 4 +- make/mcu/STM32F7.mk | 2 +- src/main/CMakeLists.txt | 4 ++ src/main/target/ANYFC/target.h | 4 -- src/main/target/CLRACINGF4AIR/target.h | 4 -- src/main/target/FF_F35_LIGHTNING/target.h | 4 -- src/main/target/FOXEERF722DUAL/target.c | 2 + src/main/target/FRSKYPILOT/CMakeLists.txt | 1 + src/main/target/FRSKY_ROVERF7/CMakeLists.txt | 1 + src/main/target/FURYF3/CMakeLists.txt | 4 +- src/main/target/KFC32F3_INAV/CMakeLists.txt | 2 +- src/main/target/MATEKF411/target.h | 4 -- src/main/target/MATEKF411SE/target.h | 4 -- src/main/target/SPEEDYBEEF7/CMakeLists.txt | 1 + src/main/target/SPRACINGF3EVO/CMakeLists.txt | 4 +- src/main/target/common.h | 1 - src/main/target/link/stm32_flash_F746.ld | 2 +- src/main/target/link/stm32_flash_F765xI.ld | 2 +- src/main/target/link/stm32_flash_F765xI_bl.ld | 2 +- .../target/link/stm32_flash_F765xI_for_bl.ld | 2 +- src/main/target/link/stm32_flash_F7x2.ld | 2 +- src/main/target/link/stm32_flash_F7x2_bl.ld | 2 +- .../target/link/stm32_flash_F7x2_for_bl.ld | 2 +- src/main/target/link/stm32_flash_F7x5xG.ld | 2 +- src/main/target/link/stm32_flash_F7x5xG_bl.ld | 2 +- .../target/link/stm32_flash_F7x5xG_for_bl.ld | 2 +- .../{stm32_flash_F7.ld => stm32_flash_f7.ld} | 8 +-- src/main/target/link/stm32_flash_f722xe_bl.ld | 2 +- .../target/link/stm32_flash_f722xe_for_bl.ld | 2 +- src/main/target/link/stm32_flash_f745xg.ld | 2 +- src/main/target/link/stm32_flash_f745xg_bl.ld | 2 +- .../target/link/stm32_flash_f745xg_for_bl.ld | 2 +- src/main/target/link/stm32_flash_f765xg.ld | 48 +++++++++++++ src/main/target/link/stm32_flash_f765xg_bl.ld | 50 +++++++++++++ .../target/link/stm32_flash_f765xg_for_bl.ld | 50 +++++++++++++ src/main/target/link/stm32_flash_f765xi.ld | 55 +++++++++++++++ src/main/target/link/stm32_flash_f765xi_bl.ld | 56 +++++++++++++++ .../target/link/stm32_flash_f765xi_for_bl.ld | 57 +++++++++++++++ ...sh_F7_split.ld => stm32_flash_f7_split.ld} | 6 +- src/utils/build-targets.sh | 70 ------------------- 48 files changed, 418 insertions(+), 182 deletions(-) create mode 100644 cmake/ci.cmake create mode 100644 src/main/target/FRSKYPILOT/CMakeLists.txt create mode 100644 src/main/target/FRSKY_ROVERF7/CMakeLists.txt create mode 100644 src/main/target/SPEEDYBEEF7/CMakeLists.txt rename src/main/target/link/{stm32_flash_F7.ld => stm32_flash_f7.ld} (98%) create mode 100644 src/main/target/link/stm32_flash_f765xg.ld create mode 100644 src/main/target/link/stm32_flash_f765xg_bl.ld create mode 100644 src/main/target/link/stm32_flash_f765xg_for_bl.ld create mode 100644 src/main/target/link/stm32_flash_f765xi.ld create mode 100644 src/main/target/link/stm32_flash_f765xi_bl.ld create mode 100644 src/main/target/link/stm32_flash_f765xi_for_bl.ld rename src/main/target/link/{stm32_flash_F7_split.ld => stm32_flash_f7_split.ld} (98%) delete mode 100755 src/utils/build-targets.sh diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 35bfbdd88e1..ef0254f7899 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -9,11 +9,12 @@ jobs: runs-on: ubuntu-18.04 strategy: matrix: - start: [0, 10, 20, 30, 40, 50, 60, 70, 80, 90, 100] - count: [10] + id: [0, 1, 2, 3, 4, 5, 6, 7, 8, 9] steps: - uses: actions/checkout@v2 + - name: Install dependencies + run: sudo apt-get update && sudo apt-get -y install ninja-build - name: Setup environment run: | # This is the hash of the commit for the PR @@ -25,44 +26,27 @@ jobs: # why we try github.event.pull_request.head.sha first COMMIT_ID=${COMMIT_ID:-${{ github.sha }}} BUILD_SUFFIX=ci-$(date '+%Y%m%d')-$(git rev-parse --short ${COMMIT_ID}) - echo "::set-env name=TARGETS::$(./src/utils/build-targets.sh -n -s ${{ matrix.start }} -c ${{ matrix.count }})" + VERSION=$(grep project CMakeLists.txt|awk -F VERSION '{ gsub(/^[ \t]+|[ \t\)]+$/, "", $2); print $2 }') echo "::set-env name=BUILD_SUFFIX::${BUILD_SUFFIX}" - echo "::set-env name=BUILD_NAME::inav-$(make print_version)-${BUILD_SUFFIX}" - echo "::set-env name=IS_LAST_JOB::$([ $(expr ${{ strategy.job-index }} + 1) = ${{ strategy.job-total }} ] && echo yes)" - - name: Ensure all targets will be tested - if: ${{ env.IS_LAST_JOB }} - run: | - UNTESTED=$(./src/utils/build-targets.sh -n -s $(expr ${{ matrix.start }} + ${{ matrix.count }}) -c 10000) - if ! [ -z "${UNTESTED}" ]; then - echo "Untested targets: ${UNTESTED}" >&2 - exit 1 - fi + echo "::set-env name=BUILD_NAME::inav-${VERSION}-${BUILD_SUFFIX}" - uses: actions/cache@v1 with: path: downloads - key: ${{ runner.os }}-downloads-${{ hashFiles('Makefile') }}-${{ hashFiles('**/make/*.mk')}} - - name: Install ARM toolchain - run: make arm_sdk_install - - name: Build targets (${{ matrix.start }}) - if: ${{ env.TARGETS }} - run: ./src/utils/build-targets.sh -s ${{ matrix.start }} -c ${{ matrix.count }} -S ${{ env.BUILD_SUFFIX }} + key: ${{ runner.os }}-downloads-${{ hashFiles('CMakeLists.txt') }}-${{ hashFiles('**/cmake/*')}} + - name: Build targets (${{ matrix.id }}) + run: mkdir -p build && cd build && cmake -DCI_JOB_INDEX=${{ matrix.id }} -DCI_JOB_COUNT=${{ strategy.job-total }} -DBUILD_SUFFIX=${{ env.BUILD_SUFFIX }} -G Ninja .. && ninja ci - name: Upload artifacts - if: ${{ env.TARGETS }} uses: actions/upload-artifact@v2-preview with: name: ${{ env.BUILD_NAME }}.zip - path: ./obj/dist/*.hex + path: ./build/*.hex test: needs: [build] runs-on: ubuntu-18.04 steps: - uses: actions/checkout@v2 - - uses: actions/cache@v1 - with: - path: downloads - key: ${{ runner.os }}-downloads-${{ hashFiles('Makefile') }}-${{ hashFiles('**/make/*.mk')}} - - name: Install ARM toolchain - run: make arm_sdk_install + - name: Install dependencies + run: sudo apt-get update && sudo apt-get -y install ninja-build - name: Run Tests - run: make test + run: mkdir -p build && cd build && cmake -DTOOLCHAIN=none -G Ninja .. && ninja check diff --git a/CMakeLists.txt b/CMakeLists.txt index 54679be4389..53aff1c71b4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -20,6 +20,8 @@ if (NOT ${TOOLCHAIN} IN_LIST TOOLCHAIN_OPTIONS) message(FATAL_ERROR "Invalid toolchain ${TOOLCHAIN}. Valid options are: ${TOOLCHAIN_OPTIONS}") endif() +option(COMPILER_VERSION_CHECK "Ensure the compiler matches the expected version" ON) + if(TOOLCHAIN STREQUAL none) add_subdirectory(src/test) else() @@ -27,10 +29,6 @@ else() include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}-checks.cmake") endif() -if(CMAKE_BUILD_TYPE STREQUAL "Release" OR CMAKE_BUILD_TYPE STREQUAL "RelWithDebInfo") - set(IS_RELEASE_BUILD ON) -endif() - project(INAV VERSION 2.5.0) enable_language(ASM) @@ -47,7 +45,9 @@ if (NOT RUBY_EXECUTABLE) message(FATAL_ERROR "Could not find ruby") endif() - +if(CMAKE_BUILD_TYPE STREQUAL "Release" OR CMAKE_BUILD_TYPE STREQUAL "RelWithDebInfo") + set(IS_RELEASE_BUILD ON) +endif() include(GetGitRevisionDescription) get_git_head_revision(GIT_REFSPEC GIT_SHA1) @@ -69,3 +69,4 @@ add_subdirectory(src) collect_targets() message("-- Build type: ${CMAKE_BUILD_TYPE}") +include(ci) diff --git a/cmake/arm-none-eabi-checks.cmake b/cmake/arm-none-eabi-checks.cmake index 2faf08bc004..ac13bc4481b 100644 --- a/cmake/arm-none-eabi-checks.cmake +++ b/cmake/arm-none-eabi-checks.cmake @@ -99,7 +99,7 @@ function(arm_none_eabi_gcc_check) return() endif() message("-- found ${prog} ${version} at ${prog_path}") - if(NOT arm_none_eabi_gcc_version STREQUAL version) + if(COMPILER_VERSION_CHECK AND NOT arm_none_eabi_gcc_version STREQUAL version) message("-- expecting ${prog} version ${arm_none_eabi_gcc_version}, but got version ${version} instead") arm_none_eabi_gcc_install() return() diff --git a/cmake/ci.cmake b/cmake/ci.cmake new file mode 100644 index 00000000000..c04ab6188c4 --- /dev/null +++ b/cmake/ci.cmake @@ -0,0 +1,15 @@ +if(DEFINED CI_JOB_INDEX AND DEFINED CI_JOB_COUNT) + math(EXPR job_name "${CI_JOB_INDEX}+1") + message("-- configuring CI job ${job_name}/${CI_JOB_COUNT}") + get_property(targets GLOBAL PROPERTY RELEASE_TARGETS) + list(LENGTH targets count) + math(EXPR per_job "(${count}+${CI_JOB_COUNT}-1)/${CI_JOB_COUNT}") + message("-- ${per_job} targets per job") + math(EXPR start "${CI_JOB_INDEX}*${per_job}") + list(SUBLIST targets ${start} ${per_job} ci_targets) + message("-- will build targets: ${ci_targets}") + add_custom_target(ci + ${CMAKE_COMMAND} -E true + DEPENDS ${ci_targets} +) +endif() \ No newline at end of file diff --git a/cmake/main.cmake b/cmake/main.cmake index ef297cdda8f..0367e797bd9 100644 --- a/cmake/main.cmake +++ b/cmake/main.cmake @@ -23,21 +23,26 @@ macro(main_sources var) # list-var src-1...src-n list(TRANSFORM ${var} PREPEND "${MAIN_SRC_DIR}/") endmacro() -macro(exclude_basenames) # list-var excludes-var - set(_filtered "") - foreach(item ${${ARGV0}}) +function(exclude_basenames var excludes) + set(filtered "") + foreach(item ${${var}}) get_filename_component(basename ${item} NAME) - if (NOT ${basename} IN_LIST ${ARGV1}) - list(APPEND _filtered ${item}) + if (NOT ${basename} IN_LIST excludes) + list(APPEND filtered ${item}) endif() endforeach() - set(${ARGV0} ${_filtered}) -endmacro() + set(${var} ${filtered} PARENT_SCOPE) +endfunction() -macro(glob_except) # var-name pattern excludes-var - file(GLOB ${ARGV0} ${ARGV1}) - exclude_basenames(${ARGV0} ${ARGV2}) -endmacro() +function(glob_except var pattern excludes) + file(GLOB results ${pattern}) + list(LENGTH results count) + if(count EQUAL 0) + message(FATAL_ERROR "glob with pattern '${pattern}' returned no results") + endif() + exclude_basenames(results "${excludes}") + set(${var} ${results} PARENT_SCOPE) +endfunction() function(get_generated_files_dir output target_name) set(${output} ${CMAKE_CURRENT_BINARY_DIR}/${target_name} PARENT_SCOPE) @@ -97,6 +102,7 @@ function(collect_targets) list(JOIN targets " " target_names) list(JOIN release_targets " " release_targets_names) + set_property(GLOBAL PROPERTY RELEASE_TARGETS ${release_targets}) set(list_target_name "targets") add_custom_target(${list_target_name} @@ -110,5 +116,6 @@ function(collect_targets) DEPENDS ${release_targets} ) list(LENGTH targets target_count) - message("-- ${target_count} targets found for toolchain ${TOOLCHAIN}") + list(LENGTH release_targets release_target_count) + message("-- ${target_count} targets (${release_target_count} for release) found for toolchain ${TOOLCHAIN}") endfunction() diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake index f028a3fdc29..5bec5463d70 100644 --- a/cmake/stm32.cmake +++ b/cmake/stm32.cmake @@ -58,14 +58,10 @@ main_sources(STM32_MSC_FLASH_SRC msc/emfat_file.c ) -main_sources(STM32_MSC_SDCARD_SPI_SRC +main_sources(STM32_MSC_SDCARD_SRC msc/usbd_storage_sd_spi.c ) -main_sources(STM32_MSC_SDCARD_SDIO_SRC - msc/usbd_storage_sdio.c -) - set(STM32_INCLUDE_DIRS "${CMSIS_INCLUDE_DIR}" "${CMSIS_DSP_INCLUDE_DIR}" @@ -321,11 +317,7 @@ function(target_stm32) list(APPEND msc_sources ${STM32_MSC_FLASH_SRC}) endif() if (SDCARD IN_LIST features) - if (SDIO IN_LIST features) - list(APPEND msc_sources ${STM32_MSC_SDCARD_SDIO_SRC}) - else() - list(APPEND msc_sources ${STM32_MSC_SDCARD_SPI_SRC}) - endif() + list(APPEND msc_sources ${STM32_MSC_SDCARD_SRC}) endif() endif() @@ -340,6 +332,9 @@ function(target_stm32) string(TOLOWER ${PROJECT_NAME} lowercase_project_name) set(binary_name ${lowercase_project_name}_${FIRMWARE_VERSION}_${name}) + if(DEFINED BUILD_SUFFIX AND NOT "" STREQUAL "${BUILD_SUFFIX}") + set(binary_name "${binary_name}_${BUILD_SUFFIX}") + endif() # Main firmware add_stm32_executable( diff --git a/cmake/stm32f3.cmake b/cmake/stm32f3.cmake index 0e4dc764e38..debc4cbce56 100644 --- a/cmake/stm32f3.cmake +++ b/cmake/stm32f3.cmake @@ -11,8 +11,8 @@ set(STM32F3_STDPERIPH_SRC_EXCLUDES stm32f30x_crc.c stm32f30x_can.c ) -set(STM32F3_STDPERIPH_SRC_DIR "${STM32F3_STDPERIPH_DIR}/Src") -glob_except(STM32F3_STDPERIPH_SRC "${STM32F3_STDPERIPH_SRC_DIR}/*.c" STM32F3_STDPERIPH_SRC_EXCLUDES) +set(STM32F3_STDPERIPH_SRC_DIR "${STM32F3_STDPERIPH_DIR}/src") +glob_except(STM32F3_STDPERIPH_SRC "${STM32F3_STDPERIPH_SRC_DIR}/*.c" "${STM32F3_STDPERIPH_SRC_EXCLUDES}") main_sources(STM32F3_SRC diff --git a/cmake/stm32f4.cmake b/cmake/stm32f4.cmake index 8beb83e4de2..c1218c545de 100644 --- a/cmake/stm32f4.cmake +++ b/cmake/stm32f4.cmake @@ -29,8 +29,8 @@ set(STM32F4_STDPERIPH_SRC_EXCLUDES stm32f4xx_spdifrx.c ) -set(STM32F4_STDPERIPH_SRC_DIR "${STM32F4_STDPERIPH_DIR}/Src") -glob_except(STM32F4_STDPERIPH_SRC "${STM32F4_STDPERIPH_SRC_DIR}/*.c" STM32F4_STDPERIPH_SRC_EXCLUDES) +set(STM32F4_STDPERIPH_SRC_DIR "${STM32F4_STDPERIPH_DIR}/src") +glob_except(STM32F4_STDPERIPH_SRC "${STM32F4_STDPERIPH_SRC_DIR}/*.c" "${STM32F4_STDPERIPH_SRC_EXCLUDES}") main_sources(STM32F4_SRC target/system_stm32f4xx.c @@ -116,7 +116,7 @@ endfunction() set(STM32F411_OR_F427_STDPERIPH_SRC ${STM32F4_STDPERIPH_SRC}) set(STM32F411_OR_F427_STDPERIPH_SRC_EXCLUDES "stm32f4xx_fsmc.c") -exclude_basenames(STM32F411_OR_F427_STDPERIPH_SRC STM32F411_OR_F427_STDPERIPH_SRC_EXCLUDES) +exclude_basenames(STM32F411_OR_F427_STDPERIPH_SRC ${STM32F411_OR_F427_STDPERIPH_SRC_EXCLUDES}) set(STM32F411_COMPILE_DEFINITIONS STM32F411xE diff --git a/cmake/stm32f7.cmake b/cmake/stm32f7.cmake index 8eeae97eb2d..cc6e5aff760 100644 --- a/cmake/stm32f7.cmake +++ b/cmake/stm32f7.cmake @@ -39,7 +39,7 @@ set(STM32F7_HAL_SRC stm32f7xx_ll_usb.c stm32f7xx_ll_utils.c ) -list(TRANSFORM STM32F7_HAL_SRC PREPEND "${STM32F7_HAL_DIR}/src/") +list(TRANSFORM STM32F7_HAL_SRC PREPEND "${STM32F7_HAL_DIR}/Src/") set(STM32F7_CMSIS_DEVICE_DIR "${MAIN_LIB_DIR}/main/STM32F7/Drivers/CMSIS/Device/ST/STM32F7xx") @@ -53,7 +53,7 @@ set(STM32F7_VCP_SRC list(TRANSFORM STM32F7_VCP_SRC PREPEND "${STM32F7_VCP_DIR}/") set(STM32F7_INCLUDE_DIRS - ${STM32F7_HAL_DIR}/inc + ${STM32F7_HAL_DIR}/Inc ${STM32F7_CMSIS_DEVICE_DIR}/Include ) diff --git a/make/mcu/STM32F7.mk b/make/mcu/STM32F7.mk index 28da7c4df92..2f88a33007f 100644 --- a/make/mcu/STM32F7.mk +++ b/make/mcu/STM32F7.mk @@ -123,7 +123,7 @@ ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fs DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER ifeq ($(TARGET),$(filter $(TARGET),$(F765XI_TARGETS))) DEVICE_FLAGS += -DSTM32F765xx -DSTM32F765xI -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F765xI.ld +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f765xi.ld STARTUP_SRC = startup_stm32f765xx.s TARGET_FLASH := 2048 else ifeq ($(TARGET),$(filter $(TARGET),$(F765XG_TARGETS))) diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt index 77dfc54c20f..674b766d0ba 100644 --- a/src/main/CMakeLists.txt +++ b/src/main/CMakeLists.txt @@ -367,6 +367,8 @@ main_sources(COMMON_SRC rx/eleres.h rx/fport.c rx/fport.h + rx/fport2.c + rx/fport2.h rx/ibus.c rx/ibus.h rx/jetiexbus.c @@ -506,6 +508,8 @@ main_sources(COMMON_SRC io/osd_grid.h io/osd_hud.c io/osd_hud.h + io/smartport_master.c + io/smartport_master.h io/vtx.c io/vtx.h io/vtx_string.c diff --git a/src/main/target/ANYFC/target.h b/src/main/target/ANYFC/target.h index 78d1cab751f..cfd82fc9c7f 100644 --- a/src/main/target/ANYFC/target.h +++ b/src/main/target/ANYFC/target.h @@ -131,7 +131,3 @@ #define TARGET_IO_PORTD 0xffff #define PCA9685_I2C_BUS BUS_I2C2 - -#ifdef USE_USB_MSC -# undef USE_USB_MSC -#endif diff --git a/src/main/target/CLRACINGF4AIR/target.h b/src/main/target/CLRACINGF4AIR/target.h index 992e7e79c4f..2b8f3c01459 100644 --- a/src/main/target/CLRACINGF4AIR/target.h +++ b/src/main/target/CLRACINGF4AIR/target.h @@ -148,7 +148,3 @@ #define TARGET_IO_PORTB (0xffff) #define TARGET_IO_PORTC (0xffff) #define TARGET_IO_PORTD BIT(2) - -#ifdef USE_USB_MSC -# undef USE_USB_MSC -#endif diff --git a/src/main/target/FF_F35_LIGHTNING/target.h b/src/main/target/FF_F35_LIGHTNING/target.h index df981eeb99f..5d6beaf503c 100644 --- a/src/main/target/FF_F35_LIGHTNING/target.h +++ b/src/main/target/FF_F35_LIGHTNING/target.h @@ -139,7 +139,3 @@ #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD (BIT(2)) - -#ifdef USE_USB_MSC -# undef USE_USB_MSC -#endif diff --git a/src/main/target/FOXEERF722DUAL/target.c b/src/main/target/FOXEERF722DUAL/target.c index 80285de5a5a..6f124321abd 100644 --- a/src/main/target/FOXEERF722DUAL/target.c +++ b/src/main/target/FOXEERF722DUAL/target.c @@ -24,7 +24,9 @@ #include "drivers/pwm_mapping.h" BUSDEV_REGISTER_SPI_TAG(busdev_mpu6000, DEVHW_MPU6000, MPU6000_SPI_BUS, MPU6000_CS_PIN, MPU6000_EXTI_PIN, 0, DEVFLAGS_NONE, IMU_MPU6000_ALIGN); +#if defined(FOXEERF722DUAL) BUSDEV_REGISTER_SPI_TAG(busdev_mpu6500, DEVHW_MPU6500, MPU6500_SPI_BUS, MPU6500_CS_PIN, MPU6500_EXTI_PIN, 1, DEVFLAGS_NONE, IMU_MPU6500_ALIGN); +#endif const timerHardware_t timerHardware[] = { DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, 0, 0), // PPM&SBUS diff --git a/src/main/target/FRSKYPILOT/CMakeLists.txt b/src/main/target/FRSKYPILOT/CMakeLists.txt new file mode 100644 index 00000000000..5d6d833c551 --- /dev/null +++ b/src/main/target/FRSKYPILOT/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f765xg(FRSKYPILOT) \ No newline at end of file diff --git a/src/main/target/FRSKY_ROVERF7/CMakeLists.txt b/src/main/target/FRSKY_ROVERF7/CMakeLists.txt new file mode 100644 index 00000000000..993c851ffa9 --- /dev/null +++ b/src/main/target/FRSKY_ROVERF7/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722xe(FRSKY_ROVERF7) \ No newline at end of file diff --git a/src/main/target/FURYF3/CMakeLists.txt b/src/main/target/FURYF3/CMakeLists.txt index d4d60d306c2..0db819ae0a3 100644 --- a/src/main/target/FURYF3/CMakeLists.txt +++ b/src/main/target/FURYF3/CMakeLists.txt @@ -1,2 +1,2 @@ -target_stm32f303xc(FURYF3) -target_stm32f303xc(FURYF3_SPIFLASH) +target_stm32f303xc(FURYF3 SKIP_RELEASES) +target_stm32f303xc(FURYF3_SPIFLASH SKIP_RELEASES) diff --git a/src/main/target/KFC32F3_INAV/CMakeLists.txt b/src/main/target/KFC32F3_INAV/CMakeLists.txt index c8bf5690a0e..1af4cecc063 100644 --- a/src/main/target/KFC32F3_INAV/CMakeLists.txt +++ b/src/main/target/KFC32F3_INAV/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303xc(KFC32F3_INAV) +target_stm32f303xc(KFC32F3_INAV SKIP_RELEASES) diff --git a/src/main/target/MATEKF411/target.h b/src/main/target/MATEKF411/target.h index 967e3c0ef8e..b12f1e596ab 100755 --- a/src/main/target/MATEKF411/target.h +++ b/src/main/target/MATEKF411/target.h @@ -169,7 +169,3 @@ #define TARGET_IO_PORTD (BIT(2)) #define MAX_PWM_OUTPUT_PORTS 7 - -#ifdef USE_USB_MSC -# undef USE_USB_MSC -#endif diff --git a/src/main/target/MATEKF411SE/target.h b/src/main/target/MATEKF411SE/target.h index 790be95bac3..a91f0eb1777 100755 --- a/src/main/target/MATEKF411SE/target.h +++ b/src/main/target/MATEKF411SE/target.h @@ -158,7 +158,3 @@ #define TARGET_IO_PORTD (BIT(2)) #define MAX_PWM_OUTPUT_PORTS 6 - -#ifdef USE_USB_MSC -# undef USE_USB_MSC -#endif diff --git a/src/main/target/SPEEDYBEEF7/CMakeLists.txt b/src/main/target/SPEEDYBEEF7/CMakeLists.txt new file mode 100644 index 00000000000..67935b406b6 --- /dev/null +++ b/src/main/target/SPEEDYBEEF7/CMakeLists.txt @@ -0,0 +1 @@ +target_stm32f722xe(SPEEDYBEEF7) \ No newline at end of file diff --git a/src/main/target/SPRACINGF3EVO/CMakeLists.txt b/src/main/target/SPRACINGF3EVO/CMakeLists.txt index 3833d8d59e3..9acbbaa2e6b 100644 --- a/src/main/target/SPRACINGF3EVO/CMakeLists.txt +++ b/src/main/target/SPRACINGF3EVO/CMakeLists.txt @@ -1,2 +1,2 @@ -target_stm32f303xc(SPRACINGF3EVO) -target_stm32f303xc(SPRACINGF3EVO_1SS) +target_stm32f303xc(SPRACINGF3EVO SKIP_RELEASES) +target_stm32f303xc(SPRACINGF3EVO_1SS SKIP_RELEASES) diff --git a/src/main/target/common.h b/src/main/target/common.h index 01a79e9b580..b76bdf4d3b3 100755 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -46,7 +46,6 @@ #endif #if defined(STM32F4) || defined(STM32F7) -#define USE_USB_MSC #define USE_SERVO_SBUS #endif diff --git a/src/main/target/link/stm32_flash_F746.ld b/src/main/target/link/stm32_flash_F746.ld index e7e8ee24ae9..443c72837af 100644 --- a/src/main/target/link/stm32_flash_F746.ld +++ b/src/main/target/link/stm32_flash_F746.ld @@ -44,4 +44,4 @@ MEMORY REGION_ALIAS("STACKRAM", TCM) REGION_ALIAS("FASTRAM", TCM) -INCLUDE "stm32_flash_F7_split.ld" +INCLUDE "stm32_flash_f7_split.ld" diff --git a/src/main/target/link/stm32_flash_F765xI.ld b/src/main/target/link/stm32_flash_F765xI.ld index 3ec72586435..130169290ea 100644 --- a/src/main/target/link/stm32_flash_F765xI.ld +++ b/src/main/target/link/stm32_flash_F765xI.ld @@ -52,4 +52,4 @@ REGION_ALIAS("STACKRAM", DTCM_RAM) REGION_ALIAS("FASTRAM", DTCM_RAM) REGION_ALIAS("RAM", SRAM1) -INCLUDE "stm32_flash_F7_split.ld" +INCLUDE "stm32_flash_f7_split.ld" diff --git a/src/main/target/link/stm32_flash_F765xI_bl.ld b/src/main/target/link/stm32_flash_F765xI_bl.ld index 867bdbe8c4d..45ced4e7dd2 100644 --- a/src/main/target/link/stm32_flash_F765xI_bl.ld +++ b/src/main/target/link/stm32_flash_F765xI_bl.ld @@ -53,4 +53,4 @@ REGION_ALIAS("RAM", SRAM1) __firmware_start = ORIGIN(AXIM_FIRMWARE); -INCLUDE "stm32_flash_F7.ld" +INCLUDE "stm32_flash_f7.ld" diff --git a/src/main/target/link/stm32_flash_F765xI_for_bl.ld b/src/main/target/link/stm32_flash_F765xI_for_bl.ld index 9661ff663c0..14f2a4bedff 100644 --- a/src/main/target/link/stm32_flash_F765xI_for_bl.ld +++ b/src/main/target/link/stm32_flash_F765xI_for_bl.ld @@ -54,4 +54,4 @@ REGION_ALIAS("RAM", SRAM1) __firmware_start = ORIGIN(AXIM_FLASH); -INCLUDE "stm32_flash_F7_split.ld" +INCLUDE "stm32_flash_f7_split.ld" diff --git a/src/main/target/link/stm32_flash_F7x2.ld b/src/main/target/link/stm32_flash_F7x2.ld index 7aba1e7b783..296708678dc 100644 --- a/src/main/target/link/stm32_flash_F7x2.ld +++ b/src/main/target/link/stm32_flash_F7x2.ld @@ -45,4 +45,4 @@ MEMORY REGION_ALIAS("STACKRAM", TCM) REGION_ALIAS("FASTRAM", TCM) -INCLUDE "stm32_flash_F7_split.ld" +INCLUDE "stm32_flash_f7_split.ld" diff --git a/src/main/target/link/stm32_flash_F7x2_bl.ld b/src/main/target/link/stm32_flash_F7x2_bl.ld index 1241562d055..5bfd3ba4913 100644 --- a/src/main/target/link/stm32_flash_F7x2_bl.ld +++ b/src/main/target/link/stm32_flash_F7x2_bl.ld @@ -47,4 +47,4 @@ REGION_ALIAS("FASTRAM", TCM) __firmware_start = ORIGIN(FIRMWARE); -INCLUDE "stm32_flash_F7.ld" +INCLUDE "stm32_flash_f7.ld" diff --git a/src/main/target/link/stm32_flash_F7x2_for_bl.ld b/src/main/target/link/stm32_flash_F7x2_for_bl.ld index 5ce5fb03774..83c9a43fc5e 100644 --- a/src/main/target/link/stm32_flash_F7x2_for_bl.ld +++ b/src/main/target/link/stm32_flash_F7x2_for_bl.ld @@ -47,4 +47,4 @@ REGION_ALIAS("FASTRAM", TCM) __firmware_start = ORIGIN(FLASH); -INCLUDE "stm32_flash_F7_split.ld" +INCLUDE "stm32_flash_f7_split.ld" diff --git a/src/main/target/link/stm32_flash_F7x5xG.ld b/src/main/target/link/stm32_flash_F7x5xG.ld index 0e72963cdb7..a83374e4e41 100644 --- a/src/main/target/link/stm32_flash_F7x5xG.ld +++ b/src/main/target/link/stm32_flash_F7x5xG.ld @@ -45,4 +45,4 @@ MEMORY REGION_ALIAS("STACKRAM", TCM) REGION_ALIAS("FASTRAM", TCM) -INCLUDE "stm32_flash_F7_split.ld" +INCLUDE "stm32_flash_f7_split.ld" diff --git a/src/main/target/link/stm32_flash_F7x5xG_bl.ld b/src/main/target/link/stm32_flash_F7x5xG_bl.ld index 6639776539b..d357aad98d8 100644 --- a/src/main/target/link/stm32_flash_F7x5xG_bl.ld +++ b/src/main/target/link/stm32_flash_F7x5xG_bl.ld @@ -47,4 +47,4 @@ REGION_ALIAS("FASTRAM", TCM) __firmware_start = ORIGIN(FIRMWARE); -INCLUDE "stm32_flash_F7.ld" +INCLUDE "stm32_flash_f7.ld" diff --git a/src/main/target/link/stm32_flash_F7x5xG_for_bl.ld b/src/main/target/link/stm32_flash_F7x5xG_for_bl.ld index 4cfd76df20a..c7667d1dc26 100644 --- a/src/main/target/link/stm32_flash_F7x5xG_for_bl.ld +++ b/src/main/target/link/stm32_flash_F7x5xG_for_bl.ld @@ -47,4 +47,4 @@ REGION_ALIAS("FASTRAM", TCM) __firmware_start = ORIGIN(FLASH); -INCLUDE "stm32_flash_F7_split.ld" +INCLUDE "stm32_flash_f7_split.ld" diff --git a/src/main/target/link/stm32_flash_F7.ld b/src/main/target/link/stm32_flash_f7.ld similarity index 98% rename from src/main/target/link/stm32_flash_F7.ld rename to src/main/target/link/stm32_flash_f7.ld index e7ebaf29443..090ce49d632 100644 --- a/src/main/target/link/stm32_flash_F7.ld +++ b/src/main/target/link/stm32_flash_f7.ld @@ -49,15 +49,15 @@ SECTIONS _etext = .; /* define a global symbols at end of code */ } >FLASH - tcm_code = LOADADDR(.tcm_code); + tcm_code = LOADADDR(.tcm_code); .tcm_code (NOLOAD) : { . = ALIGN(4); - tcm_code_start = .; + tcm_code_start = .; *(.tcm_code) *(.tcm_code*) . = ALIGN(4); - tcm_code_end = .; + tcm_code_end = .; } >ITCM_RAM AT >FLASH .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH @@ -138,7 +138,7 @@ SECTIONS _ebss = .; /* define a global symbol at bss end */ __bss_end__ = _ebss; } >RAM - + .fastram_bss (NOLOAD) : { __fastram_bss_start__ = .; diff --git a/src/main/target/link/stm32_flash_f722xe_bl.ld b/src/main/target/link/stm32_flash_f722xe_bl.ld index 1241562d055..5bfd3ba4913 100644 --- a/src/main/target/link/stm32_flash_f722xe_bl.ld +++ b/src/main/target/link/stm32_flash_f722xe_bl.ld @@ -47,4 +47,4 @@ REGION_ALIAS("FASTRAM", TCM) __firmware_start = ORIGIN(FIRMWARE); -INCLUDE "stm32_flash_F7.ld" +INCLUDE "stm32_flash_f7.ld" diff --git a/src/main/target/link/stm32_flash_f722xe_for_bl.ld b/src/main/target/link/stm32_flash_f722xe_for_bl.ld index 5ce5fb03774..83c9a43fc5e 100644 --- a/src/main/target/link/stm32_flash_f722xe_for_bl.ld +++ b/src/main/target/link/stm32_flash_f722xe_for_bl.ld @@ -47,4 +47,4 @@ REGION_ALIAS("FASTRAM", TCM) __firmware_start = ORIGIN(FLASH); -INCLUDE "stm32_flash_F7_split.ld" +INCLUDE "stm32_flash_f7_split.ld" diff --git a/src/main/target/link/stm32_flash_f745xg.ld b/src/main/target/link/stm32_flash_f745xg.ld index 161e3b5d583..ddb73a4dc50 100644 --- a/src/main/target/link/stm32_flash_f745xg.ld +++ b/src/main/target/link/stm32_flash_f745xg.ld @@ -45,4 +45,4 @@ MEMORY REGION_ALIAS("STACKRAM", TCM) REGION_ALIAS("FASTRAM", TCM) -INCLUDE "stm32_flash_F7_split.ld" +INCLUDE "stm32_flash_f7_split.ld" diff --git a/src/main/target/link/stm32_flash_f745xg_bl.ld b/src/main/target/link/stm32_flash_f745xg_bl.ld index 6639776539b..d357aad98d8 100644 --- a/src/main/target/link/stm32_flash_f745xg_bl.ld +++ b/src/main/target/link/stm32_flash_f745xg_bl.ld @@ -47,4 +47,4 @@ REGION_ALIAS("FASTRAM", TCM) __firmware_start = ORIGIN(FIRMWARE); -INCLUDE "stm32_flash_F7.ld" +INCLUDE "stm32_flash_f7.ld" diff --git a/src/main/target/link/stm32_flash_f745xg_for_bl.ld b/src/main/target/link/stm32_flash_f745xg_for_bl.ld index 4cfd76df20a..c7667d1dc26 100644 --- a/src/main/target/link/stm32_flash_f745xg_for_bl.ld +++ b/src/main/target/link/stm32_flash_f745xg_for_bl.ld @@ -47,4 +47,4 @@ REGION_ALIAS("FASTRAM", TCM) __firmware_start = ORIGIN(FLASH); -INCLUDE "stm32_flash_F7_split.ld" +INCLUDE "stm32_flash_f7_split.ld" diff --git a/src/main/target/link/stm32_flash_f765xg.ld b/src/main/target/link/stm32_flash_f765xg.ld new file mode 100644 index 00000000000..a83374e4e41 --- /dev/null +++ b/src/main/target/link/stm32_flash_f765xg.ld @@ -0,0 +1,48 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f745.ld +** +** Abstract : Linker script for STM32F745VGTx Device with +** 1024KByte FLASH, 320KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x00003FFF 16K ITCM RAM, +0x08000000 to 0x080FFFFF 1024K full flash, +0x08000000 to 0x08007FFF 32K isr vector, startup code, +0x08008000 to 0x0800FFFF 32K config, // FLASH_Sector_1 +0x08010000 to 0x080FFFFF 960K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K + /* config occupies the entire flash sector 1 for the ease of erasure, 32K on F74x */ + ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00208000, LENGTH = 32K + ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 960K + + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K + FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 32K + FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 960K + + TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 256K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} +/* note CCM could be used for stack */ +REGION_ALIAS("STACKRAM", TCM) +REGION_ALIAS("FASTRAM", TCM) + +INCLUDE "stm32_flash_f7_split.ld" diff --git a/src/main/target/link/stm32_flash_f765xg_bl.ld b/src/main/target/link/stm32_flash_f765xg_bl.ld new file mode 100644 index 00000000000..d357aad98d8 --- /dev/null +++ b/src/main/target/link/stm32_flash_f765xg_bl.ld @@ -0,0 +1,50 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f745.ld +** +** Abstract : Linker script for STM32F745VGTx Device with +** 1024KByte FLASH, 320KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x00003FFF 16K ITCM RAM, +0x08000000 to 0x080FFFFF 1024K full flash, +0x08000000 to 0x08007FFF 32K isr vector, startup code, +0x08008000 to 0x0800FFFF 32K config, // FLASH_Sector_1 +0x08010000 to 0x080FFFFF 960K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K + /* config occupies the entire flash sector 1 for the ease of erasure, 32K on F74x */ + ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00208000, LENGTH = 32K + ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 928K + + FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K + FIRMWARE (rx) : ORIGIN = 0x08008000, LENGTH = 32K + FLASH_CONFIG (r) : ORIGIN = 0x08010000, LENGTH = 32K + + TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 256K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} +/* note CCM could be used for stack */ +REGION_ALIAS("STACKRAM", TCM) +REGION_ALIAS("FASTRAM", TCM) + +__firmware_start = ORIGIN(FIRMWARE); + +INCLUDE "stm32_flash_f7.ld" diff --git a/src/main/target/link/stm32_flash_f765xg_for_bl.ld b/src/main/target/link/stm32_flash_f765xg_for_bl.ld new file mode 100644 index 00000000000..c7667d1dc26 --- /dev/null +++ b/src/main/target/link/stm32_flash_f765xg_for_bl.ld @@ -0,0 +1,50 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f745.ld +** +** Abstract : Linker script for STM32F745VGTx Device with +** 1024KByte FLASH, 320KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x00003FFF 16K ITCM RAM, +0x08000000 to 0x080FFFFF 1024K full flash, +0x08000000 to 0x08007FFF 32K isr vector, startup code, +0x08008000 to 0x0800FFFF 32K config, // FLASH_Sector_1 +0x08010000 to 0x080FFFFF 960K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K + /* config occupies the entire flash sector 1 for the ease of erasure, 32K on F74x */ + ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00208000, LENGTH = 32K + ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 960K + + FLASH (rx) : ORIGIN = 0x08008000, LENGTH = 32K + FLASH_CONFIG (r) : ORIGIN = 0x08010000, LENGTH = 32K + FLASH1 (rx) : ORIGIN = 0x08018000, LENGTH = 928K + + TCM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K + RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 256K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} +/* note CCM could be used for stack */ +REGION_ALIAS("STACKRAM", TCM) +REGION_ALIAS("FASTRAM", TCM) + +__firmware_start = ORIGIN(FLASH); + +INCLUDE "stm32_flash_f7_split.ld" diff --git a/src/main/target/link/stm32_flash_f765xi.ld b/src/main/target/link/stm32_flash_f765xi.ld new file mode 100644 index 00000000000..130169290ea --- /dev/null +++ b/src/main/target/link/stm32_flash_f765xi.ld @@ -0,0 +1,55 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f765.ld +** +** Abstract : Linker script for STM32F765xITx Device with +** 2048KByte FLASH, 512KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x00003FFF 16K TCM RAM, + +0x08000000 to 0x081FFFFF 2048K full flash, +0x08000000 to 0x08007FFF 32K isr vector, startup code, +0x08008000 to 0x0800FFFF 32K config, +0x08010000 to 0x081FFFFF 1984K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K + + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K + ITCM_FLASH_CFG (r) : ORIGIN = 0x00208000, LENGTH = 32K + ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K + + AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K + AXIM_FLASH_CFG (r) : ORIGIN = 0x08008000, LENGTH = 32K + AXIM_FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 1984K + + DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K + SRAM2 (rwx) : ORIGIN = 0x2007C000, LENGTH = 16K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("FLASH", AXIM_FLASH) +REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CFG) +REGION_ALIAS("FLASH1", AXIM_FLASH1) + +REGION_ALIAS("STACKRAM", DTCM_RAM) +REGION_ALIAS("FASTRAM", DTCM_RAM) +REGION_ALIAS("RAM", SRAM1) + +INCLUDE "stm32_flash_f7_split.ld" diff --git a/src/main/target/link/stm32_flash_f765xi_bl.ld b/src/main/target/link/stm32_flash_f765xi_bl.ld new file mode 100644 index 00000000000..45ced4e7dd2 --- /dev/null +++ b/src/main/target/link/stm32_flash_f765xi_bl.ld @@ -0,0 +1,56 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f765.ld +** +** Abstract : Linker script for STM32F765xITx Device with +** 2048KByte FLASH, 512KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x00003FFF 16K TCM RAM, + +0x08000000 to 0x081FFFFF 2048K full flash, +0x08000000 to 0x08007FFF 32K isr vector, startup code, +0x08008000 to 0x0800FFFF 32K config, +0x08010000 to 0x081FFFFF 1984K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K + + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K + ITCM_FLASH_CFG (r) : ORIGIN = 0x00208000, LENGTH = 32K + ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K + + AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K + AXIM_FIRMWARE (rx) : ORIGIN = 0x08008000, LENGTH = 32K + AXIM_FLASH_CFG (r) : ORIGIN = 0x08010000, LENGTH = 32K + + DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K + SRAM2 (rwx) : ORIGIN = 0x2007C000, LENGTH = 16K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("FLASH", AXIM_FLASH) +REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CFG) + +REGION_ALIAS("STACKRAM", DTCM_RAM) +REGION_ALIAS("FASTRAM", DTCM_RAM) +REGION_ALIAS("RAM", SRAM1) + +__firmware_start = ORIGIN(AXIM_FIRMWARE); + +INCLUDE "stm32_flash_f7.ld" diff --git a/src/main/target/link/stm32_flash_f765xi_for_bl.ld b/src/main/target/link/stm32_flash_f765xi_for_bl.ld new file mode 100644 index 00000000000..14f2a4bedff --- /dev/null +++ b/src/main/target/link/stm32_flash_f765xi_for_bl.ld @@ -0,0 +1,57 @@ +/* +***************************************************************************** +** +** File : stm32_flash_f765.ld +** +** Abstract : Linker script for STM32F765xITx Device with +** 2048KByte FLASH, 512KByte RAM +** +***************************************************************************** +*/ + +/* Stack & Heap sizes */ +_Min_Heap_Size = 0; +_Min_Stack_Size = 0x1800; + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x00003FFF 16K TCM RAM, + +0x08000000 to 0x081FFFFF 2048K full flash, +0x08000000 to 0x08007FFF 32K isr vector, startup code, +0x08008000 to 0x0800FFFF 32K config, +0x08010000 to 0x081FFFFF 1984K firmware, +*/ + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K + + ITCM_FLASH (rx) : ORIGIN = 0x00200000, LENGTH = 32K + ITCM_FLASH_CFG (r) : ORIGIN = 0x00208000, LENGTH = 32K + ITCM_FLASH1 (rx) : ORIGIN = 0x00210000, LENGTH = 1984K + + AXIM_FLASH (rx) : ORIGIN = 0x08008000, LENGTH = 32K + AXIM_FLASH_CFG (r) : ORIGIN = 0x08010000, LENGTH = 32K + AXIM_FLASH1 (rx) : ORIGIN = 0x08018000, LENGTH = 1984K + + DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + SRAM1 (rwx) : ORIGIN = 0x20020000, LENGTH = 368K + SRAM2 (rwx) : ORIGIN = 0x2007C000, LENGTH = 16K + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K +} + +REGION_ALIAS("FLASH", AXIM_FLASH) +REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CFG) +REGION_ALIAS("FLASH1", AXIM_FLASH1) + +REGION_ALIAS("STACKRAM", DTCM_RAM) +REGION_ALIAS("FASTRAM", DTCM_RAM) +REGION_ALIAS("RAM", SRAM1) + +__firmware_start = ORIGIN(AXIM_FLASH); + +INCLUDE "stm32_flash_f7_split.ld" diff --git a/src/main/target/link/stm32_flash_F7_split.ld b/src/main/target/link/stm32_flash_f7_split.ld similarity index 98% rename from src/main/target/link/stm32_flash_F7_split.ld rename to src/main/target/link/stm32_flash_f7_split.ld index f3dde2e7f7e..4738eb7af5e 100644 --- a/src/main/target/link/stm32_flash_F7_split.ld +++ b/src/main/target/link/stm32_flash_f7_split.ld @@ -49,15 +49,15 @@ SECTIONS _etext = .; /* define a global symbols at end of code */ } >FLASH1 - tcm_code = LOADADDR(.tcm_code); + tcm_code = LOADADDR(.tcm_code); .tcm_code (NOLOAD) : { . = ALIGN(4); - tcm_code_start = .; + tcm_code_start = .; *(.tcm_code) *(.tcm_code*) . = ALIGN(4); - tcm_code_end = .; + tcm_code_end = .; } >ITCM_RAM AT >FLASH1 .ARM.extab : { *(.ARM.extab* .gnu.linkonce.armextab.*) } >FLASH diff --git a/src/utils/build-targets.sh b/src/utils/build-targets.sh deleted file mode 100755 index f8633819bf5..00000000000 --- a/src/utils/build-targets.sh +++ /dev/null @@ -1,70 +0,0 @@ -#!/bin/sh - -set -e - -usage() -{ - echo "Usage ${0} [-n] [-S suffix] -s START -c COUNT]" >&2; - echo "Build COUNT targets starting at index START" >&2; - echo "Targets are retrieved via make targets" >&2; - echo "-n prints the targets instead of building them" >&2; - echo "-S sets the BUILD_SUFFIX" >&2; - exit 1; -} - -is_number() -{ - ! [ -z ${1} ] && [ ${1} -eq ${1} ] 2>/dev/null -} - -START= -COUNT= -DRY_RUN= -BUILD_SUFFIX= - -args=`getopt nS:s:c: $*` -set -- $args -for i -do - case "$i" - in - -n) - DRY_RUN=1 - shift;; - -S) - BUILD_SUFFIX=${2}; shift; - shift;; - -s) - START=${2}; shift; - shift;; - -c) - COUNT=${2}; shift; - shift;; - --) - shift; break;; - esac -done - -if ! is_number ${START} || ! is_number ${COUNT}; then - usage; -fi - -ALL_TARGETS=$(make targets | grep Valid | awk -F' *: *' '{print $2}') -START_IDX=$(expr ${START} + 1) -END_IDX=$(expr ${START} + ${COUNT}) -SELECTED_TARGETS=$(echo ${ALL_TARGETS} | cut -d ' ' -f ${START_IDX}-${END_IDX}) - -if [ -z "${DRY_RUN}" ]; then - for target in ${SELECTED_TARGETS}; do - BUILD_SUFFIX=${BUILD_SUFFIX} V=0 CFLAGS=-Werror make ${target} - # Cleanup intermediate files after building each target. - # Otherwise we run out of space on GH CI. - # XXX: Make sure we save the .hex file for artifact - # generation - mkdir -p obj/dist - mv obj/*.hex obj/dist - V=0 make clean_${target} - done -else - echo "${SELECTED_TARGETS}" -fi From fe24e611af19feee2aed0beb2cf21228bb10b04c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Wed, 26 Aug 2020 15:40:50 +0100 Subject: [PATCH 166/248] [CMAKE] Consider warnings as errors during CI --- .github/workflows/ci.yml | 2 +- src/main/drivers/pwm_output.c | 2 +- src/main/msc/usbd_storage_sd_spi.c | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index ef0254f7899..f8f2bdd8dad 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -34,7 +34,7 @@ jobs: path: downloads key: ${{ runner.os }}-downloads-${{ hashFiles('CMakeLists.txt') }}-${{ hashFiles('**/cmake/*')}} - name: Build targets (${{ matrix.id }}) - run: mkdir -p build && cd build && cmake -DCI_JOB_INDEX=${{ matrix.id }} -DCI_JOB_COUNT=${{ strategy.job-total }} -DBUILD_SUFFIX=${{ env.BUILD_SUFFIX }} -G Ninja .. && ninja ci + run: mkdir -p build && cd build && cmake -DWARNINGS_AS_ERRORS=ON -DCI_JOB_INDEX=${{ matrix.id }} -DCI_JOB_COUNT=${{ strategy.job-total }} -DBUILD_SUFFIX=${{ env.BUILD_SUFFIX }} -G Ninja .. && ninja ci - name: Upload artifacts uses: actions/upload-artifact@v2-preview with: diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 6472741a78a..5f61be7495e 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -578,7 +578,7 @@ void beeperPwmInit(ioTag_t tag, uint16_t frequency) // Attempt to allocate TCH TCH_t * tch = timerGetTCH(timHw); if (tch == NULL) { - return NULL; + return; } beeperPwm = &beeperPwmPort; diff --git a/src/main/msc/usbd_storage_sd_spi.c b/src/main/msc/usbd_storage_sd_spi.c index fc61cd6cef6..03f53eed72a 100644 --- a/src/main/msc/usbd_storage_sd_spi.c +++ b/src/main/msc/usbd_storage_sd_spi.c @@ -213,8 +213,8 @@ static int8_t STORAGE_Read (uint8_t lun, UNUSED(lun); LED1_ON; for (int i = 0; i < blk_len; i++) { - while (sdcard_readBlock(blk_addr + i, buf + (512 * i), NULL, NULL) == 0); - while (sdcard_poll() == 0); + while (sdcard_readBlock(blk_addr + i, buf + (512 * i), NULL, 0) == 0); + while (sdcard_poll() == 0); } LED1_OFF; return 0; From 4db3889160a7864d47b789e02fdefcb3a4d4a105 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Wed, 26 Aug 2020 16:03:03 +0100 Subject: [PATCH 167/248] [CMAKE] Increase project number in CMakeLists.txt to 2.6.0 --- CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 53aff1c71b4..7ff68c664b3 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -29,7 +29,7 @@ else() include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}-checks.cmake") endif() -project(INAV VERSION 2.5.0) +project(INAV VERSION 2.6.0) enable_language(ASM) From 9712376a2217d5c3d46b7fb0c1e3806d5715d1ac Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Wed, 26 Aug 2020 19:33:14 +0100 Subject: [PATCH 168/248] [CMAKE] Support cmake 3.13 and up 3.13 is what ships with current Debian stable, so it seems like a reasonable baseline --- CMakeLists.txt | 2 +- cmake/stm32.cmake | 8 ++++++-- 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 7ff68c664b3..6d7b40dca16 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,4 +1,4 @@ -cmake_minimum_required(VERSION 3.17) +cmake_minimum_required(VERSION 3.13...3.18) list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake") diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake index 5bec5463d70..dfe8884876f 100644 --- a/cmake/stm32.cmake +++ b/cmake/stm32.cmake @@ -203,7 +203,12 @@ function(add_bin_target name exe bin) endfunction() function(generate_map_file target) - target_link_options(${target} PRIVATE "-Wl,-Map,$/$.map") + if(CMAKE_VERSION VERSION_LESS 3.15) + set(map "$.map") + else() + set(map "$/$.map") + endif() + target_link_options(${target} PRIVATE "-Wl,-Map,${map}") endfunction() function(set_linker_script target script) @@ -229,7 +234,6 @@ function(add_stm32_executable) ) set(elf_target ${args_NAME}.elf) add_executable(${elf_target}) - set_target_properties(${elf_target} PROPERTIES OUTPUT_NAME ${args_NAME}) target_sources(${elf_target} PRIVATE ${args_SOURCES}) target_include_directories(${elf_target} PRIVATE ${CMAKE_CURRENT_SOURCE_DIR} ${args_INCLUDE_DIRECTORIES} ${STM32_INCLUDE_DIRS}) target_compile_definitions(${elf_target} PRIVATE ${args_COMPILE_DEFINITIONS}) From d3fcadac05a244b8e5aa6e5a59932052a41d992f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Wed, 26 Aug 2020 21:26:34 +0100 Subject: [PATCH 169/248] [CMAKE] Add support for using Linux compiler binaries on FreeBSD --- cmake/arm-none-eabi-checks.cmake | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/cmake/arm-none-eabi-checks.cmake b/cmake/arm-none-eabi-checks.cmake index ac13bc4481b..152a914dc45 100644 --- a/cmake/arm-none-eabi-checks.cmake +++ b/cmake/arm-none-eabi-checks.cmake @@ -33,9 +33,13 @@ function(arm_none_eabi_gcc_install) set(dist "") if(CMAKE_HOST_SYSTEM_NAME STREQUAL "Windows") set(dist ${arm_none_eabi_win32}) - elseif(CMAKE_HOST_SYSTEM_NAME STREQUAL "Linux") + elseif(CMAKE_HOST_SYSTEM_NAME STREQUAL "Linux" OR CMAKE_HOST_SYSTEM_NAME STREQUAL "FreeBSD") + if(NOT CMAKE_HOST_SYSTEM_NAME STREQUAL "Linux") + message("-- no compiler binaries available for ${CMAKE_HOST_SYSTEM_NAME}, using Linux binaries as a fallback") + endif() host_uname_machine(machine) - if(machine STREQUAL "x86_64") + # Linux returns x86_64, FreeBSD returns amd64 + if(machine STREQUAL "x86_64" OR machine STREQUAL "amd64") set(dist ${arm_none_eabi_linux_amd64}) elseif(machine STREQUAL "aarch64") set(dist ${arm_none_eabi_linux_aarch64}) From 227c4e124320492b17d53acd0d6107a5be346ba4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Wed, 26 Aug 2020 22:17:35 +0100 Subject: [PATCH 170/248] [CMAKE] Prepend local compiler installation to PATH instead of appending Also, use the proper pathlist separator on Windows --- cmake/arm-none-eabi-checks.cmake | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/cmake/arm-none-eabi-checks.cmake b/cmake/arm-none-eabi-checks.cmake index 152a914dc45..8d962b92526 100644 --- a/cmake/arm-none-eabi-checks.cmake +++ b/cmake/arm-none-eabi-checks.cmake @@ -88,7 +88,12 @@ endfunction() function(arm_none_eabi_gcc_add_path) arm_none_eabi_gcc_distname(dist_name) set(gcc_path "${TOOLS_DIR}/${dist_name}/bin") - set(ENV{PATH} "$ENV{PATH}:${gcc_path}") + if(CMAKE_HOST_SYSTEM MATCHES ".*Windows.*") + set(sep "\\;") + else() + set(sep ":") + endif() + set(ENV{PATH} "${gcc_path}${sep}$ENV{PATH}") endfunction() function(arm_none_eabi_gcc_check) From 056489d856cc8cc222f992b6aa6716edd68454ba Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Wed, 26 Aug 2020 22:40:28 +0100 Subject: [PATCH 171/248] [CMAKE] Add workaround for cmake -E rm with versions prior to 3.17 --- cmake/stm32.cmake | 20 ++++++++++++++++---- 1 file changed, 16 insertions(+), 4 deletions(-) diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake index dfe8884876f..7338a105016 100644 --- a/cmake/stm32.cmake +++ b/cmake/stm32.cmake @@ -413,12 +413,24 @@ function(target_stm32) # clean_ set(clean_target "clean_${name}") + if(CMAKE_VERSION VERSION_LESS 3.17) + if(CMAKE_HOST_SYSTEM MATCHES ".*Windows.*") + set(rm del /s /q) + set(rmdir rmdir /s /q) + else() + set(rm rm -fr) + set(rmdir ${rm}) + endif() + else() + set(rm ${CMAKE_COMMAND} -E rm -fr) + set(rmdir ${rm}) + endif() add_custom_target(${clean_target} WORKING_DIRECTORY ${CMAKE_BINARY_DIR} - COMMAND ${CMAKE_COMMAND} -E rm -r "${CMAKE_CURRENT_BINARY_DIR}" - COMMAND ${CMAKE_COMMAND} -E rm ${main_hex_filename} - COMMAND ${CMAKE_COMMAND} -E rm ${bl_hex_filename} - COMMAND ${CMAKE_COMMAND} -E rm ${main_hex_filename} + COMMAND ${rmdir} "${CMAKE_CURRENT_BINARY_DIR}" + COMMAND ${rm} ${main_hex_filename} + COMMAND ${rm} ${bl_hex_filename} + COMMAND ${rm} ${main_hex_filename} COMMENT "Removing intermediate files for ${name}") set_property(TARGET ${clean_target} PROPERTY TARGET_MESSAGES OFF From 888763f59ef4b118c533444a6affbabe971cb5a4 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Thu, 27 Aug 2020 12:30:51 +0100 Subject: [PATCH 172/248] [CMAKE] Cosmetic changes - Make sure all the new files are terminated with newlines - Fix typos --- cmake/arm-none-eabi-checks.cmake | 2 +- cmake/ci.cmake | 2 +- cmake/openocd_cfg.cmake | 2 +- cmake/stm32-stdperiph.cmake | 2 +- cmake/stm32f4-usb.cmake | 2 +- cmake/stm32f7.cmake | 2 +- cmake/svd.cmake | 2 +- docs/USB_Mass_Storage_(MSC)_mode.md | 2 +- src/main/target/ALIENFLIGHTF3/CMakeLists.txt | 2 +- src/main/target/ALIENFLIGHTF4/CMakeLists.txt | 2 +- src/main/target/ANYFCM7/CMakeLists.txt | 2 +- src/main/target/ASGARD32F7/CMakeLists.txt | 2 +- src/main/target/CHEBUZZF3/CMakeLists.txt | 2 +- src/main/target/COLIBRI_RACE/CMakeLists.txt | 2 +- src/main/target/FRSKYPILOT/CMakeLists.txt | 2 +- src/main/target/FRSKY_ROVERF7/CMakeLists.txt | 2 +- src/main/target/KISSFC/CMakeLists.txt | 2 +- src/main/target/KROOZX/CMakeLists.txt | 2 +- src/main/target/SPEEDYBEEF7/CMakeLists.txt | 2 +- src/main/target/SPRACINGF3NEO/CMakeLists.txt | 2 +- src/main/target/YUPIF4/CMakeLists.txt | 2 +- src/main/target/YUPIF7/CMakeLists.txt | 2 +- 22 files changed, 22 insertions(+), 22 deletions(-) diff --git a/cmake/arm-none-eabi-checks.cmake b/cmake/arm-none-eabi-checks.cmake index 8d962b92526..852ca4984b4 100644 --- a/cmake/arm-none-eabi-checks.cmake +++ b/cmake/arm-none-eabi-checks.cmake @@ -116,4 +116,4 @@ function(arm_none_eabi_gcc_check) endfunction() arm_none_eabi_gcc_add_path() -arm_none_eabi_gcc_check() \ No newline at end of file +arm_none_eabi_gcc_check() diff --git a/cmake/ci.cmake b/cmake/ci.cmake index c04ab6188c4..4546a8b6303 100644 --- a/cmake/ci.cmake +++ b/cmake/ci.cmake @@ -12,4 +12,4 @@ if(DEFINED CI_JOB_INDEX AND DEFINED CI_JOB_COUNT) ${CMAKE_COMMAND} -E true DEPENDS ${ci_targets} ) -endif() \ No newline at end of file +endif() diff --git a/cmake/openocd_cfg.cmake b/cmake/openocd_cfg.cmake index 9c2ca220003..139302823ef 100644 --- a/cmake/openocd_cfg.cmake +++ b/cmake/openocd_cfg.cmake @@ -17,4 +17,4 @@ list(APPEND openocd_cfg "reset halt") list(JOIN openocd_cfg "\n" contents) set(contents "${contents}\n") -file(WRITE ${OUTPUT} ${contents}) \ No newline at end of file +file(WRITE ${OUTPUT} ${contents}) diff --git a/cmake/stm32-stdperiph.cmake b/cmake/stm32-stdperiph.cmake index d085dc67144..3e63d42385c 100644 --- a/cmake/stm32-stdperiph.cmake +++ b/cmake/stm32-stdperiph.cmake @@ -1,4 +1,4 @@ main_sources(STM32_STDPERIPH_SRC drivers/bus_spi.c drivers/serial_uart.c -) \ No newline at end of file +) diff --git a/cmake/stm32f4-usb.cmake b/cmake/stm32f4-usb.cmake index 8c30f0e554c..7f0235a3681 100644 --- a/cmake/stm32f4-usb.cmake +++ b/cmake/stm32f4-usb.cmake @@ -56,4 +56,4 @@ list(APPEND STM32F4_USB_SRC ${STM32_USBOTG_SRC}) list(APPEND STM32F4_USB_SRC ${STM32_USBCORE_SRC}) list(APPEND STM32F4_USB_SRC ${STM32_USBCDC_SRC}) list(APPEND STM32F4_USB_SRC ${STM32_USBHID_SRC}) -list(APPEND STM32F4_USB_SRC ${STM32_USBWRAPPER_SRC}) \ No newline at end of file +list(APPEND STM32F4_USB_SRC ${STM32_USBWRAPPER_SRC}) diff --git a/cmake/stm32f7.cmake b/cmake/stm32f7.cmake index cc6e5aff760..f2726a71d9b 100644 --- a/cmake/stm32f7.cmake +++ b/cmake/stm32f7.cmake @@ -129,4 +129,4 @@ define_target_stm32f7(22 e) define_target_stm32f7(45 g) define_target_stm32f7(46 g) define_target_stm32f7(65 g) -define_target_stm32f7(65 i) \ No newline at end of file +define_target_stm32f7(65 i) diff --git a/cmake/svd.cmake b/cmake/svd.cmake index fd9b24348a2..d6d7fb80a32 100644 --- a/cmake/svd.cmake +++ b/cmake/svd.cmake @@ -13,4 +13,4 @@ function(setup_svd target_exe target_name) COMMAND ${CMAKE_COMMAND} -E false) endif() exclude_from_all(${svd_target_name}) -endfunction() \ No newline at end of file +endfunction() diff --git a/docs/USB_Mass_Storage_(MSC)_mode.md b/docs/USB_Mass_Storage_(MSC)_mode.md index 1812c4fbc09..93a9bba4d4c 100644 --- a/docs/USB_Mass_Storage_(MSC)_mode.md +++ b/docs/USB_Mass_Storage_(MSC)_mode.md @@ -83,5 +83,5 @@ Data rate 496Hz 35806 bytes/s 358100 baud ``` ## Developer Notes -Providing MSC is automatically enabled for all F4 and up a targets that support +Providing MSC is automatically enabled for all F4 and up targets that support `ONBOARDFLASH` and /or `SDCARD`. \ No newline at end of file diff --git a/src/main/target/ALIENFLIGHTF3/CMakeLists.txt b/src/main/target/ALIENFLIGHTF3/CMakeLists.txt index 3932036a292..69f611b37e8 100644 --- a/src/main/target/ALIENFLIGHTF3/CMakeLists.txt +++ b/src/main/target/ALIENFLIGHTF3/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303xc(ALIENFLIGHTF3 SKIP_RELEASES) \ No newline at end of file +target_stm32f303xc(ALIENFLIGHTF3 SKIP_RELEASES) diff --git a/src/main/target/ALIENFLIGHTF4/CMakeLists.txt b/src/main/target/ALIENFLIGHTF4/CMakeLists.txt index dd707d192e1..51d35d199d2 100644 --- a/src/main/target/ALIENFLIGHTF4/CMakeLists.txt +++ b/src/main/target/ALIENFLIGHTF4/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405xg(ALIENFLIGHTF4 SKIP_RELEASES) \ No newline at end of file +target_stm32f405xg(ALIENFLIGHTF4 SKIP_RELEASES) diff --git a/src/main/target/ANYFCM7/CMakeLists.txt b/src/main/target/ANYFCM7/CMakeLists.txt index 4fbeb706c88..c61e21d27ba 100644 --- a/src/main/target/ANYFCM7/CMakeLists.txt +++ b/src/main/target/ANYFCM7/CMakeLists.txt @@ -1 +1 @@ -target_stm32f722xe(ANYFCM7 SKIP_RELEASES) \ No newline at end of file +target_stm32f722xe(ANYFCM7 SKIP_RELEASES) diff --git a/src/main/target/ASGARD32F7/CMakeLists.txt b/src/main/target/ASGARD32F7/CMakeLists.txt index 711c638e7e1..5e7f889d6b3 100644 --- a/src/main/target/ASGARD32F7/CMakeLists.txt +++ b/src/main/target/ASGARD32F7/CMakeLists.txt @@ -1 +1 @@ -target_stm32f722xe(ASGARD32F7) \ No newline at end of file +target_stm32f722xe(ASGARD32F7) diff --git a/src/main/target/CHEBUZZF3/CMakeLists.txt b/src/main/target/CHEBUZZF3/CMakeLists.txt index 7cc65c9a5f3..f1c67aec2dc 100644 --- a/src/main/target/CHEBUZZF3/CMakeLists.txt +++ b/src/main/target/CHEBUZZF3/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303xc(CHEBUZZF3 SKIP_RELEASES) \ No newline at end of file +target_stm32f303xc(CHEBUZZF3 SKIP_RELEASES) diff --git a/src/main/target/COLIBRI_RACE/CMakeLists.txt b/src/main/target/COLIBRI_RACE/CMakeLists.txt index 11b63f73351..430421fe73e 100644 --- a/src/main/target/COLIBRI_RACE/CMakeLists.txt +++ b/src/main/target/COLIBRI_RACE/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303xc(COLIBRI_RACE SKIP_RELEASES) \ No newline at end of file +target_stm32f303xc(COLIBRI_RACE SKIP_RELEASES) diff --git a/src/main/target/FRSKYPILOT/CMakeLists.txt b/src/main/target/FRSKYPILOT/CMakeLists.txt index 5d6d833c551..2f227600800 100644 --- a/src/main/target/FRSKYPILOT/CMakeLists.txt +++ b/src/main/target/FRSKYPILOT/CMakeLists.txt @@ -1 +1 @@ -target_stm32f765xg(FRSKYPILOT) \ No newline at end of file +target_stm32f765xg(FRSKYPILOT) diff --git a/src/main/target/FRSKY_ROVERF7/CMakeLists.txt b/src/main/target/FRSKY_ROVERF7/CMakeLists.txt index 993c851ffa9..e220b6642fc 100644 --- a/src/main/target/FRSKY_ROVERF7/CMakeLists.txt +++ b/src/main/target/FRSKY_ROVERF7/CMakeLists.txt @@ -1 +1 @@ -target_stm32f722xe(FRSKY_ROVERF7) \ No newline at end of file +target_stm32f722xe(FRSKY_ROVERF7) diff --git a/src/main/target/KISSFC/CMakeLists.txt b/src/main/target/KISSFC/CMakeLists.txt index 928051ba27e..ab4808c4dc2 100644 --- a/src/main/target/KISSFC/CMakeLists.txt +++ b/src/main/target/KISSFC/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303xc(KISSFC SKIP_RELEASES) \ No newline at end of file +target_stm32f303xc(KISSFC SKIP_RELEASES) diff --git a/src/main/target/KROOZX/CMakeLists.txt b/src/main/target/KROOZX/CMakeLists.txt index 212f7a99825..4b98d7df3a3 100644 --- a/src/main/target/KROOZX/CMakeLists.txt +++ b/src/main/target/KROOZX/CMakeLists.txt @@ -1 +1 @@ -target_stm32f405xg(KROOZX HSE_MHZ 16 SKIP_RELEASES) \ No newline at end of file +target_stm32f405xg(KROOZX HSE_MHZ 16 SKIP_RELEASES) diff --git a/src/main/target/SPEEDYBEEF7/CMakeLists.txt b/src/main/target/SPEEDYBEEF7/CMakeLists.txt index 67935b406b6..d7f8a2c01fe 100644 --- a/src/main/target/SPEEDYBEEF7/CMakeLists.txt +++ b/src/main/target/SPEEDYBEEF7/CMakeLists.txt @@ -1 +1 @@ -target_stm32f722xe(SPEEDYBEEF7) \ No newline at end of file +target_stm32f722xe(SPEEDYBEEF7) diff --git a/src/main/target/SPRACINGF3NEO/CMakeLists.txt b/src/main/target/SPRACINGF3NEO/CMakeLists.txt index a8fd8e50a24..d93726a632d 100644 --- a/src/main/target/SPRACINGF3NEO/CMakeLists.txt +++ b/src/main/target/SPRACINGF3NEO/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303xc(SPRACINGF3NEO SKIP_RELEASES) \ No newline at end of file +target_stm32f303xc(SPRACINGF3NEO SKIP_RELEASES) diff --git a/src/main/target/YUPIF4/CMakeLists.txt b/src/main/target/YUPIF4/CMakeLists.txt index 4e64e13cd15..0471878a31d 100644 --- a/src/main/target/YUPIF4/CMakeLists.txt +++ b/src/main/target/YUPIF4/CMakeLists.txt @@ -1,3 +1,3 @@ target_stm32f405xg(YUPIF4 SKIP_RELEASES) target_stm32f405xg(YUPIF4MINI SKIP_RELEASES) -target_stm32f405xg(YUPIF4R2 SKIP_RELEASES) \ No newline at end of file +target_stm32f405xg(YUPIF4R2 SKIP_RELEASES) diff --git a/src/main/target/YUPIF7/CMakeLists.txt b/src/main/target/YUPIF7/CMakeLists.txt index 289873afc08..b164218ca87 100644 --- a/src/main/target/YUPIF7/CMakeLists.txt +++ b/src/main/target/YUPIF7/CMakeLists.txt @@ -1 +1 @@ -target_stm32f722xe(YUPIF7) \ No newline at end of file +target_stm32f722xe(YUPIF7) From 3b35829a062f746825c2bde6f2c49ed5411b3ff2 Mon Sep 17 00:00:00 2001 From: Airwide Date: Thu, 27 Aug 2020 20:46:15 +0200 Subject: [PATCH 173/248] Changed logic for anti windup deactivation for fixed wing --- src/main/fc/fc_core.c | 18 +++++++++++------- 1 file changed, 11 insertions(+), 7 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index c46faf8b93a..e97ae2d42cd 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -515,11 +515,11 @@ void tryArm(void) static void handlePIDAntiWindup(throttleStatus_e throttleStatus) { - static bool antiWindupWasActivatedOnce = false; + static bool antiWindupWasDeactivatedOnce = false; // Track if ANTI_WINDUP was activated if (!ARMING_FLAG(ARMED)) { - antiWindupWasActivatedOnce = false; + antiWindupWasDeactivatedOnce = false; } // In MANUAL mode we reset integrators prevent I-term wind-up (PID output is not used in MANUAL) if (FLIGHT_MODE(MANUAL_MODE) || !ARMING_FLAG(ARMED)) { @@ -527,6 +527,13 @@ static void handlePIDAntiWindup(throttleStatus_e throttleStatus) pidResetErrorAccumulators(); return; } + + rollPitchStatus_e rollPitchStatus = calculateRollPitchCenterStatus(); + + // Set antiWindupWasDeactivatedOnce to prevent anti windup from being activated again + if ((throttleStatus != THROTTLE_LOW) && (rollPitchStatus != CENTERED)) { + antiWindupWasDeactivatedOnce = true; + } // At non-zero throttle - always disable ANTI_WINDUP if (throttleStatus != THROTTLE_LOW) { @@ -543,14 +550,11 @@ static void handlePIDAntiWindup(throttleStatus_e throttleStatus) return; } - rollPitchStatus_e rollPitchStatus = calculateRollPitchCenterStatus(); - - if (STATE(FIXED_WING_LEGACY)) { + if (STATE(AIRPLANE)) { if (STATE(AIRMODE_ACTIVE)) { // On airplanes only activate ANTI_WINDUP if throttle = low, roll/pitch = center and ANTI_WINDUP was never activated this flight - if ((rollPitchStatus == CENTERED) && !antiWindupWasActivatedOnce) { + if ((rollPitchStatus == CENTERED) && !antiWindupWasDeactivatedOnce) { ENABLE_STATE(ANTI_WINDUP); - antiWindupWasActivatedOnce = true; } else { DISABLE_STATE(ANTI_WINDUP); From 0879383ae81acbdcf55e5d5f6a632e263716564a Mon Sep 17 00:00:00 2001 From: Airwide Date: Thu, 27 Aug 2020 20:47:51 +0200 Subject: [PATCH 174/248] removed trailing whitspace --- src/main/fc/fc_core.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index e97ae2d42cd..29e538857fc 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -521,15 +521,15 @@ static void handlePIDAntiWindup(throttleStatus_e throttleStatus) if (!ARMING_FLAG(ARMED)) { antiWindupWasDeactivatedOnce = false; } - // In MANUAL mode we reset integrators prevent I-term wind-up (PID output is not used in MANUAL) + // In MANUAL mode we reset integrators prevent I-term wind-up (PID output is not used in MANUAL) if (FLIGHT_MODE(MANUAL_MODE) || !ARMING_FLAG(ARMED)) { DISABLE_STATE(ANTI_WINDUP); pidResetErrorAccumulators(); return; } - + rollPitchStatus_e rollPitchStatus = calculateRollPitchCenterStatus(); - + // Set antiWindupWasDeactivatedOnce to prevent anti windup from being activated again if ((throttleStatus != THROTTLE_LOW) && (rollPitchStatus != CENTERED)) { antiWindupWasDeactivatedOnce = true; From 3e9f1f9eb0651bbc64fed46e3876c2d3e152e5ed Mon Sep 17 00:00:00 2001 From: Airwide Date: Thu, 27 Aug 2020 21:36:15 +0200 Subject: [PATCH 175/248] Moved Anti windup comment inside method --- src/main/fc/fc_core.c | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 29e538857fc..41373acad2d 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -515,6 +515,10 @@ void tryArm(void) static void handlePIDAntiWindup(throttleStatus_e throttleStatus) { + /* In airmode Iterm should be prevented to grow when Low thottle and Roll + Pitch Centered. + This is needed to prevent Iterm winding on the ground, but keep full stabilisation on 0 throttle while in air + Low Throttle + roll and Pitch centered is assuming the copter is on the ground. Done to prevent complex air/ground detections */ + static bool antiWindupWasDeactivatedOnce = false; // Track if ANTI_WINDUP was activated @@ -534,13 +538,11 @@ static void handlePIDAntiWindup(throttleStatus_e throttleStatus) if ((throttleStatus != THROTTLE_LOW) && (rollPitchStatus != CENTERED)) { antiWindupWasDeactivatedOnce = true; } - // At non-zero throttle - always disable ANTI_WINDUP if (throttleStatus != THROTTLE_LOW) { DISABLE_STATE(ANTI_WINDUP); return; } - // This case applies only to MR when Airmode management is throttle threshold activated if (rcControlsConfig()->airmodeHandlingType == THROTTLE_THRESHOLD) { DISABLE_STATE(ANTI_WINDUP); @@ -549,7 +551,6 @@ static void handlePIDAntiWindup(throttleStatus_e throttleStatus) } return; } - if (STATE(AIRPLANE)) { if (STATE(AIRMODE_ACTIVE)) { // On airplanes only activate ANTI_WINDUP if throttle = low, roll/pitch = center and ANTI_WINDUP was never activated this flight @@ -712,9 +713,6 @@ void processRx(timeUs_t currentTimeUs) } } - /* In airmode Iterm should be prevented to grow when Low thottle and Roll + Pitch Centered. - This is needed to prevent Iterm winding on the ground, but keep full stabilisation on 0 throttle while in air - Low Throttle + roll and Pitch centered is assuming the copter is on the ground. Done to prevent complex air/ground detections */ handlePIDAntiWindup(throttleStatus); if (mixerConfig()->platformType == PLATFORM_AIRPLANE) { From 5c76b8306f961174f8d2f7153297192f8b206949 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 27 Aug 2020 22:02:03 +0200 Subject: [PATCH 176/248] Fix MAG health reporting and calibration --- src/main/fc/settings.yaml | 6 +++--- src/main/sensors/compass.c | 7 ++++--- 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 9b75e06c398..c9060f1c9d5 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -405,19 +405,19 @@ groups: max: INT16_MAX - name: maggain_x description: "Magnetometer calibration X gain. If 0, no calibration or calibration failed" - default_value: "0" + default_value: "1024" field: magGain[X] min: INT16_MIN max: INT16_MAX - name: maggain_y description: "Magnetometer calibration Y gain. If 0, no calibration or calibration failed" - default_value: "0" + default_value: "1024" field: magGain[Y] min: INT16_MIN max: INT16_MAX - name: maggain_z description: "Magnetometer calibration Z gain. If 0, no calibration or calibration failed" - default_value: "0" + default_value: "1024" field: magGain[Z] min: INT16_MIN max: INT16_MAX diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index 37314601bd5..842c5088209 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -73,6 +73,7 @@ PG_RESET_TEMPLATE(compassConfig_t, compassConfig, .rollDeciDegrees = 0, .pitchDeciDegrees = 0, .yawDeciDegrees = 0, + .magGain = {1024, 1024, 1024}, ); #ifdef USE_MAG @@ -338,8 +339,8 @@ void compassUpdate(timeUs_t currentTimeUs) // Check magZero if ( - (compassConfig()->magZero.raw[X] == 0 && compassConfig()->magZero.raw[Y] == 0 && compassConfig()->magZero.raw[Z] == 0) || - compassConfig()->magGain[X] == 0 || compassConfig()->magGain[Y] == 0 || compassConfig()->magGain[Z] == 0 + compassConfig()->magZero.raw[X] == 0 && compassConfig()->magZero.raw[Y] == 0 && compassConfig()->magZero.raw[Z] == 0 && + compassConfig()->magGain[X] == 1024 && compassConfig()->magGain[Y] == 1024 && compassConfig()->magGain[Z] == 1024 ) { DISABLE_STATE(COMPASS_CALIBRATED); } @@ -363,7 +364,7 @@ void compassUpdate(timeUs_t currentTimeUs) for (int axis = 0; axis < 3; axis++) { compassConfigMutable()->magZero.raw[axis] = 0; - compassConfigMutable()->magGain[axis] = 0; + compassConfigMutable()->magGain[axis] = 1024; magPrev[axis] = 0; } From 493e3427a366d3cacc4f42f5fae70fa2edadb1fd Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Wed, 5 Aug 2020 18:09:32 -0400 Subject: [PATCH 177/248] Atomiclama and my mods --- src/main/cms/cms_menu_osd.c | 28 ++++++++++++ src/main/drivers/osd_symbols.h | 6 +++ src/main/fc/settings.yaml | 6 +++ src/main/io/osd.c | 81 ++++++++++++++++++++++++++++++---- src/main/io/osd.h | 13 +++++- src/main/rx/crsf.c | 17 ++++--- src/main/rx/rx.c | 1 + src/main/rx/rx.h | 12 ++++- 8 files changed, 148 insertions(+), 16 deletions(-) diff --git a/src/main/cms/cms_menu_osd.c b/src/main/cms/cms_menu_osd.c index dceb87da6b3..76dd8941e2e 100755 --- a/src/main/cms/cms_menu_osd.c +++ b/src/main/cms/cms_menu_osd.c @@ -139,11 +139,39 @@ static long osdElemActionsOnEnter(const OSD_Entry *from) #define OSD_ELEMENT_ENTRY(name, osd_item_id) OSD_ITEM_ENTRY(name, osd_item_id) +static const OSD_Entry menuCrsfRxEntries[]= +{ + OSD_LABEL_ENTRY("-- CRSF RX --"), + + OSD_SETTING_ENTRY("CRSF SNR LEVEL", SETTING_OSD_SNR_ALARM), + OSD_ELEMENT_ENTRY("RX RSSI DBM", OSD_RX_RSSI_DBM), + OSD_ELEMENT_ENTRY("RX LQ", OSD_RX_LQ), + OSD_ELEMENT_ENTRY("RX SNR ALARM", OSD_RX_SNR_DB), + OSD_ELEMENT_ENTRY("TX POWER", OSD_TX_POWER), + OSD_ELEMENT_ENTRY("TX MODE", OSD_TX_MODE), + + OSD_BACK_AND_END_ENTRY, +}; + +const CMS_Menu cmsx_menuCrsf = { +#ifdef CMS_MENU_DEBUG + .GUARD_text = "MENUCRF", + .GUARD_type = OME_MENU, +#endif + .onEnter = NULL, + .onExit = NULL, + .onGlobalExit = NULL, + .entries = menuCrsfRxEntries, +}; + static const OSD_Entry menuOsdElemsEntries[] = { OSD_LABEL_ENTRY("--- OSD ITEMS ---"), OSD_ELEMENT_ENTRY("RSSI", OSD_RSSI_VALUE), +#ifdef USE_SERIALRX_CRSF + OSD_SUBMENU_ENTRY("CRSF RX", &cmsx_menuCrsf), +#endif // CRSF Menu OSD_ELEMENT_ENTRY("MAIN BATTERY", OSD_MAIN_BATT_VOLTAGE), OSD_ELEMENT_ENTRY("MAIN BATT SC", OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE), OSD_ELEMENT_ENTRY("CELL VOLTAGE", OSD_MAIN_BATT_CELL_VOLTAGE), diff --git a/src/main/drivers/osd_symbols.h b/src/main/drivers/osd_symbols.h index d82d1c197f5..244decd89f8 100644 --- a/src/main/drivers/osd_symbols.h +++ b/src/main/drivers/osd_symbols.h @@ -240,6 +240,12 @@ #define SYM_HUD_ARROWS_D2 0x1AC // 428 2 arrows down #define SYM_HUD_ARROWS_D3 0x1AD // 429 3 arrows down +#define SYM_2RSS 0xEA // RSSI 2 +#define SYM_DB 0xEB // dB +#define SYM_DBM 0xEC // dBm +#define SYM_SRN 0xEE // SNR +#define SYM_MW 0xED // mW + #else #define TEMP_SENSOR_SYM_COUNT 0 diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 9b75e06c398..b99c7185bb7 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2710,6 +2710,12 @@ groups: condition: USE_BARO min: -550 max: 1250 + - name: osd_snr_alarm + description: "Value below which Crossfire SNR Alarm pops-up. (dB)" + default_value: "8" + field: snr_alarm + min: -12 + max: 8 - name: osd_temp_label_align description: "Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT`" default_value: "LEFT" diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 945acbf6354..7de190440c8 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1211,7 +1211,7 @@ static bool osdDrawSingleElement(uint8_t item) uint8_t elemPosX = OSD_X(pos); uint8_t elemPosY = OSD_Y(pos); textAttributes_t elemAttr = TEXT_ATTRIBUTES_NONE; - char buff[32]; + char buff[32] = {0}; switch (item) { case OSD_RSSI_VALUE: @@ -1635,6 +1635,63 @@ static bool osdDrawSingleElement(uint8_t item) return true; } + case OSD_RX_RSSI_DBM: + if (rxLinkStatistics.activeAnt == 0) { + buff[0] = SYM_RSSI; + tfp_sprintf(buff + 1, "%4d%c", rxLinkStatistics.uplinkRSSI, SYM_DBM); + if (FLIGHT_MODE(FAILSAFE_MODE)){ + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } else { + buff[0] = SYM_2RSS; + tfp_sprintf(buff + 1, "%4d%c", rxLinkStatistics.uplinkRSSI, SYM_DBM); + if (FLIGHT_MODE(FAILSAFE_MODE)){ + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } + break; + + case OSD_RX_LQ: + buff[0] = SYM_BLANK; + tfp_sprintf(buff + 1, "%d:%3d%s", rxLinkStatistics.rfMode, rxLinkStatistics.uplinkLQ, "%"); + break; + + case OSD_RX_SNR_DB: { + const char* strn = " "; + int16_t osdSNR_Alarm = rxLinkStatistics.uplinkSNR; + if (osdSNR_Alarm <= osdConfig()->snr_alarm) { + buff[0] = SYM_SRN; + tfp_sprintf(buff + 1, "%3d%c", rxLinkStatistics.uplinkSNR, SYM_DB); + } + else if (osdSNR_Alarm > osdConfig()->snr_alarm) { + buff[0] = SYM_BLANK; + tfp_sprintf(buff + 1, "%s", strn); + } + break; + } + + case OSD_TX_MODE: { // This is not really needed but... LOW=4Hz, HIGH=150Hz, NORM=50Hz RFMode + const char* str; + switch (rxLinkStatistics.rfMode) { + case 0: + str = "LOW"; + break; + case 2: + str = "HIGH"; + break; + default: + str = "NORM"; + break; + } + tfp_sprintf(buff, str); + break; + } + + case OSD_TX_POWER: { + tfp_sprintf(buff, "%4d%c", rxLinkStatistics.uplinkTXPower, SYM_MW); + break; + } + case OSD_CROSSHAIRS: // Hud is a sub-element of the crosshair osdCrosshairPosition(&elemPosX, &elemPosY); @@ -2604,12 +2661,20 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) osdLayoutsConfig->item_pos[0][OSD_CRAFT_NAME] = OSD_POS(20, 2); osdLayoutsConfig->item_pos[0][OSD_VTX_CHANNEL] = OSD_POS(8, 6); - osdLayoutsConfig->item_pos[0][OSD_ONTIME] = OSD_POS(23, 8); - osdLayoutsConfig->item_pos[0][OSD_FLYTIME] = OSD_POS(23, 9); - osdLayoutsConfig->item_pos[0][OSD_ONTIME_FLYTIME] = OSD_POS(23, 11) | OSD_VISIBLE_FLAG; - osdLayoutsConfig->item_pos[0][OSD_RTC_TIME] = OSD_POS(23, 12); - osdLayoutsConfig->item_pos[0][OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH] = OSD_POS(23, 7); - osdLayoutsConfig->item_pos[0][OSD_REMAINING_DISTANCE_BEFORE_RTH] = OSD_POS(23, 6); +#ifdef USE_SERIALRX_CRSF + osdConfig->item_pos[0][OSD_RX_RSSI_DBM] = OSD_POS(23, 12); + osdConfig->item_pos[0][OSD_RX_LQ] = OSD_POS(22, 11); + osdConfig->item_pos[0][OSD_RX_SNR_DB] = OSD_POS(24, 9); + osdConfig->item_pos[0][OSD_TX_MODE] = OSD_POS(25, 0); + osdConfig->item_pos[0][OSD_TX_POWER] = OSD_POS(24, 10); +#endif + + osdConfig->item_pos[0][OSD_ONTIME] = OSD_POS(23, 8); + osdConfig->item_pos[0][OSD_FLYTIME] = OSD_POS(23, 9); + osdConfig->item_pos[0][OSD_ONTIME_FLYTIME] = OSD_POS(23, 11) | OSD_VISIBLE_FLAG; + osdConfig->item_pos[0][OSD_RTC_TIME] = OSD_POS(23, 12); + osdConfig->item_pos[0][OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH] = OSD_POS(23, 7); + osdConfig->item_pos[0][OSD_REMAINING_DISTANCE_BEFORE_RTH] = OSD_POS(23, 6); osdLayoutsConfig->item_pos[0][OSD_GPS_SATS] = OSD_POS(0, 11) | OSD_VISIBLE_FLAG; osdLayoutsConfig->item_pos[0][OSD_GPS_HDOP] = OSD_POS(0, 10); @@ -2693,7 +2758,7 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) for (unsigned ii = 1; ii < OSD_LAYOUT_COUNT; ii++) { for (unsigned jj = 0; jj < ARRAYLEN(osdLayoutsConfig->item_pos[0]); jj++) { - osdLayoutsConfig->item_pos[ii][jj] = osdLayoutsConfig->item_pos[0][jj] & ~OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[ii][jj] = osdLayoutsConfig->item_pos[0][jj] & ~OSD_VISIBLE_FLAG; } } } diff --git a/src/main/io/osd.h b/src/main/io/osd.h index f1510ac41ba..376cf90b56a 100755 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -152,7 +152,15 @@ typedef enum { OSD_VTX_POWER, OSD_ESC_RPM, OSD_ESC_TEMPERATURE, +<<<<<<< HEAD OSD_AZIMUTH, +======= + OSD_RX_RSSI_DBM, + OSD_RX_LQ, + OSD_RX_SNR_DB, + OSD_TX_MODE, + OSD_TX_POWER, +>>>>>>> b8920077b... Atomiclama and my mods OSD_ITEM_COUNT // MUST BE LAST } osd_items_e; @@ -220,6 +228,9 @@ typedef struct osdConfig_s { float gforce_alarm; float gforce_axis_alarm_min; float gforce_axis_alarm_max; +#ifdef USE_SERIALRX_CRSF + int16_t snr_alarm; //CRSF SNR alarm in dB +#endif #ifdef USE_BARO int16_t baro_temp_alarm_min; int16_t baro_temp_alarm_max; @@ -249,7 +260,7 @@ typedef struct osdConfig_s { uint16_t hud_radar_range_max; uint16_t hud_radar_nearest; uint8_t hud_wp_disp; - + uint8_t left_sidebar_scroll; // from osd_sidebar_scroll_e uint8_t right_sidebar_scroll; // from osd_sidebar_scroll_e uint8_t sidebar_scroll_arrows; diff --git a/src/main/rx/crsf.c b/src/main/rx/crsf.c index a4fd468661b..698023faa8a 100755 --- a/src/main/rx/crsf.c +++ b/src/main/rx/crsf.c @@ -58,6 +58,8 @@ static timeUs_t crsfFrameStartAt = 0; static uint8_t telemetryBuf[CRSF_FRAME_SIZE_MAX]; static uint8_t telemetryBufLen = 0; +// The power levels represented by uplinkTXPower above in mW (Is 250 missing? Check TX lite powers) +const uint16_t crsfPowerStates[] = {0, 10, 25, 100, 500, 1000, 2000}; /* * CRSF protocol @@ -108,7 +110,7 @@ struct crsfPayloadRcChannelsPacked_s { typedef struct crsfPayloadRcChannelsPacked_s crsfPayloadRcChannelsPacked_t; -struct crsfPayloadLinkStatistics_s { +typedef struct crsfPayloadLinkStatistics_s { uint8_t uplinkRSSIAnt1; uint8_t uplinkRSSIAnt2; uint8_t uplinkLQ; @@ -119,7 +121,8 @@ struct crsfPayloadLinkStatistics_s { uint8_t downlinkRSSI; uint8_t downlinkLQ; int8_t downlinkSNR; -} __attribute__ ((__packed__)); + uint8_t activeAnt; +} __attribute__ ((__packed__)) crsfPayloadLinkStatistics_t; typedef struct crsfPayloadLinkStatistics_s crsfPayloadLinkStatistics_t; @@ -229,12 +232,14 @@ STATIC_UNIT_TESTED uint8_t crsfFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig) } crsfFrame.frame.frameLength = CRSF_FRAME_LINK_STATISTICS_PAYLOAD_SIZE + CRSF_FRAME_LENGTH_TYPE_CRC; - // Inject link quality into channel 17 const crsfPayloadLinkStatistics_t* linkStats = (crsfPayloadLinkStatistics_t*)&crsfFrame.frame.payload; - crsfChannelData[16] = scaleRange(constrain(linkStats->uplinkLQ, 0, 100), 0, 100, 191, 1791); // will map to [1000;2000] range - - lqTrackerSet(rxRuntimeConfig->lqTracker, scaleRange(constrain(linkStats->uplinkLQ, 0, 100), 0, 100, 0, RSSI_MAX_VALUE)); + rxLinkStatistics.uplinkRSSI = -1* (linkStats->activeAntenna ? linkStats->uplinkRSSIAnt2 : linkStats->uplinkRSSIAnt1); + rxLinkStatistics.uplinkLQ = linkStats->uplinkLQ; + rxLinkStatistics.uplinkSNR = linkStats->uplinkSNR; + rxLinkStatistics.rfMode = linkStats->rfMode; + rxLinkStatistics.uplinkTXPower = crsfPowerStates[linkStats->uplinkTXPower]; + rxLinkStatistics.activeAnt = linkStats->activeAntenna; // This is not RC channels frame, update channel value but don't indicate frame completion return RX_FRAME_PENDING; diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 740a6050977..5c2110f7914 100755 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -102,6 +102,7 @@ static rcChannel_t rcChannels[MAX_SUPPORTED_RC_CHANNEL_COUNT]; #define SKIP_RC_ON_SUSPEND_PERIOD 1500000 // 1.5 second period in usec (call frequency independent) #define SKIP_RC_SAMPLES_ON_RESUME 2 // flush 2 samples to drop wrong measurements (timing independent) +rxLinkStatistics_t rxLinkStatistics; rxRuntimeConfig_t rxRuntimeConfig; static uint8_t rcSampleIndex = 0; diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index 89523190e47..9160619d6f1 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -175,8 +175,18 @@ typedef enum { RSSI_SOURCE_MSP, } rssiSource_e; -extern rxRuntimeConfig_t rxRuntimeConfig; //!!TODO remove this extern, only needed once for channelCount +typedef struct rxLinkStatistics_s { + int16_t uplinkRSSI; // RSSI value dBm of 1RSS + int16_t uplinkRSS2; // RSSI value dBm of 2RSS + uint8_t uplinkLQ; // A protocol specific measure of the link quality in [0..100] + int8_t uplinkSNR; // The SNR of the uplink in dB + uint8_t rfMode; // A protocol specific measure of the transmission bandwidth in [0..2] + uint16_t uplinkTXPower; // power in mW + uint8_t activeAnt; +} rxLinkStatistics_t; +extern rxRuntimeConfig_t rxRuntimeConfig; //!!TODO remove this extern, only needed once for channelCount +extern rxLinkStatistics_t rxLinkStatistics; void lqTrackerReset(rxLinkQualityTracker_e * lqTracker); void lqTrackerAccumulate(rxLinkQualityTracker_e * lqTracker, uint16_t rawValue); void lqTrackerSet(rxLinkQualityTracker_e * lqTracker, uint16_t rawValue); From 2cde37585169afc6af81b389dd7ab4cb505a4c99 Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Sat, 8 Aug 2020 14:04:13 -0400 Subject: [PATCH 178/248] Changed OSD_TX_MODE to OSD_RF_MODE --- src/main/cms/cms_menu_osd.c | 2 +- src/main/io/osd.c | 4 ++-- src/main/io/osd.h | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/cms/cms_menu_osd.c b/src/main/cms/cms_menu_osd.c index 76dd8941e2e..df4ee35125e 100755 --- a/src/main/cms/cms_menu_osd.c +++ b/src/main/cms/cms_menu_osd.c @@ -148,7 +148,7 @@ static const OSD_Entry menuCrsfRxEntries[]= OSD_ELEMENT_ENTRY("RX LQ", OSD_RX_LQ), OSD_ELEMENT_ENTRY("RX SNR ALARM", OSD_RX_SNR_DB), OSD_ELEMENT_ENTRY("TX POWER", OSD_TX_POWER), - OSD_ELEMENT_ENTRY("TX MODE", OSD_TX_MODE), + OSD_ELEMENT_ENTRY("RX MODE", OSD_RF_MODE), OSD_BACK_AND_END_ENTRY, }; diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 7de190440c8..2c83711a9ae 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1670,7 +1670,7 @@ static bool osdDrawSingleElement(uint8_t item) break; } - case OSD_TX_MODE: { // This is not really needed but... LOW=4Hz, HIGH=150Hz, NORM=50Hz RFMode + case OSD_RF_MODE: { // This is not really needed but... LOW=4Hz, HIGH=150Hz, NORM=50Hz RFMode const char* str; switch (rxLinkStatistics.rfMode) { case 0: @@ -2665,7 +2665,7 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) osdConfig->item_pos[0][OSD_RX_RSSI_DBM] = OSD_POS(23, 12); osdConfig->item_pos[0][OSD_RX_LQ] = OSD_POS(22, 11); osdConfig->item_pos[0][OSD_RX_SNR_DB] = OSD_POS(24, 9); - osdConfig->item_pos[0][OSD_TX_MODE] = OSD_POS(25, 0); + osdConfig->item_pos[0][OSD_RF_MODE] = OSD_POS(25, 0); osdConfig->item_pos[0][OSD_TX_POWER] = OSD_POS(24, 10); #endif diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 376cf90b56a..4adf189d906 100755 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -158,7 +158,7 @@ typedef enum { OSD_RX_RSSI_DBM, OSD_RX_LQ, OSD_RX_SNR_DB, - OSD_TX_MODE, + OSD_RF_MODE, OSD_TX_POWER, >>>>>>> b8920077b... Atomiclama and my mods OSD_ITEM_COUNT // MUST BE LAST From 275b0219e8a6abfe02af67c74e8fb930961728f6 Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Sat, 8 Aug 2020 20:31:21 -0400 Subject: [PATCH 179/248] Changed menu sort --- src/main/cms/cms_menu_osd.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/cms/cms_menu_osd.c b/src/main/cms/cms_menu_osd.c index df4ee35125e..7d893a8c289 100755 --- a/src/main/cms/cms_menu_osd.c +++ b/src/main/cms/cms_menu_osd.c @@ -147,8 +147,8 @@ static const OSD_Entry menuCrsfRxEntries[]= OSD_ELEMENT_ENTRY("RX RSSI DBM", OSD_RX_RSSI_DBM), OSD_ELEMENT_ENTRY("RX LQ", OSD_RX_LQ), OSD_ELEMENT_ENTRY("RX SNR ALARM", OSD_RX_SNR_DB), - OSD_ELEMENT_ENTRY("TX POWER", OSD_TX_POWER), OSD_ELEMENT_ENTRY("RX MODE", OSD_RF_MODE), + OSD_ELEMENT_ENTRY("TX POWER", OSD_TX_POWER), OSD_BACK_AND_END_ENTRY, }; From 68f3f508f7c229ace72967ba3f4701e6f10de317 Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Sun, 9 Aug 2020 00:19:36 -0400 Subject: [PATCH 180/248] Updated OSD_RX_SNR_DB to use displayWrite --- src/main/io/osd.c | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 2c83711a9ae..c9063cfc68c 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1657,15 +1657,13 @@ static bool osdDrawSingleElement(uint8_t item) break; case OSD_RX_SNR_DB: { - const char* strn = " "; int16_t osdSNR_Alarm = rxLinkStatistics.uplinkSNR; if (osdSNR_Alarm <= osdConfig()->snr_alarm) { buff[0] = SYM_SRN; tfp_sprintf(buff + 1, "%3d%c", rxLinkStatistics.uplinkSNR, SYM_DB); } else if (osdSNR_Alarm > osdConfig()->snr_alarm) { - buff[0] = SYM_BLANK; - tfp_sprintf(buff + 1, "%s", strn); + displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); } break; } From c3a338ef2c1af60e82ad52bad39ea235f6dd5703 Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Sun, 9 Aug 2020 18:28:50 -0400 Subject: [PATCH 181/248] removed 2RSS. Only one is needed. --- src/main/rx/rx.h | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h index 9160619d6f1..af27191bb7a 100644 --- a/src/main/rx/rx.h +++ b/src/main/rx/rx.h @@ -176,11 +176,10 @@ typedef enum { } rssiSource_e; typedef struct rxLinkStatistics_s { - int16_t uplinkRSSI; // RSSI value dBm of 1RSS - int16_t uplinkRSS2; // RSSI value dBm of 2RSS + int16_t uplinkRSSI; // RSSI value in dBm uint8_t uplinkLQ; // A protocol specific measure of the link quality in [0..100] int8_t uplinkSNR; // The SNR of the uplink in dB - uint8_t rfMode; // A protocol specific measure of the transmission bandwidth in [0..2] + uint8_t rfMode; // A protocol specific measure of the transmission bandwidth [2 = 150Hz, 1 = 50Hz, 0 = 4Hz] uint16_t uplinkTXPower; // power in mW uint8_t activeAnt; } rxLinkStatistics_t; From 8b83c71433fb4e56c39e4393b2007d7d31b3e96f Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Sun, 9 Aug 2020 21:06:40 -0400 Subject: [PATCH 182/248] Update osd.c Changed how to check if RX data is being received for CRSF RSSI to make the reading blink if the failsafe function is not receiving RX data. --- src/main/io/osd.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index c9063cfc68c..87da334c384 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1639,13 +1639,13 @@ static bool osdDrawSingleElement(uint8_t item) if (rxLinkStatistics.activeAnt == 0) { buff[0] = SYM_RSSI; tfp_sprintf(buff + 1, "%4d%c", rxLinkStatistics.uplinkRSSI, SYM_DBM); - if (FLIGHT_MODE(FAILSAFE_MODE)){ + if (!failsafeIsReceivingRxData()){ TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); } } else { buff[0] = SYM_2RSS; tfp_sprintf(buff + 1, "%4d%c", rxLinkStatistics.uplinkRSSI, SYM_DBM); - if (FLIGHT_MODE(FAILSAFE_MODE)){ + if (!failsafeIsReceivingRxData()){ TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); } } From 182fe929ccdd6bf1e0927376bcc1f3b512efa606 Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Sun, 16 Aug 2020 09:09:33 -0400 Subject: [PATCH 183/248] Removed RX Mode Removed. It's redundant and only works for Crossfire. RFMode is displayed to the left of LQ% and works with CRSF and ExpressLRS. --- src/main/cms/cms_menu_osd.c | 1 - src/main/io/osd.c | 22 ++++------------------ 2 files changed, 4 insertions(+), 19 deletions(-) diff --git a/src/main/cms/cms_menu_osd.c b/src/main/cms/cms_menu_osd.c index 7d893a8c289..dcc5e97774d 100755 --- a/src/main/cms/cms_menu_osd.c +++ b/src/main/cms/cms_menu_osd.c @@ -147,7 +147,6 @@ static const OSD_Entry menuCrsfRxEntries[]= OSD_ELEMENT_ENTRY("RX RSSI DBM", OSD_RX_RSSI_DBM), OSD_ELEMENT_ENTRY("RX LQ", OSD_RX_LQ), OSD_ELEMENT_ENTRY("RX SNR ALARM", OSD_RX_SNR_DB), - OSD_ELEMENT_ENTRY("RX MODE", OSD_RF_MODE), OSD_ELEMENT_ENTRY("TX POWER", OSD_TX_POWER), OSD_BACK_AND_END_ENTRY, diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 87da334c384..bb7160e28c0 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1657,34 +1657,20 @@ static bool osdDrawSingleElement(uint8_t item) break; case OSD_RX_SNR_DB: { + char const strn = " "; int16_t osdSNR_Alarm = rxLinkStatistics.uplinkSNR; if (osdSNR_Alarm <= osdConfig()->snr_alarm) { buff[0] = SYM_SRN; tfp_sprintf(buff + 1, "%3d%c", rxLinkStatistics.uplinkSNR, SYM_DB); } else if (osdSNR_Alarm > osdConfig()->snr_alarm) { - displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); + //displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); + buff[0] = SYM_SRN; + tfp_sprintf(buff + 1, "%s%c", strn, SYM_DB); } break; } - case OSD_RF_MODE: { // This is not really needed but... LOW=4Hz, HIGH=150Hz, NORM=50Hz RFMode - const char* str; - switch (rxLinkStatistics.rfMode) { - case 0: - str = "LOW"; - break; - case 2: - str = "HIGH"; - break; - default: - str = "NORM"; - break; - } - tfp_sprintf(buff, str); - break; - } - case OSD_TX_POWER: { tfp_sprintf(buff, "%4d%c", rxLinkStatistics.uplinkTXPower, SYM_MW); break; From 63e222790d21d9a64deb1d609751fec44a52b2cb Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Sun, 16 Aug 2020 09:13:51 -0400 Subject: [PATCH 184/248] Finished removing rx mode --- src/main/io/osd.c | 1 - src/main/io/osd.h | 1 - 2 files changed, 2 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index bb7160e28c0..64bb2e1480c 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2649,7 +2649,6 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) osdConfig->item_pos[0][OSD_RX_RSSI_DBM] = OSD_POS(23, 12); osdConfig->item_pos[0][OSD_RX_LQ] = OSD_POS(22, 11); osdConfig->item_pos[0][OSD_RX_SNR_DB] = OSD_POS(24, 9); - osdConfig->item_pos[0][OSD_RF_MODE] = OSD_POS(25, 0); osdConfig->item_pos[0][OSD_TX_POWER] = OSD_POS(24, 10); #endif diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 4adf189d906..3e0c205ee64 100755 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -158,7 +158,6 @@ typedef enum { OSD_RX_RSSI_DBM, OSD_RX_LQ, OSD_RX_SNR_DB, - OSD_RF_MODE, OSD_TX_POWER, >>>>>>> b8920077b... Atomiclama and my mods OSD_ITEM_COUNT // MUST BE LAST From 1ab9b3cc146fff379e51515da6218ab2565f2023 Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Sun, 16 Aug 2020 13:12:16 -0400 Subject: [PATCH 185/248] Updates to main osd.c --- src/main/io/osd.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 64bb2e1480c..e367d7e44b2 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1657,11 +1657,11 @@ static bool osdDrawSingleElement(uint8_t item) break; case OSD_RX_SNR_DB: { - char const strn = " "; + const char* strn = " "; int16_t osdSNR_Alarm = rxLinkStatistics.uplinkSNR; if (osdSNR_Alarm <= osdConfig()->snr_alarm) { buff[0] = SYM_SRN; - tfp_sprintf(buff + 1, "%3d%c", rxLinkStatistics.uplinkSNR, SYM_DB); + tfp_sprintf(buff + 1, "%4d%c", rxLinkStatistics.uplinkSNR, SYM_DB); } else if (osdSNR_Alarm > osdConfig()->snr_alarm) { //displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); From f50f27d3150afd9e3f433d206ff2eac39ba72472 Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Sun, 16 Aug 2020 16:16:06 -0400 Subject: [PATCH 186/248] Update osd.c --- src/main/io/osd.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index e367d7e44b2..2ca2977e3f8 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2648,7 +2648,7 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) #ifdef USE_SERIALRX_CRSF osdConfig->item_pos[0][OSD_RX_RSSI_DBM] = OSD_POS(23, 12); osdConfig->item_pos[0][OSD_RX_LQ] = OSD_POS(22, 11); - osdConfig->item_pos[0][OSD_RX_SNR_DB] = OSD_POS(24, 9); + osdConfig->item_pos[0][OSD_RX_SNR_DB] = OSD_POS(23, 9); osdConfig->item_pos[0][OSD_TX_POWER] = OSD_POS(24, 10); #endif From b22bb5ea9bc947afb2073d86fed79f1828466d0e Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Tue, 18 Aug 2020 17:12:13 -0400 Subject: [PATCH 187/248] fixed some line indentations --- src/main/io/osd.c | 30 +++++++++++++++--------------- 1 file changed, 15 insertions(+), 15 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 2ca2977e3f8..8a9aaf0d843 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1635,21 +1635,21 @@ static bool osdDrawSingleElement(uint8_t item) return true; } - case OSD_RX_RSSI_DBM: - if (rxLinkStatistics.activeAnt == 0) { - buff[0] = SYM_RSSI; - tfp_sprintf(buff + 1, "%4d%c", rxLinkStatistics.uplinkRSSI, SYM_DBM); - if (!failsafeIsReceivingRxData()){ - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - } else { - buff[0] = SYM_2RSS; - tfp_sprintf(buff + 1, "%4d%c", rxLinkStatistics.uplinkRSSI, SYM_DBM); - if (!failsafeIsReceivingRxData()){ - TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } - } - break; + case OSD_RX_RSSI_DBM: + if (rxLinkStatistics.activeAnt == 0) { + buff[0] = SYM_RSSI; + tfp_sprintf(buff + 1, "%4d%c", rxLinkStatistics.uplinkRSSI, SYM_DBM); + if (!failsafeIsReceivingRxData()){ + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } else { + buff[0] = SYM_2RSS; + tfp_sprintf(buff + 1, "%4d%c", rxLinkStatistics.uplinkRSSI, SYM_DBM); + if (!failsafeIsReceivingRxData()){ + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } + } + break; case OSD_RX_LQ: buff[0] = SYM_BLANK; From ad6a4b7e91d6070cc259dbadd30c32e37bd79f35 Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Sat, 22 Aug 2020 22:31:12 -0400 Subject: [PATCH 188/248] Name changes --- src/main/cms/cms_menu_osd.c | 8 ++++---- src/main/io/cms_menu_misc.h | 20 ++++++++++++++++++++ src/main/io/osd.c | 16 ++++++++-------- src/main/io/osd.h | 11 ++++------- 4 files changed, 36 insertions(+), 19 deletions(-) create mode 100644 src/main/io/cms_menu_misc.h diff --git a/src/main/cms/cms_menu_osd.c b/src/main/cms/cms_menu_osd.c index dcc5e97774d..bcebb7071bb 100755 --- a/src/main/cms/cms_menu_osd.c +++ b/src/main/cms/cms_menu_osd.c @@ -144,10 +144,10 @@ static const OSD_Entry menuCrsfRxEntries[]= OSD_LABEL_ENTRY("-- CRSF RX --"), OSD_SETTING_ENTRY("CRSF SNR LEVEL", SETTING_OSD_SNR_ALARM), - OSD_ELEMENT_ENTRY("RX RSSI DBM", OSD_RX_RSSI_DBM), - OSD_ELEMENT_ENTRY("RX LQ", OSD_RX_LQ), - OSD_ELEMENT_ENTRY("RX SNR ALARM", OSD_RX_SNR_DB), - OSD_ELEMENT_ENTRY("TX POWER", OSD_TX_POWER), + OSD_ELEMENT_ENTRY("RX RSSI DBM", OSD_CRSF_RSSI_DBM), + OSD_ELEMENT_ENTRY("RX LQ", OSD_CRSF_LQ), + OSD_ELEMENT_ENTRY("RX SNR ALARM", OSD_CRSF_SNR_DB), + OSD_ELEMENT_ENTRY("TX POWER", OSD_CRSF_TX_POWER), OSD_BACK_AND_END_ENTRY, }; diff --git a/src/main/io/cms_menu_misc.h b/src/main/io/cms_menu_misc.h new file mode 100644 index 00000000000..fa776acf004 --- /dev/null +++ b/src/main/io/cms_menu_misc.h @@ -0,0 +1,20 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#pragma once + +extern const CMS_Menu cmsx_menuMisc; diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 8a9aaf0d843..7b2eb25b31b 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1635,7 +1635,7 @@ static bool osdDrawSingleElement(uint8_t item) return true; } - case OSD_RX_RSSI_DBM: + case OSD_CRSF_RSSI_DBM: if (rxLinkStatistics.activeAnt == 0) { buff[0] = SYM_RSSI; tfp_sprintf(buff + 1, "%4d%c", rxLinkStatistics.uplinkRSSI, SYM_DBM); @@ -1651,12 +1651,12 @@ static bool osdDrawSingleElement(uint8_t item) } break; - case OSD_RX_LQ: + case OSD_CRSF_LQ: buff[0] = SYM_BLANK; tfp_sprintf(buff + 1, "%d:%3d%s", rxLinkStatistics.rfMode, rxLinkStatistics.uplinkLQ, "%"); break; - case OSD_RX_SNR_DB: { + case OSD_CRSF_SNR_DB: { const char* strn = " "; int16_t osdSNR_Alarm = rxLinkStatistics.uplinkSNR; if (osdSNR_Alarm <= osdConfig()->snr_alarm) { @@ -1671,7 +1671,7 @@ static bool osdDrawSingleElement(uint8_t item) break; } - case OSD_TX_POWER: { + case OSD_CRSF_TX_POWER: { tfp_sprintf(buff, "%4d%c", rxLinkStatistics.uplinkTXPower, SYM_MW); break; } @@ -2646,10 +2646,10 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) osdLayoutsConfig->item_pos[0][OSD_VTX_CHANNEL] = OSD_POS(8, 6); #ifdef USE_SERIALRX_CRSF - osdConfig->item_pos[0][OSD_RX_RSSI_DBM] = OSD_POS(23, 12); - osdConfig->item_pos[0][OSD_RX_LQ] = OSD_POS(22, 11); - osdConfig->item_pos[0][OSD_RX_SNR_DB] = OSD_POS(23, 9); - osdConfig->item_pos[0][OSD_TX_POWER] = OSD_POS(24, 10); + osdConfig->item_pos[0][OSD_CRSF_RSSI_DBM] = OSD_POS(23, 12); + osdConfig->item_pos[0][OSD_CRSF_LQ] = OSD_POS(22, 11); + osdConfig->item_pos[0][OSD_CRSF_SNR_DB] = OSD_POS(23, 9); + osdConfig->item_pos[0][OSD_CRSF_TX_POWER] = OSD_POS(24, 10); #endif osdConfig->item_pos[0][OSD_ONTIME] = OSD_POS(23, 8); diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 3e0c205ee64..f05a268ef5d 100755 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -152,14 +152,11 @@ typedef enum { OSD_VTX_POWER, OSD_ESC_RPM, OSD_ESC_TEMPERATURE, -<<<<<<< HEAD OSD_AZIMUTH, -======= - OSD_RX_RSSI_DBM, - OSD_RX_LQ, - OSD_RX_SNR_DB, - OSD_TX_POWER, ->>>>>>> b8920077b... Atomiclama and my mods + OSD_CRSF_RSSI_DBM, + OSD_CRSF_LQ, + OSD_CRSF_SNR_DB, + OSD_CRSF_TX_POWER, OSD_ITEM_COUNT // MUST BE LAST } osd_items_e; From a356e5bb5e7d9fc2dedf1f7100117e8cac04a5b2 Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Mon, 24 Aug 2020 21:38:10 -0400 Subject: [PATCH 189/248] changed variable name just because --- src/main/io/osd.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 7b2eb25b31b..a2f013e3525 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1657,7 +1657,7 @@ static bool osdDrawSingleElement(uint8_t item) break; case OSD_CRSF_SNR_DB: { - const char* strn = " "; + const char* hidesnr = " "; int16_t osdSNR_Alarm = rxLinkStatistics.uplinkSNR; if (osdSNR_Alarm <= osdConfig()->snr_alarm) { buff[0] = SYM_SRN; @@ -1666,7 +1666,7 @@ static bool osdDrawSingleElement(uint8_t item) else if (osdSNR_Alarm > osdConfig()->snr_alarm) { //displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); buff[0] = SYM_SRN; - tfp_sprintf(buff + 1, "%s%c", strn, SYM_DB); + tfp_sprintf(buff + 1, "%s%c", hidesnr, SYM_DB); } break; } From 6f2b562bb4f22af2dfc80e3f511ab6db65136a84 Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Tue, 25 Aug 2020 11:59:13 -0400 Subject: [PATCH 190/248] Restored old code that injects LQ into changel 17 for testing. I would like to keep the new and the old options. --- src/main/rx/crsf.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/main/rx/crsf.c b/src/main/rx/crsf.c index 698023faa8a..73ce42b02f7 100755 --- a/src/main/rx/crsf.c +++ b/src/main/rx/crsf.c @@ -232,7 +232,10 @@ STATIC_UNIT_TESTED uint8_t crsfFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig) } crsfFrame.frame.frameLength = CRSF_FRAME_LINK_STATISTICS_PAYLOAD_SIZE + CRSF_FRAME_LENGTH_TYPE_CRC; + // Inject link quality into channel 17. const crsfPayloadLinkStatistics_t* linkStats = (crsfPayloadLinkStatistics_t*)&crsfFrame.frame.payload; + crsfChannelData[16] = scaleRange(constrain(linkStats->uplinkLQ, 0, 100), 0, 100, 191, 1791); // will map to [1000;2000] range + lqTrackerSet(rxRuntimeConfig->lqTracker, scaleRange(constrain(linkStats->uplinkLQ, 0, 100), 0, 100, 0, RSSI_MAX_VALUE)); rxLinkStatistics.uplinkRSSI = -1* (linkStats->activeAntenna ? linkStats->uplinkRSSIAnt2 : linkStats->uplinkRSSIAnt1); rxLinkStatistics.uplinkLQ = linkStats->uplinkLQ; From 2d81adaebca519c230b43ff6d543370a5e4a2a87 Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Tue, 25 Aug 2020 21:04:13 -0400 Subject: [PATCH 191/248] Clear LQ if telemetry lost. --- src/main/io/osd.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index a2f013e3525..36588f7813e 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1654,6 +1654,9 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_CRSF_LQ: buff[0] = SYM_BLANK; tfp_sprintf(buff + 1, "%d:%3d%s", rxLinkStatistics.rfMode, rxLinkStatistics.uplinkLQ, "%"); + if (!failsafeIsReceivingRxData()){ + displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); + } break; case OSD_CRSF_SNR_DB: { From 09e2c5aa8f88e34bc8313ffa74f16187eda95ff1 Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Thu, 27 Aug 2020 13:40:47 -0400 Subject: [PATCH 192/248] added blink to LQ when telemetry is lost Also added one space to clear SNR for when -30dB is received. --- src/main/io/osd.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 36588f7813e..9f8170fa53f 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1654,13 +1654,13 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_CRSF_LQ: buff[0] = SYM_BLANK; tfp_sprintf(buff + 1, "%d:%3d%s", rxLinkStatistics.rfMode, rxLinkStatistics.uplinkLQ, "%"); - if (!failsafeIsReceivingRxData()){ - displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); - } + if (!failsafeIsReceivingRxData()){ + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } break; case OSD_CRSF_SNR_DB: { - const char* hidesnr = " "; + const char* hidesnr = " "; int16_t osdSNR_Alarm = rxLinkStatistics.uplinkSNR; if (osdSNR_Alarm <= osdConfig()->snr_alarm) { buff[0] = SYM_SRN; From 048bbc9755c540442db371203434c03aee21d7dd Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 27 Aug 2020 22:50:47 +0200 Subject: [PATCH 193/248] Name changes --- src/main/io/osd.c | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 9f8170fa53f..a3db4547da9 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2649,18 +2649,18 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) osdLayoutsConfig->item_pos[0][OSD_VTX_CHANNEL] = OSD_POS(8, 6); #ifdef USE_SERIALRX_CRSF - osdConfig->item_pos[0][OSD_CRSF_RSSI_DBM] = OSD_POS(23, 12); - osdConfig->item_pos[0][OSD_CRSF_LQ] = OSD_POS(22, 11); - osdConfig->item_pos[0][OSD_CRSF_SNR_DB] = OSD_POS(23, 9); - osdConfig->item_pos[0][OSD_CRSF_TX_POWER] = OSD_POS(24, 10); + osdLayoutsConfig->item_pos[0][OSD_CRSF_RSSI_DBM] = OSD_POS(23, 12); + osdLayoutsConfig->item_pos[0][OSD_CRSF_LQ] = OSD_POS(22, 11); + osdLayoutsConfig->item_pos[0][OSD_CRSF_SNR_DB] = OSD_POS(23, 9); + osdLayoutsConfig->item_pos[0][OSD_CRSF_TX_POWER] = OSD_POS(24, 10); #endif - osdConfig->item_pos[0][OSD_ONTIME] = OSD_POS(23, 8); - osdConfig->item_pos[0][OSD_FLYTIME] = OSD_POS(23, 9); - osdConfig->item_pos[0][OSD_ONTIME_FLYTIME] = OSD_POS(23, 11) | OSD_VISIBLE_FLAG; - osdConfig->item_pos[0][OSD_RTC_TIME] = OSD_POS(23, 12); - osdConfig->item_pos[0][OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH] = OSD_POS(23, 7); - osdConfig->item_pos[0][OSD_REMAINING_DISTANCE_BEFORE_RTH] = OSD_POS(23, 6); + osdLayoutsConfig->item_pos[0][OSD_ONTIME] = OSD_POS(23, 8); + osdLayoutsConfig->item_pos[0][OSD_FLYTIME] = OSD_POS(23, 9); + osdLayoutsConfig->item_pos[0][OSD_ONTIME_FLYTIME] = OSD_POS(23, 11) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_RTC_TIME] = OSD_POS(23, 12); + osdLayoutsConfig->item_pos[0][OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH] = OSD_POS(23, 7); + osdLayoutsConfig->item_pos[0][OSD_REMAINING_DISTANCE_BEFORE_RTH] = OSD_POS(23, 6); osdLayoutsConfig->item_pos[0][OSD_GPS_SATS] = OSD_POS(0, 11) | OSD_VISIBLE_FLAG; osdLayoutsConfig->item_pos[0][OSD_GPS_HDOP] = OSD_POS(0, 10); From ef12bf84086a92950e573652e25514cbe9d07c48 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Fri, 28 Aug 2020 10:53:07 +0200 Subject: [PATCH 194/248] [FPORT2] fix halfduplex tristate (#6079) --- src/main/rx/fport2.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/rx/fport2.c b/src/main/rx/fport2.c index f2382d1d123..93dbe104f9e 100644 --- a/src/main/rx/fport2.c +++ b/src/main/rx/fport2.c @@ -656,7 +656,7 @@ bool fport2RxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig NULL, FPORT2_BAUDRATE, MODE_RXTX, - FPORT2_PORT_OPTIONS | (rxConfig->serialrx_inverted ? 0 : SERIAL_INVERTED) | (rxConfig->halfDuplex ? SERIAL_BIDIR : 0) + FPORT2_PORT_OPTIONS | (rxConfig->serialrx_inverted ? 0 : SERIAL_INVERTED) | (tristateWithDefaultOnIsActive(rxConfig->halfDuplex) ? SERIAL_BIDIR : 0) ); if (fportPort) { From fdec03ac50dd00942ec7bb93ec8a3a31f8a7f809 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Fri, 28 Aug 2020 10:53:20 +0200 Subject: [PATCH 195/248] [FRSKYPILOT] Switch serialrx protocol default to F.Port2 (#6080) --- src/main/target/FRSKYPILOT/target.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/FRSKYPILOT/target.h b/src/main/target/FRSKYPILOT/target.h index 3a8ddbe2aaf..a92057f4eea 100644 --- a/src/main/target/FRSKYPILOT/target.h +++ b/src/main/target/FRSKYPILOT/target.h @@ -170,7 +170,7 @@ #define SERIAL_PORT_COUNT 8 #define DEFAULT_RX_TYPE RX_TYPE_SERIAL -#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_PROVIDER SERIALRX_FPORT2 #define SERIALRX_UART SERIAL_PORT_USART8 // *************** ADC ***************************** From f3ecb80dbad6adb517d1b786f42883b41235b95f Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 28 Aug 2020 11:01:57 +0200 Subject: [PATCH 196/248] Disable BetaflightF3 target --- make/release.mk | 2 +- make/targets.mk | 2 +- src/main/target/BETAFLIGHTF3/{target.mk => target.mk_} | 0 3 files changed, 2 insertions(+), 2 deletions(-) rename src/main/target/BETAFLIGHTF3/{target.mk => target.mk_} (100%) mode change 100755 => 100644 diff --git a/make/release.mk b/make/release.mk index ecc5955e0cb..3f5de388878 100644 --- a/make/release.mk +++ b/make/release.mk @@ -4,7 +4,7 @@ RELEASE_TARGETS += LUX_RACE RCEXPLORERF3 RMDO SPARKY FALCORE MOTOLAB ANYFC BLUEJ RELEASE_TARGETS += QUANTON REVO SPARKY2 PIKOBLX CLRACINGF4AIR CLRACINGF4AIRV2 PIXRACER BEEROTORF4 ANYFCF7 ANYFCF7_EXTERNAL_BARO RELEASE_TARGETS += ALIENFLIGHTNGF7 -RELEASE_TARGETS += BETAFLIGHTF3 BETAFLIGHTF4 +RELEASE_TARGETS += BETAFLIGHTF4 RELEASE_TARGETS += FF_F35_LIGHTNING FF_FORTINIF4 RELEASE_TARGETS += KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KAKUTEF7HDV diff --git a/make/targets.mk b/make/targets.mk index f3150c9c7b2..d97710cd4fd 100644 --- a/make/targets.mk +++ b/make/targets.mk @@ -72,7 +72,7 @@ $(error Unknown target MCU specified.) endif GROUP_1_TARGETS := AIRHEROF3 AIRHEROF3_QUAD LUX_RACE SPARKY REVO SPARKY2 COLIBRI FALCORE FF_F35_LIGHTNING FF_FORTINIF4 FF_PIKOF4 FF_PIKOF4OSD -GROUP_2_TARGETS := SPRACINGF3 SPRACINGF3MINI SPRACINGF4EVO CLRACINGF4AIR CLRACINGF4AIRV2 BEEROTORF4 BETAFLIGHTF3 BETAFLIGHTF4 PIKOBLX +GROUP_2_TARGETS := SPRACINGF3 SPRACINGF3MINI SPRACINGF4EVO CLRACINGF4AIR CLRACINGF4AIRV2 BEEROTORF4 BETAFLIGHTF4 PIKOBLX GROUP_3_TARGETS := AIRBOTF4 BLUEJAYF4 OMNIBUSF4 OMNIBUSF4PRO FIREWORKSV2 SPARKY2 MATEKF405 OMNIBUSF7 DYSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 OMNIBUSF7NXT OMNIBUSF7V2 ASGARD32F4 GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ALIENFLIGHTNGF7 PIXRACER YUPIF7 MATEKF405SE MATEKF411 MATEKF722 MATEKF405OSD MATEKF405_SERVOS6 NOX GROUP_5_TARGETS := ASGARD32F7 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF4OSD diff --git a/src/main/target/BETAFLIGHTF3/target.mk b/src/main/target/BETAFLIGHTF3/target.mk_ old mode 100755 new mode 100644 similarity index 100% rename from src/main/target/BETAFLIGHTF3/target.mk rename to src/main/target/BETAFLIGHTF3/target.mk_ From e4023b18c3b5316902b2c8458151ffb8ab0e6924 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 28 Aug 2020 11:24:51 +0200 Subject: [PATCH 197/248] Update settings.yml --- src/main/fc/settings.yaml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index c9060f1c9d5..2d65ec4771a 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -404,19 +404,19 @@ groups: min: INT16_MIN max: INT16_MAX - name: maggain_x - description: "Magnetometer calibration X gain. If 0, no calibration or calibration failed" + description: "Magnetometer calibration X gain. If 1024, no calibration or calibration failed" default_value: "1024" field: magGain[X] min: INT16_MIN max: INT16_MAX - name: maggain_y - description: "Magnetometer calibration Y gain. If 0, no calibration or calibration failed" + description: "Magnetometer calibration Y gain. If 1024, no calibration or calibration failed" default_value: "1024" field: magGain[Y] min: INT16_MIN max: INT16_MAX - name: maggain_z - description: "Magnetometer calibration Z gain. If 0, no calibration or calibration failed" + description: "Magnetometer calibration Z gain. If 1024, no calibration or calibration failed" default_value: "1024" field: magGain[Z] min: INT16_MIN From 7ac4afc46ec0d7bfb90d6b0a09bb3919ccaf4622 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Fri, 28 Aug 2020 11:28:21 +0100 Subject: [PATCH 198/248] rename Linux build documentation --- .../{Generic_Linux_development.md => Building in Linux.md} | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename docs/development/{Generic_Linux_development.md => Building in Linux.md} (100%) diff --git a/docs/development/Generic_Linux_development.md b/docs/development/Building in Linux.md similarity index 100% rename from docs/development/Generic_Linux_development.md rename to docs/development/Building in Linux.md From f216c11b6ed1d186d41eec4bcba5d58c93e05ed2 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Fri, 28 Aug 2020 11:29:10 +0100 Subject: [PATCH 199/248] update Linux build documentation for cmake --- docs/development/Building in Linux.md | 154 ++++++++++++++------------ 1 file changed, 82 insertions(+), 72 deletions(-) diff --git a/docs/development/Building in Linux.md b/docs/development/Building in Linux.md index 5e8a782249d..feb86f1d784 100644 --- a/docs/development/Building in Linux.md +++ b/docs/development/Building in Linux.md @@ -1,146 +1,156 @@ # Generic Linux development tools ## Overview -This article endeavours to provide a generic guide for compiling iNav on Linux for iNav after iNav 2.2.1. +This article endeavours to provide a generic guide for compiling inav on Linux for inav 2.6 and later. -iNav requires a reasonably modern `gcc-arm-none-eabi` cross-compiler. Different Linux distros will provide different versions of the cross-compiler. This will range from obsolete versions (e.g. Debian, Ubuntu LTS) to the latest stable release (Arch Linux). +inav requires a reasonably modern `gcc-arm-none-eabi` cross-compiler. Different Linux distros will provide different versions of the cross-compiler. This will range from obsolete versions (e.g. Debian, Ubuntu LTS) to the latest stable release (Arch Linux). -In order to provide a uniform and reasonably modern cross compiler, after release iNav 2.2.1, iNav provides for the installation of a "known good / working" cross compiler, as well as a mechanism to override this if your distro provides a more modern option (e.g Arch Linux). In general, from a security perspective, Linux distros discourage the installation of software from sources other than the official distribution repositories and 'approved' sources (Ubuntu PPA, Arch AUR). The iNav approach of providing a recommended compiler is however both sound and justified: +In order to provide a uniform and reasonably modern cross compiler, inav provides for the installation of a "known good / working" cross compiler, as well as a mechanism to override this if your distro provides a more modern option (e.g Arch Linux). In general, from a security perspective, Linux distros discourage the installation of software from sources other than the official distribution repositories and 'approved' sources (Ubuntu PPA, Arch AUR). The inav approach of providing a recommended compiler is however both sound and justified: -* The cross-compiler is installed from a reputable source (ARM, the company that makes the CPUs used in our UAS) -* Disto cross-compiler are often older than the recommended iNav compiler -* The installed cross-compiler is only used to build iNav and it not obviously / generally available outside of the iNav build environment. +* The cross-compiler is installed from a reputable source (ARM, the company that makes the CPUs used in our flight controllers) +* Disto cross-compiler are often older than the recommended inav compiler +* The installed cross-compiler is only used to build inav and it not obviously / generally available outside of the inav build environment. -There are a however some specific cases for using the distro cross-compiler in preference to that installed by iNav: +There are a however some specific cases for using the distro cross-compiler in preference to that installed by inav: * You are using a distro that installs a more modern compiler (Arch) -* You are using a host platform other than x86_64 (e.g. ia32, AArch64). +* You are using a host platform for which ARM does not provide a compiler (e.g. Linux ia32). However, before we consider the compiler options, it is necessary to install some other dependencies. -## Other Prerequisites +## Prerequisites In addition to a cross-compiler, it is necessary to install some other tools: +* `git` : clone and manage the inav code repository +* `cmake` : generate the build environment +* `make` : run the firmware compilation +* `ruby` : build some generated source files from JSON definitions +* `gcc` (native compiler) : metadata for generated source files + +Note that inav requires `cmake` version 3.13 or later; any distro that provides `cmake` 3.13 will also provide adequate versions of the other tools. + +Note also that Ubuntu 18.04 LTS does NOT provide a modern enough `cmake`; it is recommended that you upgrade to Ubuntu 20.04 LTS which does. + ### Ubuntu / Debian ``` -$ # make sure the system is updated first -$ sudo apt update && sudo apt upgrade -$ sudo apt install gcc git make ruby curl +# make sure the system is updated first +sudo apt update && sudo apt upgrade +sudo apt install gcc git make ruby curl cmake ``` ### Fedora ``` -$ # make sure the system is updated first -$ sudo dnf -y update -$ sudo dnf install gcc git make ruby curl +# make sure the system is updated first +sudo dnf -y update +sudo dnf install gcc git make ruby curl cmake ``` ### Arch ``` -$ # make sure the system is updated first -$ sudo pacman -Syu -$ sudo pacman -S gcc git make ruby curl +# make sure the system is updated first +sudo pacman -Syu +sudo pacman -S gcc git make ruby curl cmake ``` -Once these prerequisites are installed, we can clone the repository to provide a local instance of the iNav source code. +Once these prerequisites are installed, we can clone the repository to provide a local instance of the inav source code. ## Cloning the repository ``` -$ git clone https://github.com/iNavFlight/inav.git +git clone https://github.com/iNavFlight/inav.git ``` Note: If you have a Github account with registered ssh key you can replace the `git clone` command with `git clone git@github.com:iNavFlight/inav.git` instead of the https link. -The `git clone` creates an `inav` directory; we can enter this directory and try and build the firmware. Initially, will probably fail as we have not yet defined the cross-compiler. The following example is from Ubuntu 19.04: +The `git clone` creates an `inav` directory; we can enter this directory and try and build the firmware. -``` -$ cd inav -$ make TARGET=MATEKF405 -make/tools.mk:78: *** **ERROR** your arm-none-eabi-gcc is '7.3.1', but '8.2.1' is expected. Override with 'GCC_REQUIRED_VERSION' in make/local.mk or run 'make arm_sdk_install' to install the right version automatically in the tools folder of this repo. Stop. -``` -We must either install the iNav toolchain cross-compiler (preferred option) or define the distro cross-compiler. +## Build tooling -## Compiler choices +For 2.6 and later, inav uses `cmake` as its primary build tool. `cmake` simplies various platform and hardware dependencies required to cross compile multiple targets. `cmake` still uses GNU `make` to invoke the actual compiler. -### Installing the iNav preferred cross compiler. +## Cmake generate the build environment -In the iNav directory, issue the command `make arm_sdk_install`. The output will be something like the following (only hopefully you do not suffer from "rural broadband"): +The canonanical method of using `cmake` is to create a `build` directory and run the `cmake` and `make` commands from within the `build` directory. So, assuming we've cloned the firmware repository into an `inav` directory, we can issue the following commands to set up the build environment. ``` -$ make arm_sdk_install -mkdir -p tools -mkdir -p downloads -Warning: Illegal date format for -z, --time-cond (and not a file name). -Warning: Disabling time condition. See curl_getdate(3) for valid date syntax. - % Total % Received % Xferd Average Speed Time Time Time Current - Dload Upload Total Spent Left Speed -100 244 100 244 0 0 645 0 --:--:-- --:--:-- --:--:-- 643 -100 102M 100 102M 0 0 1385k 0 0:01:15 0:01:15 --:--:-- 1392k - +cd inav +# first time only, create the build directory +mkdir build +cd build +cmake .. +# note the "..", this is required as it tells cmake where to find its ruleset ``` -Note that the `curl` warning will only occur the first time (as there is no pre-existing iNav-specific cross-compiler installed). +`cmake` will check for the presence of an embedded cross-compiler; if the cross-compiler is not found it will attempt to download the vendor (ARM) GCC cross-compiler. -### Using the Distro compiler. +Note. If you want to use your own cross-compiler, either because you're running a distro (e.g. Arch Linux) that ships a more recent cross-compiler, or you're on a platform for which ARM doesn't provide a cross-compiler (e.g. 32bit Linux), the you should run the `cmake` command as: -If your distro provides a more recent cross compiler, or you're using a host platform other than x86_64 you may choose to use your distro compiler (or have no choice in the case of "not x86_64"). +``` +cmake -DCOMPILER_VERSION_CHECK=OFF .. +``` -You must first install the distro compiler: Arch is the most likely to provide a more modern cross compiler, which would need to be installed as `sudo pacman -S arm-none-eabi-gcc arm-none-eabi-binutils arm-none-eabi-newlib`. +`cmake` will generate a number of files in your `build` directory, including a cache of generated build settings `CMakeCache.txt` and a standard `Makefile`. -There are two options to define the distro compiler version: +## Bulding the firmware -* Invoke `make` with the variable `GCC_REQUIRED_VERSION` set to the distro version. This can be done as: +Once `cmake` has generated the `build/Makefile`, this (and `make`) is used to build the firmware, again from the `build` directory. It is not necessary to re-run `cmake` unless the inav cmake configuration is changed (i.e. a new release) or you wish to swap between the ARM SDK compiler and a distro or other external compiler. - ``` - $ make GCC_REQUIRED_VERSION=$(arm-none-eabi-gcc -dumpversion) - ``` - For convenience, you can create an `alias` or define a shell function. The shell function will be evaluated each time it is invoked, while the alias will be evaluated once (typically at login), for example: +The generated `Makefile` uses different a target selection mechanism from the older (pre 2.6) top level `Makefile`; you can generate a list of targets with `make help` (or, as the list is extremely long), pipe this into a pager, e.g. `make help | less`. - ``` - # bash function, typically in ~/.bashrc - $ makefc() { make GCC_REQUIRED_VERSION=$(arm-none-eabi-gcc -dumpversion) $@; } - export -f makefc +Typically, to build a single target, just pass the target name to `make`; note that unlike eariler releases, `make` without a target specified will build **all** targets. - # or, bash alias, typically in ~/.bash_aliases - $ alias makefc="make GCC_REQUIRED_VERSION=$(arm-none-eabi-gcc -dumpversion) $@" - ``` +``` +# Build the MATEKF405 firmware +make MATEKF405 +``` - then e.g `$ makefc TARGET=MATEKF405` +One can also build multiple targets from a sinlge `make` command: -* or, create the file `make/local.mk` defining the local distro compiler version. +``` +make MATEKF405 MATEKF722 +``` - ``` - $ echo GCC_REQUIRED_VERSION=$(arm-none-eabi-gcc -dumpversion) > make/local.mk - ``` - then use `make` normally, `$ make TARGET=MATEKF405` +The resultant hex file are in the `build` directory. -If you define the distro cross-compiler version in `make/local.mk`, you will need to update `make/local.mk` whenever your disto updates the cross-compiler. +You can then use the INAV Configurator to flash the local `build/inav_TARGET.hex` file, or use `stm32flash` or `dfu-util` directly from the command line. + +[msp-tool](https://github.com/fiam/msp-tool) and [flash.sh](https://github.com/stronnag/mwptools/blob/master/docs/MiscTools.asciidoc#flashsh) provide / describe 3rd party helper tools for command line flashing. -## Building the firmware +### Cleaning + +You can clean out the built files, either for all targets or selectively; a selective clean target is simply defined by prefixing the target name with `clean_`: -By default, `make` builds the REVO target, to build another target, specify the target name to the make command, for example: ``` -make TARGET=MATEKF405 +# clean out every thing +make clean +# clean out single target +make clean_MATEKF405 +# or multiple targets +make clean_MATEKF405 clean_MATEKF722 ``` -The resultant hex file are in the `obj/` directory. -You can use the INAV Configurator to flash the local ```obj/inav_TARGET.hex``` file, or use `stm32flash` or `dfu-util` directly from the command line. +### `cmake` cache maintainance -[msp-tool](https://github.com/fiam/msp-tool) and [flash.sh](https://github.com/stronnag/mwptools/blob/master/docs/MiscTools.asciidoc#flashsh) provide / describe 3rd party helper tools for command line flashing. +`cmake` caches the build environment, so you don't need to rerun `cmake` each time you build a target. Two `make` options are provided to maintain the `cmake` cache. + +* `make edit_cache` +* `make rebuild_cache` + +It is unlikely that the typical user will need to employ these options, other than perhaps to change between the embedded ARM and distro compilers. ## Updating and rebuilding In order to update your local firmware build: * Navigate to the local iNav repository -* Use the following steps to pull the latest changes and rebuild your local version of iNav: +* Use the following steps to pull the latest changes and rebuild your local version of inav firmware from the `build` directory: ``` $ cd inav $ git pull -$ make TARGET= +$ cd build +$ make ``` ## Advanced Usage From a0636eb9f896b83045f61d55858cb2e9b8a6ce6d Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Fri, 28 Aug 2020 11:42:56 +0100 Subject: [PATCH 200/248] refine Linux build document --- docs/development/Building in Linux.md | 18 ++++++++---------- 1 file changed, 8 insertions(+), 10 deletions(-) diff --git a/docs/development/Building in Linux.md b/docs/development/Building in Linux.md index feb86f1d784..af622395288 100644 --- a/docs/development/Building in Linux.md +++ b/docs/development/Building in Linux.md @@ -8,7 +8,7 @@ inav requires a reasonably modern `gcc-arm-none-eabi` cross-compiler. Different In order to provide a uniform and reasonably modern cross compiler, inav provides for the installation of a "known good / working" cross compiler, as well as a mechanism to override this if your distro provides a more modern option (e.g Arch Linux). In general, from a security perspective, Linux distros discourage the installation of software from sources other than the official distribution repositories and 'approved' sources (Ubuntu PPA, Arch AUR). The inav approach of providing a recommended compiler is however both sound and justified: * The cross-compiler is installed from a reputable source (ARM, the company that makes the CPUs used in our flight controllers) -* Disto cross-compiler are often older than the recommended inav compiler +* Disto cross-compilers are often older than the recommended inav compiler * The installed cross-compiler is only used to build inav and it not obviously / generally available outside of the inav build environment. There are a however some specific cases for using the distro cross-compiler in preference to that installed by inav: @@ -16,8 +16,6 @@ There are a however some specific cases for using the distro cross-compiler in p * You are using a distro that installs a more modern compiler (Arch) * You are using a host platform for which ARM does not provide a compiler (e.g. Linux ia32). -However, before we consider the compiler options, it is necessary to install some other dependencies. - ## Prerequisites In addition to a cross-compiler, it is necessary to install some other tools: @@ -62,14 +60,14 @@ git clone https://github.com/iNavFlight/inav.git Note: If you have a Github account with registered ssh key you can replace the `git clone` command with `git clone git@github.com:iNavFlight/inav.git` instead of the https link. -The `git clone` creates an `inav` directory; we can enter this directory and try and build the firmware. +The `git clone` creates an `inav` directory; we can enter this directory, configure the build environment and build firmware. ## Build tooling -For 2.6 and later, inav uses `cmake` as its primary build tool. `cmake` simplies various platform and hardware dependencies required to cross compile multiple targets. `cmake` still uses GNU `make` to invoke the actual compiler. +For 2.6 and later, inav uses `cmake` as its primary build tool. `cmake` simplies various platform and hardware dependencies required to cross compile multiple targets. `cmake` still uses GNU `make` to invoke the actual compiler. It is necessary to configure the build enviroment with `cmake` before we can build any firmware. -## Cmake generate the build environment +## Using `cmake` The canonanical method of using `cmake` is to create a `build` directory and run the `cmake` and `make` commands from within the `build` directory. So, assuming we've cloned the firmware repository into an `inav` directory, we can issue the following commands to set up the build environment. @@ -82,7 +80,7 @@ cmake .. # note the "..", this is required as it tells cmake where to find its ruleset ``` -`cmake` will check for the presence of an embedded cross-compiler; if the cross-compiler is not found it will attempt to download the vendor (ARM) GCC cross-compiler. +`cmake` will check for the presence of an inav-embedded cross-compiler; if this cross-compiler is not found it will attempt to download the vendor (ARM) GCC cross-compiler. Note. If you want to use your own cross-compiler, either because you're running a distro (e.g. Arch Linux) that ships a more recent cross-compiler, or you're on a platform for which ARM doesn't provide a cross-compiler (e.g. 32bit Linux), the you should run the `cmake` command as: @@ -90,11 +88,11 @@ Note. If you want to use your own cross-compiler, either because you're running cmake -DCOMPILER_VERSION_CHECK=OFF .. ``` -`cmake` will generate a number of files in your `build` directory, including a cache of generated build settings `CMakeCache.txt` and a standard `Makefile`. +`cmake` will generate a number of files in your `build` directory, including a cache of generated build settings `CMakeCache.txt` and a `Makefile`. ## Bulding the firmware -Once `cmake` has generated the `build/Makefile`, this (and `make`) is used to build the firmware, again from the `build` directory. It is not necessary to re-run `cmake` unless the inav cmake configuration is changed (i.e. a new release) or you wish to swap between the ARM SDK compiler and a distro or other external compiler. +Once `cmake` has generated the `build/Makefile`, this `Makfile` (with `make`) is used to build the firmware, again from the `build` directory. It is not necessary to re-run `cmake` unless the inav cmake configuration is changed (i.e. a new release) or you wish to swap between the ARM SDK compiler and a distro or other external compiler. The generated `Makefile` uses different a target selection mechanism from the older (pre 2.6) top level `Makefile`; you can generate a list of targets with `make help` (or, as the list is extremely long), pipe this into a pager, e.g. `make help | less`. @@ -113,7 +111,7 @@ make MATEKF405 MATEKF722 The resultant hex file are in the `build` directory. -You can then use the INAV Configurator to flash the local `build/inav_TARGET.hex` file, or use `stm32flash` or `dfu-util` directly from the command line. +You can then use the INAV Configurator to flash the local `build/inav_x.y.z_TARGET.hex` file, or use `stm32flash` or `dfu-util` directly from the command line. [msp-tool](https://github.com/fiam/msp-tool) and [flash.sh](https://github.com/stronnag/mwptools/blob/master/docs/MiscTools.asciidoc#flashsh) provide / describe 3rd party helper tools for command line flashing. From 6e94916cc469339b171950a15506c2b3817cb4db Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Fri, 28 Aug 2020 16:09:51 +0100 Subject: [PATCH 201/248] remove curl from installation requirements --- docs/development/Building in Linux.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/docs/development/Building in Linux.md b/docs/development/Building in Linux.md index af622395288..55f8b380707 100644 --- a/docs/development/Building in Linux.md +++ b/docs/development/Building in Linux.md @@ -34,21 +34,21 @@ Note also that Ubuntu 18.04 LTS does NOT provide a modern enough `cmake`; it is ``` # make sure the system is updated first sudo apt update && sudo apt upgrade -sudo apt install gcc git make ruby curl cmake +sudo apt install gcc git make ruby cmake ``` ### Fedora ``` # make sure the system is updated first sudo dnf -y update -sudo dnf install gcc git make ruby curl cmake +sudo dnf install gcc git make ruby cmake ``` ### Arch ``` # make sure the system is updated first sudo pacman -Syu -sudo pacman -S gcc git make ruby curl cmake +sudo pacman -S gcc git make ruby cmake ``` Once these prerequisites are installed, we can clone the repository to provide a local instance of the inav source code. From 0f5c9b5de38a8858640aec07ec5a2cb50c8f020d Mon Sep 17 00:00:00 2001 From: Airwide Date: Sat, 29 Aug 2020 10:24:03 +0200 Subject: [PATCH 202/248] Added STICK_CENTER_ONCE to airmodeAndAntiWindupHandlingType_e --- src/main/fc/rc_controls.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/fc/rc_controls.h b/src/main/fc/rc_controls.h index b985c603944..14874de0a1e 100644 --- a/src/main/fc/rc_controls.h +++ b/src/main/fc/rc_controls.h @@ -57,7 +57,8 @@ typedef enum { typedef enum { STICK_CENTER = 0, - THROTTLE_THRESHOLD + THROTTLE_THRESHOLD, + STICK_CENTER_ONCE } airmodeAndAntiWindupHandlingType_e; typedef enum { From a8ed83fd758a53f9096cf09312da8309630cdbc7 Mon Sep 17 00:00:00 2001 From: Airwide Date: Sat, 29 Aug 2020 21:32:28 +0200 Subject: [PATCH 203/248] Fixed a bug --- src/main/fc/rc_controls.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/rc_controls.h b/src/main/fc/rc_controls.h index 14874de0a1e..b229de23110 100644 --- a/src/main/fc/rc_controls.h +++ b/src/main/fc/rc_controls.h @@ -59,7 +59,7 @@ typedef enum { STICK_CENTER = 0, THROTTLE_THRESHOLD, STICK_CENTER_ONCE -} airmodeAndAntiWindupHandlingType_e; +} airmodeHandlingType_e; typedef enum { ROL_LO = (1 << (2 * ROLL)), From 24546e4692cec326aa38fe2bc14734a55e6332da Mon Sep 17 00:00:00 2001 From: Airwide Date: Sat, 29 Aug 2020 23:31:19 +0200 Subject: [PATCH 204/248] Added airmodeHandlingType STICK_CENTER_ONCE to logic --- src/main/fc/fc_core.c | 131 ++++++++++++++++++++---------------------- 1 file changed, 63 insertions(+), 68 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 41373acad2d..7919572d8a1 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -513,73 +513,6 @@ void tryArm(void) } } -static void handlePIDAntiWindup(throttleStatus_e throttleStatus) -{ - /* In airmode Iterm should be prevented to grow when Low thottle and Roll + Pitch Centered. - This is needed to prevent Iterm winding on the ground, but keep full stabilisation on 0 throttle while in air - Low Throttle + roll and Pitch centered is assuming the copter is on the ground. Done to prevent complex air/ground detections */ - - static bool antiWindupWasDeactivatedOnce = false; - - // Track if ANTI_WINDUP was activated - if (!ARMING_FLAG(ARMED)) { - antiWindupWasDeactivatedOnce = false; - } - // In MANUAL mode we reset integrators prevent I-term wind-up (PID output is not used in MANUAL) - if (FLIGHT_MODE(MANUAL_MODE) || !ARMING_FLAG(ARMED)) { - DISABLE_STATE(ANTI_WINDUP); - pidResetErrorAccumulators(); - return; - } - - rollPitchStatus_e rollPitchStatus = calculateRollPitchCenterStatus(); - - // Set antiWindupWasDeactivatedOnce to prevent anti windup from being activated again - if ((throttleStatus != THROTTLE_LOW) && (rollPitchStatus != CENTERED)) { - antiWindupWasDeactivatedOnce = true; - } - // At non-zero throttle - always disable ANTI_WINDUP - if (throttleStatus != THROTTLE_LOW) { - DISABLE_STATE(ANTI_WINDUP); - return; - } - // This case applies only to MR when Airmode management is throttle threshold activated - if (rcControlsConfig()->airmodeHandlingType == THROTTLE_THRESHOLD) { - DISABLE_STATE(ANTI_WINDUP); - if (throttleStatus == THROTTLE_LOW && !STATE(AIRMODE_ACTIVE)) { - pidResetErrorAccumulators(); - } - return; - } - if (STATE(AIRPLANE)) { - if (STATE(AIRMODE_ACTIVE)) { - // On airplanes only activate ANTI_WINDUP if throttle = low, roll/pitch = center and ANTI_WINDUP was never activated this flight - if ((rollPitchStatus == CENTERED) && !antiWindupWasDeactivatedOnce) { - ENABLE_STATE(ANTI_WINDUP); - } - else { - DISABLE_STATE(ANTI_WINDUP); - } - } - else { - DISABLE_STATE(ANTI_WINDUP); - } - } - else { // MULTI_ROTOR - if (STATE(AIRMODE_ACTIVE) && !failsafeIsActive()) { - if ((rollPitchStatus == CENTERED) || feature(FEATURE_MOTOR_STOP)) { - ENABLE_STATE(ANTI_WINDUP); - } - else { - DISABLE_STATE(ANTI_WINDUP); - } - } - else { - DISABLE_STATE(ANTI_WINDUP); - } - } -} - void processRx(timeUs_t currentTimeUs) { // Calculate RPY channel data @@ -713,8 +646,70 @@ void processRx(timeUs_t currentTimeUs) } } - handlePIDAntiWindup(throttleStatus); + /* In airmode Iterm should be prevented to grow when Low thottle and Roll + Pitch Centered. + This is needed to prevent Iterm winding on the ground, but keep full stabilisation on 0 throttle while in air + Low Throttle + roll and Pitch centered is assuming the copter is on the ground. Done to prevent complex air/ground detections */ + + if (!ARMING_FLAG(ARMED)) { + DISABLE_STATE(ANTI_WINDUP_DEACTIVATED); + } + // In MANUAL mode we reset integrators prevent I-term wind-up (PID output is not used in MANUAL) + if (FLIGHT_MODE(MANUAL_MODE) || !ARMING_FLAG(ARMED)) { + DISABLE_STATE(ANTI_WINDUP); + pidResetErrorAccumulators(); + } + else if (rcControlsConfig->airmodeHandlingType == STICK_CENTER) { + if (throttleStatus == THROTTLE_LOW) { + if (STATE(AIRMODE_ACTIVE) && !failsafeIsActive()) { + rollPitchStatus_e rollPitchStatus = calculateRollPitchCenterStatus(); + if ((rollPitchStatus == CENTERED) || (feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING_LEGACY))) { + ENABLE_STATE(ANTI_WINDUP); + } + else { + DISABLE_STATE(ANTI_WINDUP); + } + } + else { + DISABLE_STATE(ANTI_WINDUP); + pidResetErrorAccumulators(); + } + } + else { + DISABLE_STATE(ANTI_WINDUP); + } + } + else if (rcControlsConfig->airmodeHandlingType == STICK_CENTER_ONCE) { + rollPitchStatus_e rollPitchStatus = calculateRollPitchCenterStatus(); + if (throttleStatus == THROTTLE_LOW) { + if (STATE(AIRMODE_ACTIVE) && !failsafeIsActive()) { + if ((rollPitchStatus == CENTERED) && !STATE(ANTI_WINDUP_DEACTIVATED)) { + ENABLE_STATE(ANTI_WINDUP); + } + else { + DISABLE_STATE(ANTI_WINDUP); + } + } + else { + DISABLE_STATE(ANTI_WINDUP); + pidResetErrorAccumulators(); + } + } + else { + DISABLE_STATE(ANTI_WINDUP); + if (rollPitchStatus != CENTERED) { + ENABLE_STATE(ANTI_WINDUP_DEACTIVATED); + } + } + } + else if (rcControlsConfig()->airmodeHandlingType == THROTTLE_THRESHOLD) { + DISABLE_STATE(ANTI_WINDUP); + //This case applies only to MR when Airmode management is throttle threshold activated + if (throttleStatus == THROTTLE_LOW && !STATE(AIRMODE_ACTIVE)) { + pidResetErrorAccumulators(); + } + } +//--------------------------------------------------------- if (mixerConfig()->platformType == PLATFORM_AIRPLANE) { DISABLE_FLIGHT_MODE(HEADFREE_MODE); } From 4d26f5e1bff8334529c02f43d45d41c255009ba4 Mon Sep 17 00:00:00 2001 From: Airwide Date: Sun, 30 Aug 2020 00:21:34 +0200 Subject: [PATCH 205/248] Added ANTI_WINDUP_DEACTIVATED to stateFlags --- src/main/fc/runtime_config.h | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/fc/runtime_config.h b/src/main/fc/runtime_config.h index d24ea66a25d..7b28b464688 100644 --- a/src/main/fc/runtime_config.h +++ b/src/main/fc/runtime_config.h @@ -131,6 +131,7 @@ typedef enum { MOVE_FORWARD_ONLY = (1 << 22), SET_REVERSIBLE_MOTORS_FORWARD = (1 << 23), FW_HEADING_USE_YAW = (1 << 24), + ANTI_WINDUP_DEACTIVATED = (1 << 25), } stateFlags_t; #define DISABLE_STATE(mask) (stateFlags &= ~(mask)) From b08d1e6dd85a2cf8397805c29fc187759de5dede Mon Sep 17 00:00:00 2001 From: Airwide Date: Sun, 30 Aug 2020 00:23:38 +0200 Subject: [PATCH 206/248] Added parentheses which was missing --- src/main/fc/fc_core.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 7919572d8a1..cb9c1f3a014 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -659,7 +659,7 @@ void processRx(timeUs_t currentTimeUs) DISABLE_STATE(ANTI_WINDUP); pidResetErrorAccumulators(); } - else if (rcControlsConfig->airmodeHandlingType == STICK_CENTER) { + else if (rcControlsConfig()->airmodeHandlingType == STICK_CENTER) { if (throttleStatus == THROTTLE_LOW) { if (STATE(AIRMODE_ACTIVE) && !failsafeIsActive()) { rollPitchStatus_e rollPitchStatus = calculateRollPitchCenterStatus(); @@ -679,7 +679,7 @@ void processRx(timeUs_t currentTimeUs) DISABLE_STATE(ANTI_WINDUP); } } - else if (rcControlsConfig->airmodeHandlingType == STICK_CENTER_ONCE) { + else if (rcControlsConfig()->airmodeHandlingType == STICK_CENTER_ONCE) { rollPitchStatus_e rollPitchStatus = calculateRollPitchCenterStatus(); if (throttleStatus == THROTTLE_LOW) { if (STATE(AIRMODE_ACTIVE) && !failsafeIsActive()) { @@ -697,9 +697,9 @@ void processRx(timeUs_t currentTimeUs) } else { DISABLE_STATE(ANTI_WINDUP); - if (rollPitchStatus != CENTERED) { + if (rollPitchStatus != CENTERED) { ENABLE_STATE(ANTI_WINDUP_DEACTIVATED); - } + } } } else if (rcControlsConfig()->airmodeHandlingType == THROTTLE_THRESHOLD) { From 75ea5cd210c0079f6b7976b243692c2ec4a230e7 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Sun, 30 Aug 2020 09:53:27 +0100 Subject: [PATCH 207/248] remove obsolete / erroneous / historic dependency requirements --- docs/development/Building in Linux.md | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/docs/development/Building in Linux.md b/docs/development/Building in Linux.md index 55f8b380707..e12d6dbf6ae 100644 --- a/docs/development/Building in Linux.md +++ b/docs/development/Building in Linux.md @@ -24,7 +24,6 @@ In addition to a cross-compiler, it is necessary to install some other tools: * `cmake` : generate the build environment * `make` : run the firmware compilation * `ruby` : build some generated source files from JSON definitions -* `gcc` (native compiler) : metadata for generated source files Note that inav requires `cmake` version 3.13 or later; any distro that provides `cmake` 3.13 will also provide adequate versions of the other tools. @@ -34,21 +33,21 @@ Note also that Ubuntu 18.04 LTS does NOT provide a modern enough `cmake`; it is ``` # make sure the system is updated first sudo apt update && sudo apt upgrade -sudo apt install gcc git make ruby cmake +sudo apt install git make ruby cmake ``` ### Fedora ``` # make sure the system is updated first sudo dnf -y update -sudo dnf install gcc git make ruby cmake +sudo dnf install git make ruby cmake ``` ### Arch ``` # make sure the system is updated first sudo pacman -Syu -sudo pacman -S gcc git make ruby cmake +sudo pacman -S git make ruby cmake ``` Once these prerequisites are installed, we can clone the repository to provide a local instance of the inav source code. From 1cd4b096966e9bcff90ae0de27219a47d155ca9d Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Sun, 30 Aug 2020 10:24:44 +0100 Subject: [PATCH 208/248] add dependencies but otherwise disclaim information about unit tests --- docs/development/Building in Linux.md | 2 ++ 1 file changed, 2 insertions(+) diff --git a/docs/development/Building in Linux.md b/docs/development/Building in Linux.md index e12d6dbf6ae..7ae6082f5a1 100644 --- a/docs/development/Building in Linux.md +++ b/docs/development/Building in Linux.md @@ -29,6 +29,8 @@ Note that inav requires `cmake` version 3.13 or later; any distro that provides Note also that Ubuntu 18.04 LTS does NOT provide a modern enough `cmake`; it is recommended that you upgrade to Ubuntu 20.04 LTS which does. +If you wish to run the units tests, it is necessary to install a host C/C++ compiler (`gcc` or `clang`). This guide does not cover building and running the units tests. + ### Ubuntu / Debian ``` # make sure the system is updated first From 8814b007fced105ecf2f7ebc3991e9b1e41c6835 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 30 Aug 2020 15:09:49 +0200 Subject: [PATCH 209/248] Update formatting --- src/main/io/osd.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index a3db4547da9..8513ed5bb93 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1660,7 +1660,7 @@ static bool osdDrawSingleElement(uint8_t item) break; case OSD_CRSF_SNR_DB: { - const char* hidesnr = " "; + const char* hidesnr = " "; int16_t osdSNR_Alarm = rxLinkStatistics.uplinkSNR; if (osdSNR_Alarm <= osdConfig()->snr_alarm) { buff[0] = SYM_SRN; From b24f8705d900d8eaa64b9ac245cf117a5c47979b Mon Sep 17 00:00:00 2001 From: Airwide Date: Sun, 30 Aug 2020 18:19:50 +0200 Subject: [PATCH 210/248] Added STICK_CENTER_ONCE to settings.yaml --- src/main/fc/settings.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 389b0b02189..6b30faf85ac 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -128,7 +128,7 @@ tables: values: ["GYRO", "SETPOINT"] enum: itermRelaxType_e - name: airmodeHandlingType - values: ["STICK_CENTER", "THROTTLE_THRESHOLD"] + values: ["STICK_CENTER", "THROTTLE_THRESHOLD", "STICK_CENTER_ONCE"] - name: nav_extra_arming_safety values: ["OFF", "ON", "ALLOW_BYPASS"] enum: navExtraArmingSafety_e From c97d66ea131d66c1a81c3cc8cd705c8fab911484 Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Tue, 1 Sep 2020 21:04:47 +0200 Subject: [PATCH 211/248] [SBUS] Added back the unsafe behavior of S.Bus channel decoding to correctly detect failsafe on R9MM --- src/main/rx/sbus_channels.c | 13 ++++++++++--- src/main/rx/sbus_channels.h | 2 +- 2 files changed, 11 insertions(+), 4 deletions(-) diff --git a/src/main/rx/sbus_channels.c b/src/main/rx/sbus_channels.c index ba87343e848..380b1b32240 100644 --- a/src/main/rx/sbus_channels.c +++ b/src/main/rx/sbus_channels.c @@ -82,11 +82,18 @@ uint8_t sbusChannelsDecode(rxRuntimeConfig_t *rxRuntimeConfig, const sbusChannel return RX_FRAME_COMPLETE; } -uint16_t sbusDecodeChannelValue(uint16_t sbusValue) +uint16_t sbusDecodeChannelValue(uint16_t sbusValue, bool safeValuesOnly) { // Linear fitting values read from OpenTX-ppmus and comparing with values received by X4R // http://www.wolframalpha.com/input/?i=linear+fit+%7B173%2C+988%7D%2C+%7B1812%2C+2012%7D%2C+%7B993%2C+1500%7D - return (5 * constrain(sbusValue, SBUS_DIGITAL_CHANNEL_MIN, SBUS_DIGITAL_CHANNEL_MAX) / 8) + 880; + if (safeValuesOnly) { + // Clip channel values to more or less safe values (988 .. 2012) + return (5 * constrain(sbusValue, SBUS_DIGITAL_CHANNEL_MIN, SBUS_DIGITAL_CHANNEL_MAX) / 8) + 880; + } + else { + // Use full range of values (11 bit, channel values in range 880 .. 2159) + return (5 * constrain(sbusValue, 0, 2047) / 8) + 880; + } } uint16_t sbusEncodeChannelValue(uint16_t rcValue) @@ -96,7 +103,7 @@ uint16_t sbusEncodeChannelValue(uint16_t rcValue) static uint16_t sbusChannelsReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan) { - return sbusDecodeChannelValue(rxRuntimeConfig->channelData[chan]); + return sbusDecodeChannelValue(rxRuntimeConfig->channelData[chan], false); } void sbusChannelsInit(rxRuntimeConfig_t *rxRuntimeConfig) diff --git a/src/main/rx/sbus_channels.h b/src/main/rx/sbus_channels.h index 1354d82fe3a..5e8a6a02681 100644 --- a/src/main/rx/sbus_channels.h +++ b/src/main/rx/sbus_channels.h @@ -72,7 +72,7 @@ typedef struct sbusFrame_s { } __attribute__ ((__packed__)) sbusFrame_t; -uint16_t sbusDecodeChannelValue(uint16_t sbusValue); +uint16_t sbusDecodeChannelValue(uint16_t sbusValue, bool safeValuesOnly); uint16_t sbusEncodeChannelValue(uint16_t rcValue); uint8_t sbusChannelsDecode(rxRuntimeConfig_t *rxRuntimeConfig, const sbusChannels_t *channels); From e934ea07f87d20df5bf4747a1485c18cdbcd99d1 Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Tue, 1 Sep 2020 21:13:03 +0200 Subject: [PATCH 212/248] [GYRO] Fix ICM20689 driver not switching to fast SPI speed --- src/main/drivers/accgyro/accgyro_icm20689.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/main/drivers/accgyro/accgyro_icm20689.c b/src/main/drivers/accgyro/accgyro_icm20689.c index 6ed891dac39..291cb91626f 100644 --- a/src/main/drivers/accgyro/accgyro_icm20689.c +++ b/src/main/drivers/accgyro/accgyro_icm20689.c @@ -120,6 +120,9 @@ static void icm20689AccAndGyroInit(gyroDev_t *gyro) #ifdef USE_MPU_DATA_READY_SIGNAL busWrite(busDev, MPU_RA_INT_ENABLE, 0x01); // RAW_RDY_EN interrupt enable #endif + + // Switch SPI to fast speed + busSetSpeed(busDev, BUS_SPEED_FAST); } bool icm20689GyroDetect(gyroDev_t *gyro) From 76ad6b89fe5f35ddd75dff93bef6f2aab6b18bea Mon Sep 17 00:00:00 2001 From: Joe Hermaszewski Date: Wed, 2 Sep 2020 20:08:30 +0800 Subject: [PATCH 213/248] Add me to the authors file As discussed in https://github.com/iNavFlight/inav/pull/6078 --- AUTHORS | 1 + 1 file changed, 1 insertion(+) diff --git a/AUTHORS b/AUTHORS index d9650a8421f..11085ca78c9 100644 --- a/AUTHORS +++ b/AUTHORS @@ -37,6 +37,7 @@ Hyon Lim James Harrison Jan Staal Jeremy Waters +Joe Hermaszewski Joe Poser Joel Fuster Johannes Kasberger From da96a92cbb6aefef1c2861a76882cb21d176d131 Mon Sep 17 00:00:00 2001 From: Airwide Date: Wed, 2 Sep 2020 21:20:14 +0200 Subject: [PATCH 214/248] Added STICK_CENTER_ONCE to processAirmodeMultirotor(void) --- src/main/fc/rc_modes.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/rc_modes.c b/src/main/fc/rc_modes.c index 505c04ed59f..082f10191e2 100755 --- a/src/main/fc/rc_modes.c +++ b/src/main/fc/rc_modes.c @@ -63,7 +63,7 @@ static void processAirmodeAirplane(void) { } static void processAirmodeMultirotor(void) { - if (rcControlsConfig()->airmodeHandlingType == STICK_CENTER) { + if ((rcControlsConfig()->airmodeHandlingType == STICK_CENTER) || (rcControlsConfig()->airmodeHandlingType == STICK_CENTER_ONCE)) { if (feature(FEATURE_AIRMODE) || IS_RC_MODE_ACTIVE(BOXAIRMODE)) { ENABLE_STATE(AIRMODE_ACTIVE); } else { From 49725decafb17ce02948cec568bd8686f6b67865 Mon Sep 17 00:00:00 2001 From: Airwide Date: Wed, 2 Sep 2020 21:36:59 +0200 Subject: [PATCH 215/248] Moved rollPitchStatus assignment before If statement --- src/main/fc/fc_core.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index cb9c1f3a014..fb6d610337a 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -654,6 +654,8 @@ void processRx(timeUs_t currentTimeUs) DISABLE_STATE(ANTI_WINDUP_DEACTIVATED); } + const rollPitchStatus_e rollPitchStatus = calculateRollPitchCenterStatus(); + // In MANUAL mode we reset integrators prevent I-term wind-up (PID output is not used in MANUAL) if (FLIGHT_MODE(MANUAL_MODE) || !ARMING_FLAG(ARMED)) { DISABLE_STATE(ANTI_WINDUP); @@ -662,7 +664,6 @@ void processRx(timeUs_t currentTimeUs) else if (rcControlsConfig()->airmodeHandlingType == STICK_CENTER) { if (throttleStatus == THROTTLE_LOW) { if (STATE(AIRMODE_ACTIVE) && !failsafeIsActive()) { - rollPitchStatus_e rollPitchStatus = calculateRollPitchCenterStatus(); if ((rollPitchStatus == CENTERED) || (feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING_LEGACY))) { ENABLE_STATE(ANTI_WINDUP); } @@ -680,7 +681,6 @@ void processRx(timeUs_t currentTimeUs) } } else if (rcControlsConfig()->airmodeHandlingType == STICK_CENTER_ONCE) { - rollPitchStatus_e rollPitchStatus = calculateRollPitchCenterStatus(); if (throttleStatus == THROTTLE_LOW) { if (STATE(AIRMODE_ACTIVE) && !failsafeIsActive()) { if ((rollPitchStatus == CENTERED) && !STATE(ANTI_WINDUP_DEACTIVATED)) { From f897f60caea0c4226cbacb93898c9fdcbc262a91 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Thu, 3 Sep 2020 18:30:21 +0100 Subject: [PATCH 216/248] rm the obsolete Eclipse document --- docs/development/Building in Eclipse.md | 50 ------------------------- 1 file changed, 50 deletions(-) delete mode 100644 docs/development/Building in Eclipse.md diff --git a/docs/development/Building in Eclipse.md b/docs/development/Building in Eclipse.md deleted file mode 100644 index 35750c78f05..00000000000 --- a/docs/development/Building in Eclipse.md +++ /dev/null @@ -1,50 +0,0 @@ -# Short Version -Install the latest Eclipse Standard/SDK and install the **C/C++ developments Tools** plugins -![plugin eclipse](http://i.imgur.com/IdJ8ki1.png) - -Import the project using the wizard **Existing Code as Makefile Project** -![](http://i.imgur.com/XsVCwe2.png) - -Adjust your build option if necessary -![](https://camo.githubusercontent.com/64a1d32400d6be64dd4b5d237df1e7f1b817f61b/687474703a2f2f692e696d6775722e636f6d2f6641306d30784d2e706e67) - -Make sure you have a valid ARM toolchain and Ruby in the path -![](http://i.imgur.com/dAbscJo.png) - -# Long version -* First you need an ARM toolchain. Good choices are **GCC ARM Embedded** (https://launchpad.net/gcc-arm-embedded) or **Yagarto** (http://www.yagarto.de). -* Install Ruby (see the document for your operating system). -* Now download Eclipse and unpack it somewhere. At the time of writing Eclipse 4.2 was the latest stable version. -* To work with ARM projects in Eclipse you need a few plugins: - + **Eclipse C Development Tools** (CDT) (available via *Help > Install new Software*). - + **Zylin Embedded CDT Plugin** (http://opensource.zylin.com/embeddedcdt.html). - + **GNU ARM Eclipse** (http://sourceforge.net/projects/gnuarmeclipse/). - + If you want to hook up an SWD debugger you also need the **GDB Hardware Debugging** plugin (Also available via *Install new Software*). -* Now clone the project to your harddrive. -* Create a new C project in Eclipse and choose ARM Cross Target Application and your ARM toolchain. -* Import the Git project into the C project in Eclipse via *File > Import > General > File System*. -* Activate Git via *Project > Team > Share Project*. -* Switch to the development branch in Eclipse (*Project > Team > Switch To > development*). -* The next thing you need to do is adjust the project configuration. There is a Makefile included that works but you might want to use GNU ARM Eclipse's automatic Makefile generation. Open the Project configuration and go to *C/C++ Build > Settings* - * Under *Target Processor* choose "cortex-m3" - * Under *ARM Yagarto [Windows/Mac OS] Linker > General* (or whatever toolchain you chose) - + Browse to the Script file *stm32_flash.ld* - + Uncheck "Do not use standard start files" - + Check "Remove unused sections" - * Under *ARM Yagarto [Windows/Mac OS] Linker > Libraries* - + Add "m" for the math library - * Under *ARM Yagarto [Windows/Mac OS] Compiler > Preprocessor* add the following 2 items to "Defined Symbols": - + STM32F10X_MD - + USE_STDPERIPH_DRIVER - * Under *ARM Yagarto [Windows/Mac OS] Compiler > Directories* add the following 3 items - + ${workspace_loc:/${ProjName}/lib/CMSIS/CM3/CoreSupport} - + ${workspace_loc:/${ProjName}/lib/CMSIS/CM3/DeviceSupport/ST/STM32F10x} - + ${workspace_loc:/${ProjName}/lib/STM32F10x_StdPeriph_Driver/inc} - * Under *ARM Yagarto [Windows/Mac OS] Compiler > Miscellaneous* add the following item to "Other flags": - + -fomit-frame-pointer -* The code in the support directory is for uploading firmware to the board and is meant for your host machine. Hence, it must not be included in the build process. Just right-click on it to open its properties and choose "Exclude from build" under *C/C++ Build > Settings* -* The last thing you need to do is adding your toolchain to the PATH environment variable. - + Go to *Project > Properties > C/C++ Build > Environment*, add a variable named "PATH" and fill in the full path of your toolchain's binaries. - + Make sure "Append variables to native environment" is selected. -* Try to build the project via *Project > Build Project*. -* **Note**: If you're getting "...could not be resolved" errors for data types like int32_t etc. try to disable and re-enable the Indexer under *Project > Properties > C/C++ General > Indexer*. From faedca0cc22e78baf37d1f5d465b766e6a17aa40 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 4 Sep 2020 11:32:33 +0200 Subject: [PATCH 217/248] VSCode instructions --- ...ding in Windows 10 with Linux Subsystem.md | 2 +- docs/development/Building in Windows light.md | 2 +- ...DE - Visual Studio Code with Windows 10.md | 102 ++++++++++++++++++ docs/development/assets/vscode01.png | Bin 0 -> 577636 bytes 4 files changed, 104 insertions(+), 2 deletions(-) create mode 100644 docs/development/IDE - Visual Studio Code with Windows 10.md create mode 100644 docs/development/assets/vscode01.png diff --git a/docs/development/Building in Windows 10 with Linux Subsystem.md b/docs/development/Building in Windows 10 with Linux Subsystem.md index 39ca71cf9b9..62ace80d1b7 100644 --- a/docs/development/Building in Windows 10 with Linux Subsystem.md +++ b/docs/development/Building in Windows 10 with Linux Subsystem.md @@ -1,4 +1,4 @@ -# Building in Windows 10 with Linux subsystem +# Building in Windows 10 with Linux subsystem [Recommended] Linux subsystem for Windows 10 is probably the simplest way of building INAV under Windows 10. diff --git a/docs/development/Building in Windows light.md b/docs/development/Building in Windows light.md index 6cc0c48c79f..d9d51a3683c 100644 --- a/docs/development/Building in Windows light.md +++ b/docs/development/Building in Windows light.md @@ -1,4 +1,4 @@ -# Building in windows light +# Building in windows light [Deprecated] no cygwin and no path changes ## Install Git for windows diff --git a/docs/development/IDE - Visual Studio Code with Windows 10.md b/docs/development/IDE - Visual Studio Code with Windows 10.md new file mode 100644 index 00000000000..5643a208ee6 --- /dev/null +++ b/docs/development/IDE - Visual Studio Code with Windows 10.md @@ -0,0 +1,102 @@ +# IDE - Visual Studio Code with Windows 10 + +![Visual Studio Code](assets/vscode01.png) + +[Visual Studio Code](https://code.visualstudio.com/) is probably the best free option for all Windows 10 users. It provides almost seamless integration with WSL running Ubuntu, syntax highlighting, building, and hardware debugging. + +## Setup + +1. Setup build environment using [generic WSL guide](Building%20in%20Windows%2010%20with%20Linux%20Subsystem.md) +1. Download and install [Visual Studio Code](https://code.visualstudio.com/) +1. From the VS Code Extensions download [Remote - WSL](https://marketplace.visualstudio.com/items?itemName=ms-vscode-remote.remote-wsl) plugin +1. Open INAV folder +1. Use `Ctrl + Shift + P` to run option `Remote-WSL: Reopen Folder in WSL` +1. Allow firewall and other permissions if requested +1. Install plugins in WSL workspace: + 1. [C/C++ from Microsoft](https://marketplace.visualstudio.com/items?itemName=ms-vscode.cpptools) for C/C++ support + 1. [Bookmarks](https://marketplace.visualstudio.com/items?itemName=alefragnani.Bookmarks) for simpler navigation +1. Configure the environment using the following snippets as a base + +### C propertiues + +Edit file `./.vscode/c_cpp_properties.json` to setup enabled `defines` + +``` +{ + "configurations": [ + { + "name": "Win32", + "includePath": [ + "${workspaceRoot}", + "${workspaceRoot}/src/main/**" + ], + "browse": { + "limitSymbolsToIncludedHeaders": false, + "path": [ + "${workspaceRoot}/**" + ] + }, + "intelliSenseMode": "msvc-x64", + "cStandard": "c11", + "cppStandard": "c++17", + "defines": [ + "USE_NAV", + "NAV_FIXED_WING_LANDING", + "USE_OSD", + "USE_GYRO_NOTCH_1", + "USE_GYRO_NOTCH_2", + "USE_DTERM_NOTCH", + "USE_ACC_NOTCH", + "USE_GYRO_BIQUAD_RC_FIR2", + "USE_D_BOOST", + "USE_SERIALSHOT", + "USE_ANTIGRAVITY", + "USE_ASYNC_GYRO_PROCESSING", + "USE_RPM_FILTER", + "USE_GLOBAL_FUNCTIONS", + "USE_DYNAMIC_FILTERS", + "USE_IMU_BNO055", + "USE_SECONDARY_IMU", + "USE_DSHOT", + "FLASH_SIZE 480", + "USE_I2C_IO_EXPANDER", + "USE_PCF8574", + "USE_ESC_SENSOR" + ] + } + ], + "version": 4 +} +``` + +### Tasks + +Edit `./.vscode/tasks.json` to enable Building with `Ctrl + Shift + B` keyboard shortcut and from Command Console. + +``` +{ + // See https://go.microsoft.com/fwlink/?LinkId=733558 + // for the documentation about the tasks.json format + "version": "2.0.0", + "tasks": [ + { + "label": "Build Matek F722-SE", + "type": "shell", + "command": "make TARGET=MATEKF722SE", + "group": "build", + "problemMatcher": [] + }, + { + "label": "Build Matek F722", + "type": "shell", + "command": "make TARGET=MATEKF722", + "group": { + "kind": "build", + "isDefault": true + }, + "problemMatcher": [] + } + ] +} +``` + diff --git a/docs/development/assets/vscode01.png b/docs/development/assets/vscode01.png new file mode 100644 index 0000000000000000000000000000000000000000..10a594075e137bc63dafca1963c1bcedad525268 GIT binary patch literal 577636 zcmc$_Wl&v9voMSWNN{%vgy0%ngKjKnaCdii2=2k%-QC>@?hc#a?y%9#$2s>t=bZc2 z^V}a_)m!gW?OHv1*6Lo<)7{hE(<@X?27vSd{{sXB1d@cfhynxz0tf;E?in8T?VoSs z;p%S}NCyRg5Jcq!;o(~c#zgR&AOu8BG{UpqySM&(TX8i92ncM7KYoxB3ZE_@AYKb3 zLOZ1mR%5V`8ES&dDKM#TK}kHMAQlTQ?fvxNx{QG~EIx ztro4Ex{j3>j92IBMjPj98*1y@buPSz5NL|wp^zc%<6igEukn)cU~$i~tM<3;Hq$55 zNB2GXvmAo(HnJw|TsLDjb`PmHNXhaYiT^m7*#94g{#TsCOaF;p;x0T>>wlaA*9cJL-?up-LJjv#u&1y9 zVcT}oaAZcv%v~l+!oOuj$ic#NE;(rb0idswB;Wk#z!e4<6S=FSjd6O~rn+MtX8ZS# zg;;w>AxF_;0JGLhNRUOOVbaqf;9}r*-$UuQGMn<+lf0r-Mz}#z5Ir{}g#LRJM-oM| zzgk+SLQi)rzu4jmG?=(8JnSLmcFh=3$pn2eL)hK@I_-2L-ma*@zU^&DzSae9)BF#s zmWtGK14I_`)htazJh>mTw~UeEh@7%>Jq!KVeOI8`&aL!$fx+?FA=!(ddN*=F)!^0m zcA>oQE{TVev|@F5q}$u57<@%=l;3}^Au9l4saSNsNxh?_Q>%rajI6Lcvx}z3G@H~* z*X(Qw32HZdpEy>*%cEgrtB8j4JC*{0nO2*D17{t6%uOx+Hawb4=JPtYBktuG8QnwI zJJYOf$;RHE--rC9eD85YI{%J zJ4@0^>i88*id+Y_cW7YtHWB{UV$WfEqM;H7WV?TZ)IUy>HI?Rs(#$}M=OmbnL`f)N zQ-prP@ZUVa_r1V##h`FoZM{qR!@;j8= zFtxzfXN`V8HS65=^wSuc5*Iq|LL~}5Xu6qQsnE>73Rs-IV#R$&itcT9PAXj*e z*f%rL_)Y2QV#^VMuw5U`Aj1~Zw5!QqpI{1X`qM>MmX~S#6AOgzFQ{>oNEx^piPFbg z%W*-S{tqOC@lwtTqhmM#m9f6sb(RV)M|2}TK)lm$K{}ty4E3V|w&Os6PI{ne6{4k^ z+eiMkPjO|qKb8?F$q1?MEjLUqUQQjh9%=h~qW8Bm_UJ&yxzR+yzsR>x&x(TU>ZIG{ zfAp?75-!yvTX;(f=15yBm9_-O@92oSU*WeuJoGH2*tGrfNY^ZlI^@e%3h}{2C=?N< zJR1#vt%3dKjAI?@kz;9NmbRyRX`W&%>M<$WaW!8Gtol=mi|6ILXm4s?pS}RG!6!@H z0@teEXELkxgoF2o2k%yQOEdf@?)HTUvhcngYcM?#*V*x}E+}`c95an3tvKr@Mzi1D;|g{`wyQ>qbMG<5?cr|x;#;vQiuBUc+#vACBh*f3mI zEjxTlYcmvQKX>m-05Mmb(8ySC&7Q6?e6c9cJ33CRP_TDt~^E-2fa2%Lx`U zQ^1#gxI5KnY#<%D7UB1jgZnZjMCVHNz5^;$l2v zb)^mA_+wh=KyICY4KURn-^v1jLRzqPpo3Yo9RY$O2|2YORH75E{zDtE=NUNGvsQ?B zLit}zGZ&FWy-4ShB(-IURYZUUG4(IIDro*p!d5*y*13HO;`A|!$Y#wi?&)6{-klYm z)Nfg;seLh^J?W1;B`uv^a+Y!d{SOIazpHITbL?wbTpvaN{vKO><06i z_~Ar_m9zQP@fGkB->nHh#D`7~dqOlq1#rnh?ch9=v+>1NiBV=lOxMTt2o%EGv9cg_ zH1`}K{`CCC)0nMdb-7WPD)LZi^02PTnN?r6m=Ox<#@6CY^)VBJIk$HM4@b3PD6IS?R3$uqmw zF2rnoW*KonGjY?;P4}|R`}|;ZIe5`yq6!XL5ZkBM3eLl;c+JvF0HN+as)s!IXoluJ z*9d0kHo-F|(8gv~uYA7$#e*a3@m#LtS*X0A#U$+H^+&+8#D))c z;FO@w?)%bhREF77SikUHIijC7bFj2{SpnK-ft;-?rQXhreeLY*>fnl;JsBb_r>snc zX>X0ETO805DNN`>^K@%Rh4vbY?1kJ4IDL??LFe!*dDel&c4zLI4gSk}$bXqp5s~ry zMu^u$#6S5?Qc%zxc@=gjv_nNG;fgIT8!Kx@Uj zT)Qke#2g(D!f32ABA(53Ln_$Z(TqHbx@HP8M*JwBLJi-qGiTzfHH|Z2j08uHZw&@> z|0d#gOoHnDpo@47TAxnx6;WbGZTl%-MUHLoovd1cfh?cc5Ay#K)Lf0ZGejr3kZjws z-%x|WY3L*5{0pcy($^5Im-IByQOeD1q>|Vw&_%OkkS{N zI*!R@vFIIH+GB)ySdzK7tRA#~{cF;Wam5VXT?NojSjgK&cXX57=ZrYVXRw4n@!9Zj z+JGMwSx>_dY`4|ftqpY`)3pZXv_El&l5=+-?}vwQ)_gdX{IIjqy=&5y=#U8Y>J*)B z;XXocABSkRq&f?)k~@?5>2d2I%uV(4s~aY0Nl5zKt6{`B$Av$PIy44;%0jq43HOVw z>Ia;>=w&BQz9nXJphB(=@`_s1^>3=C3Q*p{GUv{vm z;sjFsf=^~a?||xes@ed|(o|l%0XYrsMBFwwKE&AB5+!yvy`z}Mpq+iU9Y}wFayw~T zor|QlQ+AtRr@;-NpDBs+4^)&|t9 zncvtRpZCtNTfv}Pfayx6`6pB0DsUEBBVS6NPLS-h30@KwrGXO5_Zu?a#9vg@i08db zDCQoQYgkZ}Mi!1dRM}p0OlmaCIi??<-W_ibpOeaIJj^Ew@bCwxPUJj3R=7tUJqX4x z7DBLPVF6+HG#ZMIu2gn;usx0x7UJ3-h2B*}zEg5QZah}5K&T>8I&SkbZ!avLDJxXs z>l!&OYUQqV@@60TRjOU8EyX^!;JkC3XqeX2w!x0YIK?=)Id%P+g%)$I~`uVaAA?$~jG zk&E1AgSJ$~v^uA6UN$#EOn{U{a3~HoLuh=Ck3cMf5Q)x+wX8wZ|=dj*w6EJrRX0PrN)WE%ywtt|EHT!bSwk$Bj})eOKfrs9AdUz}7_8zxlyv zb4gZR*T>1cD@x&~r*=K>B58m|1hD{&9#I0Y6CTS+-VFYS2vK6Xz)HX0%a39b|0GW3 zR8D0g=%-`tefqDO7{aaL+;ZH6RDLhFyKw>g#1YUkr*jk6KR73SO{G2c^(#P`iE>RI zZN$?k6g_Sro+E>4dho|H{HSF`>HUm|dZ7$=ffP0)7Gqfw`1OLFu&XIJl%AU*ixz-H zXXvD!dqgu!qlKFkt->7-S{-Fdg7LE>FU?BQ16O{+5t`$Zqn&j{&D`nK&!@ItW{5gs zBFZx*GjZkfG{69nDQ}NAtB$%$?AizOSmQEv@-nM z7H7u}v^RXEA-_G>4w@7pcIqfH_=SG$U?$oQtCwRco23+gESBE_>b>b2LpRY7U|Td| zNqmvd4|i57hPAagp4%m1|MsoI<<0R@^NgnCk0y}2{0_T1_T%Q;t{U*z#4{GZUb}`w zv16>lfL6UjHNH!kQp$3^#8qp#t2T;z)8Dwr%Mb$%xSaxs)_)xgJ90s_$L zH#6t8qQ7I)qd`xYS6^k+r7BZf+pf^xa~uaPPkdkB4|nB=?2Q76c>Oksean!&WIZD$ z4mIX)%j6cC-aP1CgnbHCedhT~5|NBSy{%2s%^7SuFT3}NK43ilCr>Wyu6lI9bp{%@ zZLU(a!>r=#FI^{XES(>t&)fvj`nysHH75oXU9>ePyYF20L*!ZKQi;~{%d-k$K}p6W zsBap{ePSx!UA3-Iv)5pBem*S1V)YmMk7sBm>lsw}HoT=;NB%_5?48Rm zbgx5D<-DI8k%$69`F2Z{mf9+i$%$XzxgRDVc)Z{1Xh)=-uaz57ux!E}UTTq{Bk7)3 zsB!mBZ6z^Uag|=)2)aMS#i;;DJc`jhT8|ps5z|TV4gW2`c-)uCtG8CKSk%i4-qN|)77Ox6K&Sd_|JucPVc-W;kkSf001+i|3{|4r5= zIV2QBJ?l6Ie#xr7NcjY_TcjH~tTV2~YF>Dp4_Ki@sBYeBb;sbT?MHx&!BsnDTNXO< zv{~$Xc$TDF*WC`q^X{a29(3H$C#kX$Q4js{0~YxQc*m#aJ~E+}H*q`LbZ8=I1DA}W zBC{Epcc$OV)6QsPV=V`q$3tqLueR|artyVnj6(pFY#~$f#AYFQ;d+Z3)U&NUk^C07 z6MR=#E$eZeJdv==dgj6d{UuQ+94YtuR>D*!*c5WB5oW4hO?^n)uJw>A(YZjodv8yGaWj@?xvP;gA-Lh7C@ z%tZyK!tY`dXW$p3iycOhQ7o!2Lz;ikuB5#z(9J+i{8?TQ7Y&1Nb9K0+6nc z6%*y$=f=EGXBBm3=)@BUFq2Om=rrV;-cf zEaDA{=($J}R1)iclXSH2c;gYp8>T`#Zgp2ql!&A4Z#6iilF!6P)mh$x9t^qr zte}YEL%UF%xxP4kmM4x8-l?@kBjzr9WbNyq{Gl;F9EUqd2}X1%5U!`?lU97Rv?*)> zg=7rsV&LikP?o*s%s9@a3>t-o@MOgQ#-KWk!Z&4DzP>; z#y5m>OEwLkfP^QYn*B58JNT@}^OKWa#Z$q4F|SqreqR2l0%}aD z?Tb0FpeAgk2F&M0NrHxzt0(`*NI9L|W|po_u<~nuh)O1dE_dP`>yI#}x9AV~I9r{K ziU*1M_CtiMzq}{%yxXrC_Jf=+t4X`?=j>2z-$Xj+iguM?9yB7+H)73AX_ZDcWSkd` z9OT4wn@qFrp0_QK6hwGt0tc1q$)7U8*$qh}MG~y(4j(JP@bC2R@#or&hK9N+>)GCgvCFnEM5H7n2G-#^_dS;`OEme&&T zr`Nk-Or-Yq_7O+Z3!9(V+?v*UzXp%~jPex$EbLkAxeNw2aEA$(tr=+i8&_EbBdlBs z?FECF0T8#Zpp8E-1$4)2KAWZN`@!#by&6Xa&+EoE}Lf@a6i>QAro+m6LUZax4}VB9CBWDrAqw*ADbdX z6^1Gw;RFauvcyi6g@36mwCo>@XMM|5PLaz?pa805^aE*4E`<%03l(z7URK7m&On@VY0dZz3rqSHS3KNHWt*QjW^k5JVG>o2uhZR5B5j9Sv_LLiVh{uQfuupX%Y= zXi#vfMqO0$bA63E(KdJ}5d_=EUtAK-x2YxnSQ-C3igsyLX9-xDCHbHz>LI675#`Kh zDUEZ>^X+L&2Z&a`MXXV5ofQy?^`KoDu?CbgccWVTh8nxaF5~L+Q{|=0!(zD6>6ld^ z*dx!Ku|9aM=;N;|4`OB|uUztfS=X3f@|N{z7T=T1)+dw&FxlByuDikY-=u0TNDyiq z71hJx?m1j{!1i!}d}q9%*&rSWO3LgETHP_Rwi`^&#Dp-c_yn4wIc*GE+in}VEyG)i z@`_<^BlEfl@pbcsydiUQFCtG#`BL7q$IrUFcW+T;`Cd#_>**{w{+n!b> zx#rzD-6M8MuBLFXKonZj+Ux9*y$z$FL>+5m>y+M99zylzr5)}}AKXMipg2!022ax` z@`^+>pnBWen%m{&2R#YB7h(RBdD9hSKvjxjt+j@cUwis6e)=v?leVCOL}Z94pK8$ z$Ns*4E46_#+&q9;GoueKo2Kd?H`io{rq%FT)hiNe%h->E(@IaBjLsYF`LY;<=f?5< zYqDW%k-n7g zIGTf2Ruq090|lwnK6>g&WRwdd<($2;Vtv(WCbIvhDW4>RRZnco^_ws~CcC?z9wg zgiQ|6)95s&JhsPW<~J(Yea^Z2gwqCfW}%Bu#H;z#In2_n5p{Bo6=ln~#9Z6fQZ{TV z-dS4hIpWK9+eW2fByXira|TbEC8sO4UX*Slt;9`LoWZ)|SyzHcm}TTLghX40W07~N z;gwkheE4P2#jLa{F|2udo0(2siK>yIbi!F>-h_2>$W&)ME05U<>J{P1{3&CaSCnV^5(NXbr4 zA*E(RWsFq6O(I0xS&i)1*l6cdT1>!4c8;e~Kz|4;14xIYk`VZ@BD||Hbw)3awp)a; z%fkJ=zHklGa*al(OmMw2kDk**G~Vm04&rIP|D`93f^=2BF$BLL?(#as{>k@G90nJ+ zi6Cz|Kr@P@C!xb&!0N5+a-+gNo`ryLt?7B|um{t?jchM#9=>74`PwMUdCoSf)$Qa+ zWAPu-a&%a>!6@Z0s|(%_VW^=1rvSzA?R_}xQ2MfYDmEm9C=JA$zhtj*%uNXWDJYI# zrf)Mt)QknIw)bQJRqA57vfdVOGpGUiU1KZ=RK&si=oMWk7-mw5$&oaju;IJn+X&;( zM%yO8xp<&V(o*q7EYM&qkJDL?OrOp=e&$DbcY3H1L7iE}2yO(CruAH|)cipG#9yTx z;mA0^*Em&6hn35V6XuCSyj=VaebwOEL6z+2sO8eW1;6oF8+BE-s*$e$5zFf9&j;bh zs1eFfCo+R-yYJtHPAb7Nk52C%j~hcYl=ut9F1HNoE!=B6d+E$CE#y&xFPWmS`_G+LfaVGQ^!{hZ z7V4Tdlo7g|(Gw)}0%<^`?%UOv;~ZJuLdtzQmgRn5QBdY)UDZ0>CO zYPvv^DK6$H?rC!tPe0)o5l~#TH6uI_YuT=k%NC}_lMglFTxs&;dWpx^no3sQSIC0J z8CW|)dh$>UImnz|*uN7D;l%jL=U5N(-tfgTnoDGC2j$re^^TmfMCUQNLOePn4Q1!N zOi_@c>hZbfsEnaTw7U?V9qRQDdW~c1mG7yb#5?-hR1XX1KVZUoS$~+3$dB@!JY){S4LYAhvcZQSJJc7#7I_!A)vzs&oJJK-Rm8BM2Rfx@gUT ztlYjKLKerwMg3l)4}FTU6{nZmsV^H1q`$T#2tN~wU~~MToVSvlNRaL(m|0K6S!Y&*b&P!eMAR}N2dfx4 zd~mw=M3)CRvw-?p)SGYZaCzq~IPX7>yfmRE-C6f{j_Nl?Ic@Ch@bxFR60b&$vL=|G z2WG^euD{dz@oWbk@*jTY!r0i-&P~_Re6_x~MGzEu7MCWTMdGlR{Jm$q!A|~@i3ZU+ z1@5xLDdW4x*q)ql=h4(>iw^AZDuGK{2;k^l<9zgspuDSj&5)q8#EFz*6Sna3e&3$fZh z@42z-$aY~WeLd06+R(%y{Bw(D;}Rwe0=Rq~2_u@4^?(9J;|I#?f0!-O+fEnQCa;?m zINC3{+XEJ)cQ@WvhT!u+2=6-QiE)v;$*`o;^B0+At={Ybi->?hw<>MA_tn3f7wapA z0V^(}1gBqA<|ld8`9*%ro6wC;CM4Z?qb%}+^nE#jN0SohZl{Hwa0jtLI}{69ZdN4> zD5)4kd2^F~!@LnL75tRj`lyf8yCJ1R3KMLVF6m=cCA=>&HD<`*=NL8b`N@>di)eNY zSsD3L(M;WQ7gWi0licv)uHOdZcNpfFr^fsn4J*o4JZ=Ovye_ETuTvc>tzJkkCqVRJ4K3YFc`|RRDVNTj z)L~xI(7Ei9FK{JsrAX=FEO(j^gtKqiX8nz>O294?M5&}%l_%o%U}D{$9+qthEi>rq-S z>bR{er(9W|%E6VJJ}WKZxZN=Btl(U=I*!4kTRCA`h8>t|G7wAf&}xW(N}M?ZME5yf zJ2QUX%~Vr!k>pNuP&fVt&1%aEZM|*coHbA06sFz5p3kxg_vjkurimn zpS5rHasU1>P^WEQ1GeUD^v`1n^I;nyOto)o>DycQB?w_O2t$I%P9A zi{*DFBPPNKmLpN4)?bg!s*9<$AWHOcl8XW(v85d}mIrUL+9AAki43)DK3eKSaQ$+t;|2MHDr(bP2nk!Ux}JR6Mt1BS_( z{*Z_`o|>~hCng)o#?@S*GXg-(b2Ji>QUx*hx4|rL0r<}5Fe1iRJX)(~P(jaP%pvZ> z!ai=);k60*#87(&$CrkTC^3b2$j(A;Ov$i_VHv)#ae@V1sjvsW9x%6!{S|R+qgj+I zd7K%Rqj)MG$#$<(bF0^T@N=kZ-mIv>RvZTN6zQsu9&D61h&i^6&swQ#gepklg0GhF zdZX4nhK;zcWd0{(f|ph8fWwM}cQRvH!VproNxCta zp2X-lJy+M-UB28PFLpehqfT=-(~}l}N=4GhV{+HG;AIyi^mB?Mgj`L9nD)nSo(tuF znH-~=8#6u5RRtj0ntlCbwQ0=c{db+CeUrE2u+Fx>OYd?U^KoL&j^F9DeCJTHySa|! zq)D>I&)L3M!w~j8ZGgK=Q{;KK25aeNz`U^3rPjfF+&NhFc0WBXSu~qd zU0n&?dDQP5sL#`~)K5sXNotaoNj@@td!rtZu3GW#HYovmw@{*7m+dg>S$6Et)5kw8 ztGotQd^3zxB3+Newh>f=q@-Mzg6ynE8nKG_U#D>*jt(Urx?Q;sP;W=$DALgkvI1pE z;p6+UK7=v=88nC8?px0QvD-!MpM;YqzLOIi)16F;g@4ds`y90<`v)G!(ci-_e(i^W-G-h!pzDJQ$K#a#$LEJod-66Oyf5duA+lBi5egB;6AB7EEf0e8JX%})A zN(O#BVSyK;$Z1Y39BEn*lQPc9bsr2JHy&u#u4Z=d|4Hv3Fo!@eTp=K-C~JOH^j{X{ z|G1i4({tMk{1qMkPXICs85!9=@vlhXe*)@IfV2Ous`)>Vl9}rv{{I^Kze4W~seRP{ zeD%M2>H&TAfX4)%`w8t9_?vT}&O}V;bTZ}sA2;~kooem=u`4&kA1{W_0X=m-=Qj2` zp3~5@R)Rm9k7{bIj&l8D=H_%!R~-M7fq(THQ2!~(fBpRj(7^P+3<2Qa;JBpzv84Y5 z>HWz6p&tK_k^XO!;2i!ZpZ>uzGIO*jWU8dPf6nS3@EkfJm+gNLPWe%LL&yI-mi(Zq z`QVdy8WaBY75uVGn1UPW_NNrUn*ukKCf=AOFV*7RA^tKBG9ojVk_J`g<{lr}q_zG}i<(;@$pIWb(YXm1C(4ZLqXd5yP1;ntLY7AFrk zUP!#6OagI`Ia|%oK5<42P0lIrS%y^4KfRr64ioyrzg^Uc-+IOL`nCe=(zyR+ zsQ%=$q3}hY>N6;YX@|I{$cAA6=gBX*q-$^%6x7GHtN3gVHmACL!SZ`CjqEv}t-jcv zK4^BKHfC6%nJs5q;5HnW2U~mhfVR(dEc-I~JdSv+o*s2vnN-h$-}L9ec=poUv7Htz zYW}65kOY3R?Mzgd*j@CEuyfcw1(eM(IgaH;7Xdgl)ZXtejr;?!HtHAx`9o50UhV2! z41hIbV#8lZIwB^co>*Npf14D@zA3p|4_FU5~6nKuO1f2e?%+HdW#$)aAo7HlPvGVus82wS zakf|)EstqiMOJqKI&`Z~QA)CZhcdH!%#PW<F3MSK4zjnA~&U~ac=7uOdr6Nb> zNVSrA+gN=;O3JMFE<0meI^vWTqxhFn%SK6T95T_PK!o)d@Any<8Pb@9(3|d0=cx9t zwyy3e1wg~z^OPK|Xto<0(wt~d*%l7T&-Kdhn{5)CH%!(k_pCp^PyVzKmx+2VVHi%3 z-nJesgE9t)2Dbm8a(X1_{mctHX|1)x{q5Y($iwz*O~Uh)<4GL|^x>pjcqR5p8vP#k zmVqt8`S~fyJTU+Ve3QKN<8Kb9{!sC7x%`5of^0UL3blisFzohmDI4~Vc8xojtiFsT zko@zd_t@hQf$F`j4O9Q?!Y(Gx;^BbDxtAsb)Mz4ooWr+$aA4K%9_`#^t$Rqu=WVO! z>PtAD&!lA3h{X0JGG|(-9ws)JFZIN5kt{W#m{?fcSSA*K-y#!0C2V%<;sPgrjD8GATk#jZZhI|V5TZcfjr zY?hc}pOFVPS7BA-&5~D%3Hc~hEcA1{wtfS_+_iUvVx_UV2h06NCBYw!sl*Uvd#3^f zadn+HE^E->srW6Ro`BRD>s6GU3mSSed_Z zxvinZ03Q02dKzq)KLVy*3=C)F5b;S@8k>jikZ;A*9`Q7(W6SD&X%;;?4$$~X-}eQr z`+aQsWx?6V=pOto+v^urz6rBO#gt)BlbikNAKON-KSz0o-4$hW`y)> zB}{*5b&FbzMTKQ~lG~c-!x8E{C?cKjO1SFX(z;sSz^_@~zbEljc`>2!V14jl`fEFtCvg18 zguLwz*S83wVYikF#Gg4&3@Mp~{a8&$q_Jo{cqqJY$5%^|%hL!ri@~}-uJh@ueFfvZ zuDjxOzHCiZ>Db(7XhmxwJ>fS&<}!QgqcrQRL^iCJKFM^|EPS+}XR+@Jk4vW>?R%_R zT;N*XC$?aH z5ZsD?VyXu~@XGnVeb*CXub%GWjC@s@)bs16iM2Pz6^J<2-h~G!wi>DZ4wZYJ6;RU@ zNS+NX=SUBSw{Jv%xvwp^2UC>jcBVR8r&jq*u`BqCL%%Ggt4r-|Jrs27gQ?f+x@YS$ zZY0o`RCf2!f@_$U&by(-qO9cMqy4Zd?|rwe$b&K{o_qJP6Tz$PKt7ee(#kH2H%kdd z<<<7nS{#+O)u_;%g{!M3?(>>fy{}7P9KzajA1aS0`e!7wRg+@-xwovH$H0?4Sv&sA zM{fDtlm4n$Uc-zzh0+gx!OeiJeO^{s0mhUfV;=3<50?sH{^6b)j*V^td-a+-f=^i! z{u)WDh(5Y3=)w(7$22pFEk1i6&)XZ<+)syATn1XY+LXuEMYuh>k&K2%C1c*_v+xFm z42ktlnww_D{(!>NVk|kJIyv|h3~R1$Gky^L^CvOx-7|ZNP^8iMTGGV=Kl#lIaUX42 z89|Q@>>X&fulbz5oz%c^B+3P(mHrNPlLzNqWnV3R+{f4?z zNky`!H3=Mw61~$~24a2Q1CjqO_+(-;P)ng<_YQoJfm>B6(Ui%KM;r&9CwF}*(xB`n z;S6t(ofwSUo6Wr?^WwwqY9$c!;w7&6PkV$e2=Q5=>FyF! zH~C>gF1x8?{N#4^i!p}nBE_5=Pj%O8T+NZlBoErpu4$g%WcvXmJB-6-vXI;brkDs= zABFHCBg-w6)AqeN=g{>}UZ_$FOvv&KX-cZ-UO6?1QQ3p)+K|BI&o&n^kdJDN9JrYU ziy=R*2VJX-K$r*w+$2dX{CFaj`?WFeur!a&^MXw5E6zxXsk0V^b?zOKpi|x#WV5J0 zPf2_EyKS`EK2HR_LdzY%D&imhA%syXQ0e#;Yp@zmAEyKkX%W_1xeT zvgMIJ$Lwga8N?EQ;f=!x-P@2anfY68OM6tZpKYNh&pf-ulgO<_yrqyLX3mGs7;KJ? z{)D@!ESK%A+#t$Wc}~3b$iUf!q~rPd52@4yE#oXX)!@o#$KW#MPv;G!g%UGwn;*?( zqn?v^1sPaMYw!&jZ{opwd0g@^5^Qa^S}}W1@jwi?C8ZT9Mvf`g5mib2iu&-*4SQc- zTEKtjTh{iAO?2o}9tT<6V6QT$C^fKeQh2R8JhFKV5}+;;QKa6&r0$*I7#{BX8sKMJ zb${0c)6xbU0(XJY;a<=22(_PK?q0kgqpWzNpicFm<_fL)rM9z5K6V3Hs$Wws8AIv+ zb}Nd_PKGQdUon80!!S@nXe;v&RRk%VwR`9H*Y?+bVbYM`l;I9n>=qU*oGW=!?-tJa zn^%?Al!oaVM#il^;F>ukc%Ji)cw^lxzvBizS$+4cratD!GPsg5XN~|@VXe^ z*3c3LX%+ALO>IZMCyGo@FrO;8%8?IS;NgQaIq~EIw&m-%emNh4W2CjITqoxqeobCA zRo(SlVMcDDfyg8H_Wq*idJ8%L1BxuT_YCY8X}SME7az)d?}SICNEZl_7i)*BWgtdv zvG&k^j_+R7H!M7}iF>F*5uUNaBEs*y*C&7;N}FlG+}R5ST5lW}-#$nHhe$TIjz*ZV zA&@uV2}yOBLKU>(KGe!Ojha*Zv{)`N>0O#ZTak6|-SrlDalkML6djAiEZLI*mr@ z3AT&_W)uTC6BSYrOrqCgoOH!FQL~RSOuKwU88sf&71Gz96tCgSaM5!J70wnH!IO-2 z`T8v$!gvkV#N6DYK`l#nZ{|K`s$x{i1*<;l6ywt)NE4AL;t;_OYu)umMO-$}BJNH- z!7F$O)J(Hj(~(sMf5L&!XQ!}^3}(jVpYr{Ip<}RW))MwhD_U1shw=n`@$F`@Wn07&S2VbS5GjUAm9?#rpH- zwPg&VJ3?%dF4o5j7{o4%Pq9IWy%053_u!g?)o}s}GZWha@yY->k%6baf!wh&`=c2G zKCiV+x%5!~A}c_#nHzkdHr{+kM^~zk(GkOS8t3l&HNNUEl4Wyw6}8ndugMz+GdU0x zkChizK16C*`{o`VMk1hq-{kZoU-%mtTj7p=CfP%>4K0gq-SLpkbMsu>ilvuORjJ^>r$`Ed&B0NCc5>=k3t%{p+2cf}VPq7vKBA9v^>&$MP}R zuu>+zOCQ~oaMd3p3b|6|^-!eDKi_vvdiz`PQOk~(S z#1zAl)I$66pb&eK2*E;6_k>N)glmo@xL{Iw8Eqn80?Gj}&0++BBOH{|viNc)Wu=2n zb6;&H+#rfz5pqGZy(6@YAr&?IitvmfuN~;CBSQB8~Zen`5rACqgyn)VW9bb-8>HwhojdtvJ@Z42(9&g!W_Us6_DKCQjN z46YGFc18Ge8Z8Km(Jl(YJFNTX?J4CHf)bAx?QM!>j`U8JeQ>F9YDJeV7F*BUvF}vZ zzUrg$6k~8>8tM+6DVj6+yfc6cxWfYJEV2+RRupb+#F6oTi0s1Y3pO`GB|wAFl!K67pY0^%WES{amF@DyYYUcqssbVfZhTZO`l6?g+1?dBXoEd_D-(@i z7DqmV(C(|I%ZJmIgD7M*cai880vBZLW9MVivv2B=$9-^QhZDb>`<^>j)KE+SZtd0} zy@e%_0F4fgBe=C-JTkt)#}3g#fP47U8eYKwhYbHWkRJ~^tl856f#1Yw)o&4Xdiiy) zM?G6#f-6R_ufK^EkfQ2PXsRikn22y>{A^k2nuxZN(dPP?_A@^808mL(MW&|%KqiKa z0Yas)VJ5Sw+;a=>T>^Of@jN*V-o8-UiWZhipOa@&(!YHzlB!g=q}ne=08xWdF^5?Q zYW=v?F;VN;*WokxyKY&Zh%ZRi1JeZwx$d5z^ol?ELomO~@5~q%{pu@k>a$;Zr*(EW z?MBNhS(Fa25$+d)5g|A}S?Mi)m0K^z)|cRd^{U?NQNFP27G;pGyf-9=LX7=#duPAf zXXK#_377AUdEkzLmr?oen`)j`VC_}Olrt?Oqk^OJ!Y%J7N5>luKBxoq39n|t#WEg4 zH!lGt-k@j{FTdBcIXtNuxUG&?x&h$6K=i)%lf|?9o&}_#=AR?{~1ax8eOO&9>hn- zzk2HgFYTEkW-URVB{>_MHYPp-gZbP{%biliG@@i3U`BQ=HGcaY1Z($7A;cfbHg`p{ zFq91z7~uBqJXZ{`hP@EE?o8Uekmn(2LJNJz0;*APsKxxT9-HZfjINWMhf z=!YrzM)~6%)lJtiYDB>78VS0M%L%H;7P4C&IxU% zl-L0(&Ye+I@J<+G_q3^?wZXNU(yrC*qz1hg^^)sv@&t$Z|vg$g7yZ3 z186;PdFaK2q&sn~rO3sKN>?R(JLP+M;&AEihsaKzm(hB9haqMYxj+Dr|Gj}h z{WZU*{9)t?WYrlq8>D|yqwG0Ec1Wurnxz1 z57oY41EZhK3C~2NBWsc&C@$D^v=5*cFMfWM>VGZi!I|a1b+-Xe;)#Ra-=LL~v*^Kw zm^t!u_s;wmD0*Q$8~H^$+w-PUETS2CpbFjYoU^2WDq|jo)`OfxFa0J5+{>z+!?CrF7k%hHBZiA6-EncY7||<- zc(q?nFUrBzR&i>}Q`i4AboeNKfCfR~x%5i{ZyVU}3;CO@;}i5yr=q&2!H!~daSTc+ z2-0hs%ToF7a`|&UW^)f}T(L8_N+LemUY088(i~}WfXi?$vt9l&MA6P0^sV>86k4+m z#h?#hqdTzDvGt+8y;EBDyX`3}M9f)I&1sk9hV#dcG3cPqrjOG%`IwVmZx11dCwuki z3w|VaLD~6~jb+&b(|Fq%p={FoDj8LZjqV0bJYwwnB>a~q%sIXj3>gpR8g zl!FF8czSW8$mDv;8{;2RD70n0qz5~w{}?IjP%UbQm#M+9^^k)^uEH5oxYF5y>f#q> zUOSOsblxusBW&Sc^AT^xb_P$cu5aLv&^7avmS-QZr#7j_$*xz0^T$!LQ?g3s;r% z6fcU4^=Yw0a3=Tsa^RI9c!OV*vq6+l!?MeGlp6E!|D)_IC(PL5jO;aSiV7P6Byz&bjwF=RWe`&4=vCFFUgL%&b|nwi&pa$!bI>!K`;Yl`;*VYEJ z#xoF>sz(#9^cGq!qi`=a?Q^F%xdJOgq zh)EICK#c?KhCuUA)?1P`FCgKp`qrrnMTK)@9K?M@a;Sdix=~J$c-0Z(m`1bK{rDMo z;^>Rary`70Y*}pJ1TDIhjoXckm|-ew%+&9Gg>+Xe#l^i8d&9@3uXRAYRo}Ztjh$8h z7>*l@pBRd0Xgt{9`t=5)7Hn+M9!sX2bi}n|j4geIKwL;%oEkmWdbE8(!04L2H3J3- z$K1G6Uk@_i_)XPgO(NlT>jk9d;Qciq!<0Gb?M&U2ftBFur`cR*Hh(7)IbvG$&aVyS zg?#B1g{I95wFSRs>gT8=6;shM{K6#e(Ts%>itQaHys~An?-~gui(fLF1`J&$?W%wC zBimPSbf_HH#P&EZEh~E%p96pO<`4)_&$8UEJ&C{0`5kEn;tZ*6kJ7g>^Uul06XeM!*%M@J7se5(J%AMRE~5nFiDzbEman!>dRg()`VIXOcoZSs<(?s4 zJJ>Hk(IKxzms9gYA+?gROnx55&Gs9xl6*~C%RE}rwu z5?eLP>6m1lpD6at2h7cnd#KoA#IcCSU}v5~T2# zsy%)yDQ#-UT1X7SP>F4CgK7`?&JVVCuJ|#fpJyU)Htej;*Hf7sCzjg~Fj?Ga8UCCRWwz*Y7EF}@i4;m2X!p+C&~71rVYkra($;DpSG1hL$e0sg zrPfPwpm4s)jzz@p+T52$O<{8N9^C-qjL++T4_NW- z7Z8)Rg%CMiiwZwE2}4-_ zEWSHe{Vo4_+{}W18O%f&OV`#1D;YExz)yOo$&fmzb-T`82L2vYCecBs{Nf@j5Mp2I zgaK{3jFS4sEq^x?KmW@RW$!~DU7B&kLg|W__RcCFj&TGJ0-Dl zuQ2c6uaFl}_fxOtIDPt=$Lo||k%l~W3@&d}xmm4ILI`lMDyKrAa4S=Ld+FJ9>t(p1D zHXq03cH0+NpJdB86c@{)L+nj;oK#B>gKW6(L`)bTm@|^uPy2OB1!jVNU-r}%v84qy z#rcp85*;4IasFfxqPTGMZ=Ug+BtUy|Npf$o$!8>N2fwq?tm1wN9Y68UQOI9Q=ca8i z6|Ca>g3#@Q(oxJ$+0Pd-WS`(m#`&{ee5vrl@pGh?$Ti7cIYli-FONUhEBId-s5#%l zcw=mTuxiwcJVfm26poI6&obEY!~^+V(TwxloAGvmmcWcfntMD zWH`M=*{90BD9Qv)-f!<&Lr)Zj0kOnMu;STKx7cN3RG^v3W*3uZDVM;;^4srcT?d+H zDFP-ihC3!M5V(qRq2dXN;WYczvnB=s4ZE zP@BPoQl_!}PB5?xuNM{NZ)?~5_&mdy-+foYV;mK4VtRH} z2^SG6Pb(W10B5BIRyUSjYq8RNf-M%i&R$G8-^L4`Xj?0?B+~f8L#0^QhN#<)S6wQe#mTe~Em=oH&xKM7pt|en@+< zBt{_9ASXn3agUmA(LIM%XY49zIuYnm6Ayvf{<-BQG$kjn#|rGM6%l>zZY%5g!2Z_kC(^Qy|NuB zBzkn!V+N9|&2zWjG+-kp){AbMAK@JyVCv%n(!#6M=xKO6ULX@=8|?z@)YIfMP+q!N zAAKS$c6U_`x{w}4wFGJsSY+aQpmuP)rGOJTj3=X-adv19)<1FcGTz@{Ob3mFGD~$r zH&%4+=fp6TusPlGaCQp~vV@zulp5J0O;3Lv=nle{tm0)Dae@gimwL}R+%+@%4_cp*3^*wn!lk=K1n#bV{HT1&z5{i5wt z*6lgVjN9I=&n$XC5$>+wmf(1ay4=GYO6~2#S$BZ6b*$)zRb+vDp)|Q2WM5i~-{pfE z%+j$j%eC9gp%BUaLLc!ZK{iPUA+ckt{HO+6-Hdigy^> z8m3^8sB)6k&3Nx@%I|c~{PXl{$PdKJ(+CO8^xk!AnJLlpC!sRoQdwwJ*x|&7jwt^A z-MMr-WmyEcPe`NK2#H%1N>wpK_E@Zf2pI!jS=GQpVZ^KBo&ZCgaaIl-on+|?HC1w9 z0hnpuXQ(T{c~s39+aS62H7&QiwLtxZwK}0ZsuCt!B^Uc)=9b4*1%6)%X4vs#AG_DOOECS_4_S#lFI}{;s zra0+Sn+*bHQ4IxEQ8=FC*?pwvX}XvM2bcUNu+Z>(`Nc}Wi(Re4yc^lh)q7j7OS%-} zmT)fOoZFq2vaqHX9bkY)3}?VOvJQ&NL@T8fDKN>Acz!}7w<>~Sq|O{J9rtG zzau5wT~4_TWoFmYloj^aUn^XxVI9ORK}T1XM7N<(aB8JmjY1+mZrmlLd+hk!Ea3X< zWwIvqal4Px^60Jh>q=OcCiwwioq?+V)a)(ZburDx z?O0z#UAY^^faEAmX$7U9w2vzekJ>jILQc$ABncI48i8v;k!h3C3@A?ettv@Q6lt-M zf~vhA4!M36BCsRxI*F0i8d@g!4vlJ#hna%$m5jix-Ejnqm=A}^PFi~Pry!M+Up(LF zX6N{;g*I>&K9s3{4}7EBo6{V5*DR6lu)8>|Xb>;+nudn?nPQ_wrAN1%?_GxNpzyWx zs=DB4&t9U@gGs(pr1Ikw5(bSJy3C|&*_m2c(|QXT47yuYcCK|(F@_kMuS+-k_huMcQ!Whc z1P>-8k6isE~ z9CB7+9RXi}F9~=zUZdRoZCAjpC52C>(;Voono3gGwIQhfojH#Jw2!TX0g#G|-Ri`* z;%5lKhCN6dZeVnMn@^!z1YW*&C%+D-QqxZkRPnUeOPTEyE11vODd&<|hJAK|r!>H0 zwXN+Ep1~4pQSXus7Z(u&AI08JD!a}g^(L!UHsa=3M(taapeSc4g77FTroQOEA0}*X zMZ`T!4PdA2rON3W=Kt(qtGvTyYfz7O3bP>O&H9bBgc1Jn7scsPYw)$_rMKOyyO-WQ zGGuF^LV0C|q4lDAU*QgWH9;o5Hg-)b)?$d0_SZqX-8_`$nG%x_*EfE(VvR4qm|Is? zr4^P}dLx0;p6WmvG!Y-4F<^@>2Ht0a_l|f_m+ZPzqqu9K5c)3zzsLqA#)Mm%z-Zry zw%!qKS&0Yr%6&?U1O#>-pB%7R&a8pKm=6rI+4iv59@)={1la6vri|I`9Px?AdyM%6=Uuy zHgAXSw5fPfgTZzwre+j(zFL^3^YryW>_W?ZFcP6d~#MEhPT#UaPtgSjed=Nq`C5O8h1IdW7j&%np)Pl z9+1(Jr`3X_9TA14EGxmcjLITo1Tr?e%*mSCN+(DUXBXM1m(INDW@M-OVk|{~!S2Oh zqf0LRcs6zqhA4*I33h5OK@@e}HZ1decQOnj`BprU9H2g=NsqgBzKkm_d{nA*yEb{z zT82{t7v4Qlk>UY0{Cx{%Zh8I+q}<p=@4NM%f>~p<+E9Mtl>Pr@4 zD=E60T^%WjX*b5)V4xNzr2Vabbgb@Ri7wXAp5PWW^%beWL2V)9r!B+Ei5L@FB=g;f z9|HDEIWfLpT(=#}i~Ux^CXOp!@v|V?Y)m5C2WLrc<;8JlXF`L|Q_^{E^%^cvwdgA- zCXz}A*i~T_ha@)vb+$AJnbx4p1JcCk>va;}tU6ztQufN#kbkam<)OMlDE%z3^~zp! zu3M66Piza=%KHPoWpCFvE+KFvM1EZn+?t0A;xoC0oMt*!W;x^j>Nu#Q=Hxc`3T)A4xO?}6}E;)DPZhvzHi0adUoAQT-4ZR&a zt$SWn70Ltt>Y`bSJ~Br~UzJvr!EKg5CzND=kr_Y0QFwIK63BvI=6W2FiX~kr7bRqo8QUj6Z}+Db z#aL;3JDIZog6lzb*>#4=bX>`d%GR-Qu0MGgE|aEosmC~754Bu@5Nfi=VDhVDJ-xN% z-`Msh>-Ah5fDx&c!FgWHSx-ssUKl*aMC{iQTm>ygQ&bT5 zu3&V;=D;|+C7Qe1j=-Wn@cMemE9KMud!yyJf$!~m0W9s&UWwl)5h~;`hX1;!pHJ@U90dr+%PHK;_$4v!nLwZpyPqXFx++CNl z+^j%f@VV6+=5v4CRY}Tg$}fE-N;-}&dd6|E2@HjzFblBUto`bPfxi&!;j5`}CiHF<kcf<5iA{8bjcQEq1G^SQ+g268h9 zTf^t&KsCT>PIn-^l-E|o05GPQ>(f+Bj#MjC23E;wgAU z2zCze@?}n@57MJQA6483TxBYZNt_3M`8!F6MruqT{wAamF*WSGea!qv?O46UKFcQ9 zLdbxWeJXDS=!x)Qr=FgCWwlasi5wbtHofX_FLpgI%`uHL?_ff@2J6bvN>%*ZRHiUY zX-|lR_h8y}skB~fLA*KlbqJ_E($H%*&Fn?PifgWo|}yvCo+- zf<%|DfDdmodw2j3IO+{~_}VqtwJn)MV_GL|e8=(GxUXjdo-6IR+N!^v9W|Q9OgF$z zA)(_=x`rFt3~0g5O}Lg(>WYffpEhcj3yaHSnRVf!wg+q3wZ`49ccMOY<@Wft3OLT> zeq7R$PkVao)&&>F&-Z*_V~4BpJ1&W30!P8fhJJVlcMNc|df}Y>P7C zr=ixEUbQ@?=vPb&(W*xr5Kqp3d@qs_%#Dg25}O|Q;h?FT%Xt}H8aw1A*CN&r1fs@;^)2kcb{$8uAPnX+g7}Zyv*6p4uvVE{H+8$7Elr| zvv`n9AA$s>ZAg!7FFVAVK z3Q5&|5u=ThZ?|3i*-zF(l}&onNlqlWXpOnCFPQVbdcS6FP?m1Q%yrdgv)(b|t>nnZ zJ~oWf^1A`83+CJTpuW;+147EA%HGtH>B*Kh{s4_#yZ+Yfz{z&}TZ{>SaMQB7Q~Ct9 z{P(#b1g9A1-ZoRN%dZTahk;V_-qqrdZ=v3x3|yw>S<@L*2h)Z2ZOh%^l|D#Tc|FN~ z3tN-Z#p?Uj1fA{2`gJ&&5yQ6*qp5D=5biffi&e~YmOgAD_)dcA)E{V=wVskrK&_!F z;Q1Bu_}ZLJJf_3m#q3g&se$!`haCZz1W=(VDDpZgEr9XdKU?pM`4=yu&iO`UTJ>Gb zQ}=iLt#hnDgk`l?C0kdj6}4l)tBm(8mFN}~Nu7hDc()jlf#NUDZm`Amay-XcJs5kM zT`;?{`@R}-1oV=?Odv&pxzo3$*~?4H)D@i$A`72L&DwTJCZ!h|+&=Wo)5KY?T!+5L zpm=>E=+Qgm{58-3zM;#*FwY($8xr7ppUy9?H>Wrt*osN+K8PpJBhfgb=i5X*YN+eb z(C`GIMbh3dh(ye7kjwYmKUn1hY|IZeoe|#_qK49SsQ3_bG<;@W@6Pc}e2F2|!nqU>&2vA9BTj;UWGVgw|UMJ63gGBGOatTZf-TY%wM+Mqz9nGJW(R+$k)Ng z2rV9aKEBYVy2mt@_WsQB(*@rj9lxzlm%`2`fz~gN_~Ha)gQJ&QnH|+i!0*LLN7{vo4^f@n^`vVNdg)qq zFQY4E(WMW7Qo4OJNUNsHO`uXm@|(?reLFC;PR-fQMY9SRTz$gJ2(pGu?35sNa-4rSoTzu1oA=iC577;|ynGtOcaOrWq4MdXEl4oPDpsBjGAa%0%X5DL zevk3Gs`Qq%lv->C?yaWi@;xD;rk)%%)VO|@{_|dcUE{dy@QB;6kG+lFG@L>>Pa+~` zmueS#nELlT>5KI*3{To}?1F^y3J5!g$6u^uW}d0cy0CO7c8gN?HnPCeSH9Kmawc>> zaOh9YUS40#&R#ka0C(*BoWgLbGUum|r|xxkyX%G*Uhl2thc%}OUU@5dLcDW=BatGU zr<`05VU_DeOwbCnV$nk!A__DIDknV$O@ac3%@pno{8te4-Cy-Bo35za2pi4O0JuM4_)@=o-ybAfN6i-sV6&9q%*S5k&igRs$6*)4I> zd%bs=40^*A>yuxF?;aL|)e%wbn1+PD1Q%9xN+;yD1@AAJliPAsG;Rp#3Aqpy%bgk6 zGh-RDg=IMe@F$hYQVFM5Sgb<>vnsvQyo`#HL_uOePcMk|p?6*X^~bRDDJuro+9s?B z_NeaxywnrIsvSHECG_68AVNmJcz<7l!twQ6B9fo{V(eWhgXt#mN`2?#YiM67g67+l4P&LpcU9X+dj zdI9hiw!vn_ve*^K}El^*yEi0{080I$?odXO}aBb z%kix2SWsSmH8AIC_?z2?YzljQ%k(fK_8wwzcB!Sy`QGvbu2plJlzo3&4m-Nzy-zti z=EV8l_NGylT|TQB!QS}0_bnFJ;WECT(3XHAF$xT|5YtAknWMJnch}+4;f44wM^Afx znALE+H1ly`eh&{oNwld|-Q21{BaSiad`2&Bon%!3SHaS3|9@AQ(3eP^{Gxk=GR{@RAcB3FmBfNB1bmVl1l^Tw{&y znh4gG0@?WEi>DJ2jB!^SJ@x|>g?np@DyB#?Uu*L>?&_8i@)bmovEj`*LpVcRv80k$ zOj!w`E2*z80 z)BCfzuRiN@{MJs9u@dbFG~>yi*Uw@Zqzs<>TyD)#a%HbLvNotX!6Nqg-nS$ZtW6dK z^P8^pKrH+D3jEByU>5{-RaqQ*pp4$Ri`K%up!r5OK`;|IuH9VF8XcZBTV1Vs?Gewy zA7r!0N6oVQ!u+^5txZw>^=n3!MwHD#$@j1)$~^lDhi@Jf^deq@L2oooyCBJ&7o#fg z!=uHdim)TNV~ie$)y{@JM#$y{NblSnJoN7NF`=4(i>^>?$9XmsmGxy@+yz~E+_ToW z2+T;}S9FzF+93vV*(Be9)1IczZVMw{s;blJtV-M3Y9zWF{~P>jNt5wH8xq?*a9%Z2>T}N-_uos&`+4FZy6~EI8a_o{;Z@nKSRL^%;nv6Q zMJuxJR@pbt$skm|T7rCaKJsnMe6oC1K zZan4htAVHSe`PD{Jqq2OMyE`zBE8oSe!_>bs|v9Z&8e>}yHqxt+Y zdaHxl2&WHBl$ZJWXug}1M=b2*q!@sjAxDt&7tzDt_`UJq#wOR$xSCAqBZ?_`$CU?K z4j@;!e?>`)?)^$JHT3;0#?j;0?mUy4ooeP&oRQeXe(l}aqIDMP1lqwjh7zMD4?;qH zO<=uU?E0o82Q|$le#p|jV5&?#p61-mKlAEKwuxe8{cov5U2ntE;^p7OKU{wr(G>xp zi!@MWGia`5C(jOQ68vWp@sAG;{5M%Lbko}Gb806m=6Als{smYEk%NS|ZTls9}tw!ksPBNHLC|M+c2M!F#3>kLy7~dLpw4fsYcD7k_sq ze19{{JRj|0=u7m5Dm{WpEnz=dtBz08uXt-opruAHbuqdoHNYjd)00!r?*rkJBL>EX z$LI`^XQ-ibG#>cd!PXHUE7=>T8lZ3&$>^q5+v zEiG)U$7V?2zkb;+q7dNyPWMA>N{{`S48mmW>*2R?%(LaRuKYOyjqtxsdelTcMOK34 z_0MehoF5G|RwpJS5!Vufscv_dmn`3M3JN#lId19Z-Vx-&&IE{H+aRsG*tx1TcBFI{ zkIhJrAD+q#*6Lt+$9B9*Ag?!l42E{V)!8}cgG^4(4E{D&3?nhfaFnIfqfqWF+fzYX zRy$ezk5uSCAJZCpkk#Np?3mth0~DU01`gpp<4*XTKWp%vV;s7gHo@Lv7HHHdloqtX?4^DtR8qxJ%$sa3Ai z8HYIUWy;WsY&1;A&P4pxjjZ-ZhPolQz1g+1`Ax3v;ipz5cEm@>ZL-Vt}K}F?_@FF#fdTVrb@NH9KLsMO{%fGJ|ew^0Q@pFW2S9p}tUGs&| znDZcxL6z8NDF2uA`=-Vq$i7DZKTCw=^zEW03@^;el2)~62R^Wd`h1mqzW$PIbm*1Oe67Pj&;7fd^Vtmc z?e=%kbg$&-jM3o-*N02vS7mISZmDM2%{L1F7%l&3PDkmO|6g>AiSj&kl-qii(Ri0= z5Yz4d@eQA-{sgAfU5`Kds*Liq6)gQ9{1FvDIE-SjZQFrunS(g+=@ByA_~3Q6O3qc- zj_SCM+Hy9F&0T9>mvq}xK;F8gYA4}%#o-@5G7{AN-G#f{J2YViP3Tgz(TplLF82{G zidFLezu72o|5NN5>Uke~QaXjLx~3*A4yTwAEY$ylXM=8uAwrV}vXG z8$3*Zn+r|`0>dFdQ@=wx|Ayp9NkxOsgCT^S*c*lpB40Zx_01%f6(CovA_CvolC4dE zj_qUl`e=f8b$ZoQ|C)wKPX95N{(MnX#iQT|q-!_<1mp%AN;L-O%3G0yU6Ak9UiS*b zf{=Aq-}K3GA3(=CMmH#kmC-)sq8SfY`yq@ z$_?L}{FX##&7uFb5@1nd?Ze)B#~YZM?6L=AJB`{=p>3{h=}~Y|xw6brVN&>_^r0x4GRvp6*V1=-;MZ!_g=M9--MEnA^7ZgXw#e=O5bggSxon+PEiHPZb@s=X zZ*bht?5@p8m7 z*nac;|32@(j$|2Xw!R&arm~_m#DV6+NrUgWnV6ZAT%;7n#>SLJRXz?5H8I0Qk}V4h zOQH)OLssV-E|*E=tJ9RQEy;b$WsB18N(NXI0|S;!VLFx5+IM+-0-BV!HuN%>2QLcW zG&>&rkgtgSCdjFFWOESW!|811(BNN>bP~(j;ZS(3zN^H1c=aQ~YfLy~qE+9?a`(el zDfz6l=!oxmeF}JtaP?UEcK!~E$9cI9;c^WSy||%}@K)o)l2vMu5e*42#>aVUf{5tQ zOisCp|MT)NYBK1OaggOZ3vYf?T@_bK%^nw&w&ca(e{xjd7jG~3H&Y31VC4a!4eSsi z@)>bQo_u^r_UtxbRC|=S$wljW|8~OyE%dkV%iIIuAmH-?Me^YA7_o;ZyZJY?TNkZs!Wb|CPbEd3t~h|PyTwM4YUk3SHP zfRD+ZUNw53Fdiva{JBx=ohP~)-BK=~FB>^Y+6{Thxd6@+K}#GXx8|E#J6_fE_4%l< z8(bMpe2nBj6;J~;gXiRsiX{u?S%rHfk@P1`U*A~s{ZFsw5i4*;N>B z*Hc!nZ`-c2!NZ+U8=bL*8jAGg>MLz#FmV{w%GX#eeZ2Gh%$M%(^U^?zZi+do|09)X zguTT|XM!lRj~Cg;xfn6d3#aj&2b1WzIg{sY-SZ5FiA>xaeoNcm>0#fjvXZ8cgUfDU zBdTSTCu+xB3inZ?DlzD(vNnm3=@^>$-`iAWtt}y&{YrlTlNKW)Dux@=Qn8QnSoB(ncUNZN+1FBkY%HY`sG75-!bvRy_{YtKqkT`x}KOqkfM+#}>ml zp6+qod7L*L5BRWKWj$(+jvRBJOV51_aJP4KoA`d=!O?f_5MzU09?Ie%W<7`{=2`t& zr?o`@s;s66mpJJ}`$fa&?N#N?huky>GS9cC49R=$s&jpQSDgEk3C}f-+K}5=pBFC< z7@;*Pr0yJLUI;aIQQ%k$TAXwsS(a`4v**%3xf5XOzJ=+r(mMHtbU_GJ%Yd}phsDzw zhFWKIz!R4N83X>;@FEn9Gtl_AXTW-QO9l%EdIiF@Q{P49yWzNd!Ub~THK={*#65^g zVx>uR{i<(@`+rEmqGMC|&DGa_f*CKY_=c=p3qq~D8|2Glh~{DMgNU8${K8=ndbI*g z3r>I0>9+jU;1YTp0dqn!>oy&~ZcZZFo zq27hj7K>+~Clpe@QWrv?xwaWr#Ly*vtiI5q`M{I4dqI~-iB`fWR?!>~^$_7jjtPPU3&wh(?W|on(%@f?PiiDnl5J63DRh%W zLfp^%`o=n;$%$@6MxWDtNdbEvt7<8?8(k5{#BAxYg)$z=pv8~qXD~|(-Yc$nPLI$G zgeTM80ciN8rx`m@(LH`Vf0)X0g0NOTM@nSs*I5Tf-qFrJ??-?(wLu!4Tu&a==QhUK zM|iMv6K3~FTyYTnd0bUAOESNhIvI)NWedPturFFP%odsZBlX?<1ce$}OK30x!F_BKleT zE;4HwZ^x=oB}{+B$1Q%onn)5gH!Lh&)T2kn@$MxB7jmx8RmV4aj3$oxW{RydHg$U8lO5lcRG16-F3*Me@nTJuV1jWM(`nmh7ERJ$Scwp=g}!j750(yF-!}5nSqc9Mexl851*yRlEzLpc*>25DIzTD3_4| z!F6bZ5h@arI`)_KbIH?d%CbSGz;wPBiZ<7kZ1)LGw#3WNMtt3w@w%=Uh3l0TpNx22 z{TS9(05i|y7KI#;;9M;5OWN$Ae zdb2r^d+Ccyjy?ut``PmWH)}j@cdRE)9t4_`{P%n_ot>@;zi#7f{w9w8rSD9Xhju+XLDyfbmLgCyYO^xzS>z2w3>Wg3*Bdf%TD}^2bwUr40gb}^S zTASpYriy2qsII|2PgY0TxomJtMze<`EJ6`Mr$aP|mh~n(>IS>!Sbhm21YayE)D)@G z+z5(#zfd?)z$0kwNFH3RQ1w>6ydKtAkDM`FizEaYuXh1ArgEJLKkUYZ*@4Qt+HAPR z!&7((JzVX>T5?M(*YfAi;;LIyM7;fIh}c#c=1NK>NFuix_uXO0#gejfrk)T72a`np zrxJ5?=_mAF1tG*2!clkU$FFr(MEvkS@@7af`Ql8DvA%6#B`=(94ZVkX>Mk4TpQfpq z2xGg(l2U7y1Ufvcyj;~{9Cn2g;3)a9Ip~sf{}1*0zV#_*dP(f9TE2 z)+9@-mL=$C9^C=`Pln4#5b{9XBU@4_QF1OqrDs}UUc548^}`pUMj5`UVtc~wC_8+0 zN3NwR7rKg_EBSxw&3RgZUTOsz32`6xgmbW-W?Pg5E#KN0bTEWn;0m=o{Pbh%0J8SQ zJYo^!MB&Q)d_0`BiIs&_oD7K8$d<7c!^cMMV!+ThU!FC?Bf6ZNH=R@AXo&2#z-(th zCfK;(M#_-W_S^gexG~gDllLWhFGo90)WK(7Z%<>uMS`n~_Ws=jZ8;T6806U;*7}r( zN2mAogQ^TEY(^RBWo$*)_r#l6A>j6%CMVEl$wNRNGfGn?8#Z+Gr7LT)R~yMY3x`d- z>IA8!aquF#)=^D>yT>7;EjLLy9;!B9H|q;8zv_7q!S64)ConC<>{FW%ceSf15u%s? zX*cY?M(bp8GGfE2ahI+Nv(*5%6F%1{3SZYgI1= z^oXldY^YTGQYQK0X0w)QgJd)E{02{oTKisfxVzCY1 zz$*<&yB%;UhaaJ9*z6{k(7}C8R=EqBjI1hCi?wfJ3ud!Tp`7v=Jg6=^qy1g&tUX=H zr#Kdtg*K!`+(dpcyj?9}9wBvl#6*FQA6W$$-bVj8tj=pvIlioRdOxc1ZTn<%QAyXH zbtmvKl8jFI@$JizOo_l48cPm~GzsIKcWHrl3!M|N5L>LJ&&2-^qru*6LClwhb|5U`E7_1x2Q2pPIs;|vw8Fv&c0tGe%>ZrR&NL5d zwP#1R#C!Ux&Nk`tyFhh|Hm6^!>`{Fs;-$R!Ax(BPm8(N{a4SpfcX%Z8?(^pIj<^Ww z7UiotTw6o0GQ{*H_-p#4FX-j8k?JrCpou@j}!Di@-xYV;T7EtpxSA#caiJ0 zT$_F?vCpsVv05Ay|2ULYD-vSOMagI6ISp6Ve4YQ>Q}`c3?9Zl(?oX6kHB&g3HBI$f zwH2v91b9tZ1w?N94#ynQZF4{)u zMg-~g8kcN&%sxtjAZhg~N)Q3rKKqGw~R$^yo`9%=^ejQG~r&M8e z*`azsu_3206ZHlM2Tk^iptCH0zvn@h*c;6<{$$T^RpJ}mDONcQgT7o6ujOvpCV1a; zrVQ3bw-|&^s)`YhQ!bm!J?@SB`F=#cL3irrqAsF*84K!y-lJFT8G_c2mD)RqMZ=xH zmA)k(3n4;3(%geej;oBOO*Qj!R<(V_L8O*=%-^xhpBa%YGd{Q)T$pZzd5PWYY(z$D9)o&Zq}Nk2MUlwetjy^%RAZN z7dAuu@0}6XvGzo-77*?51WbW__Ctd3{IP%G{hL!Yc|t*M)jiTo zBLb7mtSp6%fl7T#0+uDXzz6&eW3^+W{n!0ziZ<7eHgc29 zvXPI{M(x7=+^1_e+&W3g+fQY;_v*Pq@3KWSHoqJbudVE=l*Zj=^-ZQuI4UiM63-6g zk+nQ*d03D8IewE@j`Ddy)owtV0>Xt*0-~Ujt5$R;qWCm*B^5}4+wUKLXgcZbzaN*~ zDpv_UlWv=>=nemgerG>~t}aN1gImiCI6F(IDG@r-&5hPNUFwwmSTf5?A)txodE1#% zRlt|iq>2ck>L2N3BbW!FT`42wT~+|9`P~Qh(9!}=6lCB$VRs319@Ux)FFBI_RK}~H~`>Po;y(ted_Gj&f+E+eLm{N~B zgi?m5)(q z4o{x~3qA!rf+8=oX2O-|wVqJrQ>zIems{1T)1YI~q;0ilPZ6V_D>?(Ycrc*C)=1C4yFu3*4XCR>dPRXw}4tt{o%R!s+w9wR4J))FlEYp z7;?(()+c!qQE~bBv%4CkaojKOg_ZRisy@*8`@&c##%xf##|tah>fdmEI5FL+x#aZl zwxfd~iF8}k*&4Oe-cuwr+{7U5ZWLR|Juw&^)S#bz!p<+1botsbU8u_p7f;BBP{;S_ zAS~S5$R;1N?>boVfYeB@8d??4#z3C<%);4nniHnlXrZ?@B}oSO?ZzqhmiQ<)AI%{| z8v_hJaUPQNj1(E`2RkU5#EoT^Yo-)(m+82IHh`T0UfvHQW9{{VuKD}(O*fE(MgNQB z`9zHf_rMo-Gw4djCEn2ry=oj#gk0AJYuR);O0J!SFIra@zCr|r`2lf3vydCNiR(+)u_txKaF={Fk95nOY*q8kBvWXZqTWV+$9BX~fD zh%w0War|x$l1y9amlb6)zT}z6R%$=tuN`xqh6<1hqDF>3tlbUWdkSh7Fl~G`>D)s5 zDc4qe$)yLyb%EU{{=oarkAJ&L8W`hjblo!CT)8g#h2$(~`w#0tKyhpJ`R3C9qwA~V z+S;~mOMwD~BE>0Eq-gQtUc9(F6nD2maEd!cN^y604Gs-n++7L;_Ym^ZbH97vJ?DKd z|Ljfj%VuYwDI>&xUE79<3VTWxCCP$1^S?Sr{3myT3{SrP^{u7w_}YBz-)KpOf}!>t zG5@~Oe~wGsa3T6e4jzY}hpDVNZlC5*yL> zUe|@1LjWE~;pNoSC>J%nvgca=?{EG&Z>H)r zWZgfoz#}1v%*Y^ZopHiAX-524U2BY0-22xE{%5Gd z4>Z*b4P!CM_=n%M5i`^ZrlqC1lx`BOIHLTkwLt62%HWZ;EHfP&8@34Sv7W#2-T!(g znTmA#c9&o-Jn)KO;KiGOVCu-2G@Igpl_Y~Nho!~wsi|Rkc~p1z_dP>H(grLH41x9a zoKN=?{$)q>&NT3;BI@kS-sXN3dUfU2KRCFRW|>p$f&*RKHwN#;iP%0rYjRwV z-PrhygoM;RJ&n6Rkv#-TW;#DIf|0bgwjSDk`jHq$;dduCmY$kQD15hp7)>EUJ~cIk zzn}Z)2ZP?SdmL+j4GAf=2DN4hdc7_!Ej@I*zcAO)t;7n3=so+_!_JucqA;$aH`nTF zdEFPt@&9>5T3T9smg!ozPxK6Iy<;Ls$Z7i<$3;Uib*e-YCt8TV$;imygOro=mY0vO zbfjp*@0}kF6H_@Ay)ZMgg2BYqQco}n4x2I3%ZZ{M*>wbS5yG4+UGgOql&y!55vTK8 zF>6C%2YuF$J-;uBIId;&h24?(l_>Nl+Cv{R-rt3VQgd=48wQG5rG6_SpZLsHf&c+8 zH*5W=RG=jV_+Y`|UqS!^N=ix_;bcL2FO@kBKO>-@0TjHorRq!$It>bXe!Y?uiw!#c z^-DEFz*F&62E4#IRH{~NX5A8`#Iuvc9L}UP z%=-KnbM!A0Ta8TmeDmYO&@eReP00Kv`4s+qVqEvs05SNAY$gE`RjohJXaHvlp2m@J z;)@uK1+>SB`0$6l-M(UPxIL3NDZD&8oIwV!3Mu>8U{O(1Gd;f&c{~#rd_3#3>8dtp zf6-}J9s6rtQ+m5PN($=)wyVaz3uzMgDOnftmrtW*aXNWW|pXc5*D68+w=KnB1upB&yrHhsc#9hQ!NI|%E6J2;NL32V%EY90nY*J#TnMa;9W)}uIB`Vy zR|(%08TsBt@sWLZ(g7cYdPDo^GeF^o&(2ecL=rw> z@8aqkOhxbp`NAv9t_Q;B4{>6HS=BR`NMr&Y>bI#03AuwsZr~++={Rx?0Ze)^h*ZAH zt3jZS)Uu;|4B5&lp1|8PnB}SBhAr>BNC3>tvrdNU&7ura!jft(zMPdav%x`Oii>sf za@k>7)J@qLfSOzboFmrCc#aA`kx~4MX4iQbJhTjas7|OMSS|-Z-y4+ z-uypqOVK!*xlArP!5xgudUA(#vvDVukkF)1Fv*+bT|-!sD~oH45W@Oa(!~BRBva_;c^QGfJ0X_-5F1IJE9NNIzC@hfND|${m&~_5RUiYtY zS!I?yszy`Tz)Yrd}T zs+`6{?QSniv3bg=m2=2AZiA&?T}vSzl0KT*e^epK!sV5Pdzr7g2=k1hcD#2?0h%U$VYJMnJpj7~Vv$>Qe@nLQ4{klNH1S@3bD^*>1VVDfP;QS%H-w=$ zZuKj{uykjArVoX|(=&bt*vBEXTSGEBlvnJK8d!dQ$q*gl>J8C~Kj2TTchZwUvkUL} za?32y)u>5jP1jfBxr^VZ&Xe3BE2yKye7Jgz3jZ0Pf1TtVfzu#ay;a|V8{p$tnHr`$ z851Fet?&H!S_qg?6veDngx|XB&12l@)*jiPl}`IjU3`{ao<@ssWRzpV;}rt+*^NK#W>-K_4Oav|cXN~E zG(qNMxe>~DX?sbt*^OH!^LaEyvUKrG{%6{}ke*h9x5vltXS@A!d6D;TC_bh&c@6mZ zOw~mRIB~x|_b1MmO}-?0jg*Qm8@}R$DqD*tGr}NMnv1cgpue#PMgazT=GID*s!~Ta z-qQ0oNTxqSIf!$Vp6Nl#(17cm_0v!>aZnI8l+7Q1;X5Wr4UqfhQcx8WCd(?X-RJ7Y z`k`KFpj1*i0q~v}&6WzgeODiPy#8lMtwD16<6zS6hW84?;e~-St*VLQ+r551 zykx?j&wBxNNxm{djE8*P(CaX#Q{Q*t%ifAz^<9hW^Y~e@tui{kukZ6VM%_u}aIl3; zKRn#nB3rH^?_?^7ecHjv_^Eu-lXpqq+}Lw(D(!p{tqByKx#Md=vmu>ds;<87B%7+! zIfvUY@=GD1mt3nxDkJy3jyj`H39!;_yTMMg%3vbs7=>Yv2}Qr2)BjI%0aTo~6| zca74}`|#_z?-Th;C0lznWxt_UFl(l*Muj$a?KPg4r{iQ{(o#2l@eaFp?tRwwSbvWM zRQfb^4I}F=Tr%WiLPJ{lE}|}Q(q4x=Zut-w7$s#!ZdI6RFY-uQt025oGmU@aukE#u zOms1kyJ3g%>1CaHw|`nLwwGmWu4t*6_Y=V<2fsJ|y-b94^;(%U9EO7pmnP3hQixO<8yA>6k7j6MYQP|DqEvK?zRCk=Q zJ&*o1d^^^yxuPfP&{QdK=6zl8HF|=z{lRCOq%dgTf$1I{nn>G1&NFlG@WId1w z7#f5PBM$=32#>#C`Sy)$_$gFPUqktHEg;ReH)^rUA>$M$C!)>?7sRd(FDxrtf|@9- z(PY{qTqzx7Z*MBY3`&|IXP3CFsr4!40UjXI7 zsjg6)f_Cn%uPJ+*Kbs(#0xj~P{v_iSj-Yp3l%|V&2ERyNqrLk%gPg@)jmwq9**dwT zzer{DK}sV&r!;17j+jYWaQGosbgo{Ay{CNI3ULvZ&i`#w`IoC~GoV>mqMltvA=E{t zUg{w(em|!(*i!Q^(y5QnXKvi17Um?qcXj0KB+!g8%$fHm-N`q`Y3^!q2y!A^<2exxZ~^q0DC zP0j#@^)4*H-f1v7{~eQ&{Ot2!M{MYtHXftz+2LVfvbqISS)e5!!!j=O*C!GJfC!;B z6`|#Akfz{_)dfXr5xDIX=~Z-ls$y z-10e12Yw`EhV0=B!Hk85=SKdevrzAlxh{O4N7g1q3AgJE_Oo^I$-y!_I!{t{KRGzp z^1okgok_&w)FQihAUV06qmT;@^VPSv;MI0QI;E`s8}Rb(LyH}t78W*4u{1Lq=BS-mS2@j>A3Q1{h&WTk^zrW+e@d-%iPSjg(Wp+O z{(SwW`Q~6%NVIC*FKDt4$dUkMl!htqk~Nni0-PA7TKC4Eto%|nJ@TPAG4&wKJL@)=i?>Llq4wN*i%%Vd{U;zB67-NcSfDN}>^(_f4i09^cgv-cls`KuRdd0x z_vA70rCl{MWi#Vw%KF-LvBpC*q*L$c}_qsw^+AsWspM!@O=7A)x2ZOib z6Ow~ZP+Z@&qaa%DrIRwLVu>EUbRfLWgF$GI_w%NnxO)2HMieEc&h1OtoND zYI_%ce+%#o^@QiQWiiRbx;p!>Es4*qC@X;ScTy~#4Ex%N(FNIwIbmEY&zX!Yi#@Vj zwq%!#O|^|)-S&MCOX`Z2JR&z44a;dhe|U6!-llL}CY-O(9y{pz<;>p{hodyqo1`AF zoDW?=!=IP(nR^%oqg1o#B8QCVZSjjd&u08aIO7bZ;}@#Hw>mb;`m74$Sbx>1(}a0c z^cb`NYgZr6C(Ic5hE+FCm4AqoQebv)`Ap8UnnbvHCLUi38hWbb*cb8PI@LF6XY)$a zyj@18*)7mAxqAA?0soC?yo>2h=1L5%E@wc<#YpRgiA>+`FTMk6$)6{;uYP|Bw=sW* zpB!;$u<`A()&lBXVN{Pa4M|fxcmKGsU0>t0NK!!v8L0DkmEtRmNG+fbRo{rnW(2>_ z4ncqxnf_#KTs3#Z2(Vv{_zqNEHN0Pw`C@yGyo@Q%1`d9w-70kyR#&0Zg+!r%rsl1q zvoM+rdbHYK!@<#}#UDImcFClT;luI-2axW!*NMxL&02=IU@( zuIlz^Ua5;Dm0CLX^Foa=Dk`eza+AHekczaOQbvgshPD}Rer+SG9jJ3-K@cg1`O*BX zzjk{2WMzcF!|LiQuwAB;QF|;rJWWoL6;F?spuV=RLug|U_Ot+me$ zHClb1uZX2UNpIvmRgyv2&XL+Im2b(TmDGRS7Z|hbyiu(- z-0b%8Tie7Y+h*jP8p=l+WyQtvhQbCyuOcD^-J6f6^GU3LN=<|0YSf_!IDTvb>B_I3 z%nfv}u2JI{=aS*e%M>JDuUNXD^PYWZ2C7w{A@H@M;tH6?$AJ~)(Y!qzVbb!7Jn&|$ zkv}!>QuOF{Fb}}P`rVv-h;lL2SB8EjSEre>#owb{4rKsv-z&*CwDo28$1ImA@YntZ zA2s&MAVQ(@5|?@x5U!LpRR^=W^2@!*H$65Yih-OuzA{jGPh}3nq*9wl6B=reYP|Df zC+7@(J8aN8-Ec&lY=-IS%%XvKrC=XDu=skn?f%{tneiyrrlzUTC95bfa1Pv=qt@j- z;Xpt4iKT4$x-oP<8mDEM6TSEeZ{MF(2ZZATZ_t@jMtoaN|HMQ9Vt$eOZ2A%>?J+qU zg#m3?kRYr<(0ru>DxWpE`Ak~Nyqq45SfDXaS10FZ_te3%0&yR6-YFzry+Up9jPh$V zPuk<#lT6QfA6qk}LiM1ecdI6$Uq)AUht!j4AY#kD4N+EX2eNt1`5Ck!} zHI`V{tl^;9uI~J)YmoQw?m1+g46dnV8L_}-$+&07kw);iv;6((7W>Pa?3c9P^?H8t z;BBw@Aof-5Dj~md6nu~%5+o^4S2Q3W7^=ny2F?}PhdmK#oXdS7Dgr)zc!A{AJy*b_ ziAj!1Do92l^rj^F`^8{@qlK|PkK+P~CGU^r-u8Wo4rsyehQPK@61r92&9*T-uS>nS z&H^&;%q6lz=^Hm*THzu#M4)rArvA`YMzIh53<`!X0H*_qi*!lZ)&IzKBlo&KK7ysH{(V3Ue>k#vl|aqg4)jdA4^QY&vg zrz}&ctnFPx-HXJV&+`CCe8UxeB7t3R?7pAGC_*I&pHUWdh+@JoE+0LqDe1;!{ShbZ z*Rzq7Ky2qetpYau;rtX5{K9A^4J|1}YsY>lw5dRx-y?v7mDA?A{%Uxi6xa+uQ z%97A@Bv4=b;pXGydLxL-I`;*qWwCk5a%$nt;)vAm%e;Yw^KtU)M?!n)el;U%Dly{b zjjl7Sxw6}X5SAWH5Z6-B*o4DJJ4u*?!7hpQtoqWIw`eF9>4p=Iwcr{TmdX>cktL26 z!mN+FkrzuV^E(l*F|F1>XkNtLNef?k8pAXzNQYJ@(1v9`>b`2WS*@xrcgZkVc-$gz zA0@Q!slp#ho+!c;US(lN6XV4WtJkRSzdZ|1zo4dMX3<<67L_uobwR~Bt3C-$ty|Y< zo&WZlh0j^4P@HoJ$qwLbFz|)qJ1*ufHNtIdCL=AzFrYZ1#j^|eg>1mm`GGd0@?izF z+T*|t$XekVYZCR-Qemz9)UIdoHA({%z|#o6M#H9@Or~XB!AE7C*FWF{eFlR)&pR3~ ze+>=fKJxqUsQ>Ci-qNBKSGh(bBTQRg(eZaP{n8i|cZdJ}8Y8cK;;N+o_la_YMiK0GZwf^9Rjzc^s1V%PjE{U(9oxfyj>m7l zylfB`-fCKN7k+0dvB;ffY&$$pZ8L2$n#C=3V>;-v6(y|Lxv?&pK{iwG3-Vykb+cA3U>v=loQo00x8 z?I*gMwOW9lzW8Vu;FK<7=F>m2)($-L08P2 z%S%KNFq^fOmzTfCg-FE15U~WGd3t(&@$&k);hT_YB>xs0;c0Zz2qm@h%6O6VPe-E+O-_#Nx+zka|CmxY_zBi-U&S}!MY`X1%Mqo`o5StTE z;pl$+wZ!#1XpYrCvOTE~yns{Fmf)FKZy%Gka6L3Dzf?4$VV+nWg{Z=tua7Hdf-QOCj0Q? zC$o2yHv_b-37B*!h$e#50{@}tGD#C>ur8pX+Rv{9UI^YY`_ks8})2a!7rx0a?f?r}^f5_s->-3wJnBs&}-3Kk*Uqx<%jiyn4VG8zDM zm?F<$b`FA-OdVX+G}Q|u3H+4b(utsg+Pi}$0!Ewy#$V7YDpYxmqI1T7EAHTL2OU3h zF{=2XGO{ZC0KiwFeDjCu%87-v2%p_TSv9Rz>-~}$7XGM;9~{+8C{=Eey32E5@-jao zMH|-J#ny80T)|_Uc0mt`L!b>=J;IX{YosKo`jZ#Q#?F56nk7`y1E!xL^yQxPu5sk! zldyf`NA^z=cKP)q<|5)YXI;1}Z4vsnOW%+#6638i;_GW&ZUCtP79e1$%rY$xD>WhC z?B27TJQ<|nP-s$2bOPbo7)UD41e&a4Jvvx6EV;wpN2&i zztiq3&qRsb&dXg-$f)%?(4a0{Jw)Zy7Mgw8)=hZ_fW2+e-rbbHWAthFp{C-5 zW2)@*u?6o`uCO^>!VjY$&pLz{v74w&Vd<Q2 zP>^}MOv{^C=$GGU%|BeRFQ06)9bKAh*WZ|k%vDpo@VEDO{{%Qnq58C(h-qQ4J3aQ{ z{177aBa8v&Au&(TB%>gY^vG|LMD*HIfX|wnYv8KGL3jiL?>8GR^hvR*&p%cDzVIIt z{eXKKo8va>#>LguJS{E`>j#%@Xs&oz9^m$b17YJ&0t`;)Yz1$s41JL=n;JtqaooiK zpx2sowLZFfkY~Oc$Yq#unp_^rW!2hHHrRsHV;K*mhBd@6sn;Md7*$Hn6;e+# zg?B$4RHv>^cKhMbEO*3Q%r+k#*Np zvlDQ?4#O~N9WDZ6Tp~Xy27$ch z{ilzE@3PsPz0BubqU@tJPUxnj{qOsOEKWfC?EHsYmetCc@i`X2+kmKczW9W%4I{#1 zo1mm*{h!ID?H59_pcY#txp<{d^x{j-g_lcQiTjnATFxf=177n-p5hv^AskLd#R`I@ zqi8p=AUO}s%r2NilawZxAaG!i*E&~*=0|baaWI?HohZBlM}09*QLA?EW00t!w=z9w zIJN`?hDL~Ll1&1`=qi!~XfI%0LykinD&Jj61hiNO+UR##IO?U9tK<3QQ>e@G8!{KL z?VpiA@+a<$QD-8VE(iO)PPcyh1)e!6!@4`IAI7`$c%-QM=g~B^(%gZDc8W=9Fy?f6 zpa>*1w-Ugp`1pk=0;G+MS&w{Nku>3qP-ilGs6~rWpOUVqUt*nxbuEIcPYeX;GKfef z`!#zJWmlvHPsEJ4W}5TqVorjJy6?LGo)VzS3oWBGJ0S$)6B3R{9?K~yrB)9<ucZ z^@w7!MY4jK=U+Q9J%5CG-amt(Klt)c)=<=tUh*_JV(yTwhBZ8d8z?bIoY$^^Mt<_Y z_(4b3OPtWLs%3V3t7ce{d}ETJI=``9p>H;B6h`)~tD8bVO=WKd&EQFg??7|^u%Obw zY`(!o>d69;KUdc4HD<>pa+88l7~&~7L5X>|F&3D=d>k~2x`jqUX%fbYhJ;Ng>Z zif+G~ zIoaS0WsvTO-^nq!+(D}_GhbNa>o0~O76!G!UVKHa%)Cyo-P)PKzM}W_OKSAda!WUI ztJ$qG5mSg&hE9&Nn1)^EyZ{*mW1|jc0`CvO0DqL05A&ruJG)uw1!s7_RFmfSx|~ic z-_uKZC$;oMH=vW__*sqT{yGQ*@}M39-2AS>!(u`P#HPF>Qg zRiHHkAC~J$3XNvx_b+8Zzr*1^7gM8)`qS(92C3u8ssxuc7SD)FMyX#tj7B8xcMdK5 zXv262t1K)fH)B+^Dj!r>A z*P-}~ayW0mG(TH{%qgOtPn=MmH6Z=MJg#8375PEGe!kWB4L_zYnf7H8<$cZ#)MQ^7 zYDnE?gRCtG=BkM0>@Mw-=wNphy{2=&#}vPPcK%Hxu5W#OaAz}kXVj^7bkSAe{vFPLP0!s#nfeDG-Tgu#?sHgv3OudDz1d>({Wb z5%+UOxKH*SPcr@+f_seuQT>l^E8mL`%7nqQb*xZmy;gNG~M z^{TzNVZGmbfpU{B&f|ybjdc}dKCW^M>HUCux5o!y!+duZG=IfyWuX(w3BcOC=rh6O zw6xb?6yN-%Hmp8pN7_I-r2EVZ*U?BFq_kRw>%%yZWV_fDb(Ks9I_TKIb#gE50>c)u zo}jj<$?&NTea~`u{7l7-M8)euf=gCKMiJq? zp1b&wp{@>c<}WGRUD9ir2f0jx1Y%#!`+3Bt{4zlcsr_f!kY$amB&TCM)jAvUxHd-N zjIV+TIDSd2`k!7qdE_^V$2RimFS!S&m#0W}vDmb9UB6>y(IA!~Y(Uj?s7N#`fEIx# zOZK;(rDjn9{Hrd!$|ruKg1&_RL_PtR8x46FOtu;9PKXYCZgo*oL*}6D-cHyV z7?w4c#Twx)`h$LA^9Yn%mNJ`Y5~TPdF*eFY3fMJ{5wU)XH5^ZC=DS~0GIh(+8ZTXE z-}>k2F5ILCn%mBsLYI>7tn9{G@0g-`x3q+%zq*+6xu=IpY9K!P9?xW#hx!yqQAp=q zphs1D(uWGcaI%h-?HRk>cUQDCyR;ICqqZ5gzHK1EfC~K;6DS*l<6^O*KX^MbQKUSs zq{Qryny7Hf;|h8~taw;0j6mzGiI0aGW4;TKY1FKWIVE0cFS$^9ZK`IKl6Y%MI;suJb2iyN>`?@|ZaxiCq&K z=A}G+Pn3qt59eF%88hgV*-E0}tWG!0T)e)bO&IT&3$K(~CCDgxp!oALrI0DBhWDS! zE+i0yO#JyHN!iIAVva9o;n zE$ry{{9+?2rE)ZZxN_Vrso#s?_J>x0i(&G3JLdYU`I5(U@P(h-DQDXj@6&0tY`5&2pe5OQgS`}47`+<5>RR8Z!U$8*f42`cP5T={HWPBWh*<;s3(D$ zxT7PN*sVfAxXcHMQbKqy>DZZuRtN%DKhE}!Ff0V5oxUG5HVuHip+$HS=*6L?0#o+Lfw5zg?P>xu?ZqpWg~Ff9 z)^1U4XvDb8CM$Z(ax$eO4yPmUx4@&{pT(i{6CLexulwLUgjS$?Pdz#Da#+I;7GKyL zF&=nEFt68I{fMH}FVmRxe^J(d&JI%C-)_cZ?1^N2K@v~`Csvp8l`a{!O@BuqY?ysh zeC$p3Yh2#~jEq4KN?>whR!!Nw!h$H5Am6OkL_@g^Q4iPAdqBS!TDX3+3*^v%c`=!x z1aAyif=O|l^bw0a;5ZJ})yaww%}sB5!H}<3Tp7*04_3P^5MA?)<3*DLUH7Sn1!O~b zqWWqqF1$iUNH@B{Q){!^T4+>%DfgRdwVE_a2K2WyDO_Uiu*5}Jhx$l|+qQb{Xe%-! zhRKP()}^xz1ljYHAe9kSOygWx4(D#qDNIHDG;!Ql1@nngTW*YutT%G({Y{GA;;AxD zJ%gAsSWzv|S9^qFE*NRQ>00d_oAnM-b3aC}@3Z%{>@m#!PP}zuoPfVuYwne#+&+ec z-#L2X;e}OPuX={}J>ZzH=<%(q){rQ?d*%zp$MxHV8)q{AZm_`Da7*Aol~B=s)mpHj zuwo6v95tO@`5RYKoO-Rz$=|(E^R-$69~k%x^@mPzYDcf6hU1|EP8^7AhWUWbfNh}h zyrVZ4dTS|oxz@DDBV$~3kgFwq>Bbktbw)3FF~04NnxqkY7g9eIH=;!iJvU3z{?W%l zsY~owdG^|-v+G(Cpc)uYprxj5{91Ku)|El_Qwa=X1LWHV27G|pSyq^w8D?b4y>i*TlZNn6 zAY-QorS_QHWk7I~hHR!f9SnfgGy_V6Hf@XzGPGmn*K}gEgD)UPx5aG!ZS39tOnZ-( ze3->)kKG&x2`!dfdllh{JvTg`wo+leTM7}A>7)&BnP0x?y2IGyxvO^;RD*zfu%r40 zv!zjZHoneb1wUb6mX|k&Q4pA#263NhlAoOxRsEBP&V>|HB!A>>d^>KlSvaq?4`Ht; zl!-};x|{Xy{!V}Qqwy#vY>7LB?`3?4E89hAVJJlXiPU z(AntSzt*ehIAJ+`ZLGu}9etBqP=c4jO%T4G{i0bjwnlvkXW6`P_Y;}ieb#pa1}o?0 z_V;pv8I<#5?@4ki3P?5inl?&(`y~3>;34P(*dV`F;eLg zJK=0*6Zg7D{$PW&$b-T|rsyE|vHWB#!T+Q~F!iDi{bHp8{9Z*@pJkotaG8I3!>39t zOU|IBtqqRC7hi7k*jqih_F?)x`f7a5aW^n!4E#CwvASYPmS$%9z5x|As5lc@`A1k1 zB3encF=N*>_0lCKC1is#X?26|?H_JSSzTQ@fdA#H?tdfs(hnY7gJA3ALvP}~b}xRq z-+t`pA6;^)So)U#cV`>!@UC#Tkk`nC{9f`tTs|Ub{8QLv=p{V^=UbiZASpQftHD*m z*@GmKV4dlTD-S&!1e;T8Agp$1i;t zBxu^{ahF+`({tF0waM%0hXNj5C0$+zE?Ax}5%HCNqOg0Pv>Kya(a}7k%mR70=6NEY zwPI=N_%8TipdWFH2d9GdftL0~_$7Pu2XRw?ZL6WGe$gB=lUD4aOl+W)+DtXNo}L~a z0fCL)eAN`^gnQ@NeC!*t#?|MmD9C+%QaWR?1EFJKDmf=DFYG5FJ#RlWDmxU7$~@LV z3pD+}CwHTN=uYZroVV-b-&?auenezf4Y7&XZ@aiqvsv!Q+s$%2`s1?uL)q?Z_2|QU zFL;dlf8j21{~b;_#eAsCd27Td=iglO+3lD>omtLbq0HiBf=@5tvK1ai{P0?|gSwA_ zSeI&Tmxv_2Y_{AJjE&6333aX|g=$%7(fh%&lFPzt^uwy#4gF>awwZ-K&jXBju)e32 ze?te2fXvT;-(}w3tYTbewyw(yi)@5ONxOv-jGrFFj91Rg+HOuYhF~0{M8+p5`v?9H zgKI`KW1iZ1NVS7I>)&tvdy_uHb`0O1!}sOH8$ddi=jOY+!=Q=8<)Eh-a^8l60M~@& zc(P7u7B5*97rmq??K4h)pOAY0%EaX~X`XyGaD$Jd*pt`sTAfjqQS5LID*>g=C2;|% zh!#$_zwppo&Xv^Uq`uxI{TD}3$2TT85={_vP?_*Mqd5Tpl^jb@t$aN3d41GwlXibs zMS)N2L<>vZF*?;7U~Sfy>;=|v=-|yj8*h{IIyh%)hVZ1d##S$)$qR9@QT(*aem3B7 z%Z+rk33p0Mpla+RTTVKU-B>`~%9rDZ?PrIMPl%kie*`$qNB^M6_x%2m{(^&I2(GhQ zVMR12gcot9>%Z-Wy@=)r7k6 zJ%rAseYsXa;n9`#=C2Uc&9gS;{I0_jD1BK}!^j(a#cy%ud374Pmg&3snV|_oCT=BA z2<;k%7qn$^eUAC(f**C#9$FY|7XIcN{^0?_%K&>_#maEFZj~P;>J1nvyJ*d7UJ#p3 zO(}P`o1x~`A*@KOGl8rVD>>U>}MrXv_A>Sw0xsOcRI>mDcP1_XK$~f ztzBYoAaDt2hpaSg_$>!G9PHR)x!Ny}{vuEif^Pm^A=7TfVPpI#`txKV~j)feTK z$NQx4gwVr|VUF98RIeI)1<=exDq-fY!;<)IWb<&h1o@~Ogds^!&w*CqXombI^HoK3 zJpz(A%j-B;NO;Th%ABX&y$cJtu4i6UWE8QwufW-VFQ9)PP6>%wF8g_0f;QUj5SN?; zVt56v#cA_-UHoPIdS29syc@kDL4F6m#G{qIKZ7Tl-(>N4zdO;TV7CA4!t_glpu&_5HlP`D4k27=thB z>+5R)w+;n`g}F2$ZwQlaNOZJwRH)%UJ+Z^pB~R4Hrz3;+Ej*F7;WyR9o3fCap3W3! zY;OMUC<5a;k5yf#)AGdsY4?P%$+0Ui4FY~XnePc`(TRG6_$$t#XZ(Os=N7C#)jR)Y zES+C`e&I#aoD0FT$d^$`@6d@EB4olRy01rOjfnrU{R9S!6QB^AtH|GGCj5_8yJp?J zC-|Lj->&i*LCL(C$Qv%=tyUhd4h`2YA!AFgFJ~lSC+r-{tg!B;g43fgE2dXP5pwXFV zQ8L?XcE0&4X)2)2*E0Of-#I!cN$p^{nH2;l2kGiELR8@N0K^Blf-VLR4^J!05>C&9 zi5{smcF%F1Jpce8o?&U)-rAb1G7zAlq3Q1FLEz@*uIq&JZ2SBBhi_M_4ux7^A-{78 zo1k9Q&u0X&ef)VEoRkqE=!vl=`)e(4QhZ^${}LURXK#VsbpN+F_rIKL+v1UE_4L{EF;ozeQ0tBIUc(d97%Iz<~XvhDXh8GK;37s=pd8JV+-r>A(a}4r5p<(?5Q_NzGImI45hz&a6JMrFU_?Y~cFy z+jCm(9-t@c>&JSbIiB;eXKw1*IqI6~#uP6AqOlV?| z)RbE?*CZCV6F#<}T?*Dq&CaH{^6u0pNeo>&EvE{C7`+U%U$MdPwy4$AHj;3Hxqaoe zO8@A9v=^NbQMt62DUEcC6%2DHcC;ZP>4Wq@&W0yXthUW^eP{?alNZ^Sx)|+Nu^+CS z9+~?ISzK8B8ODo;K2IkW-r0MWR+yAIPau5psrXf;XR00fT%2GlDVx~HzlJca?#17Y zMWt{1@Gvqu8pHl*iOc(Zb`o8W#~}L|*Kz>)!StE}e1YU8lWqpvIR!$W|BF1V-iLb9 z{BZkSfibt-46To^z>AP4(EXze}mQ3^Ucl8@R%4$ z8^&xJ<@5*46CNz^E=1GE?z+NzzCwr1+wlPS1o5ZAA*excKv8LnU$ z1(jB$l$(G4#4=aoutcPTVw%8wM6fkF1zi9Fi{2r`EH?zF>u_K?2!zO=_pO&9K494d z(-L0so)76(taji6Zpl8XyATUL3U029l3COy$g~dZi^4hFxg{ksEU#q6!M7ULizw7> zfZk6OA?8O|Rw47^=vVgudcg#^;!hKmAyelilIi4kQC_3l^CCUP;l3{ps+J$>pO0q? zg&W9vSZ&(GY$ZYOOr@_yb_}wzqGdC|fq7<+=l6n-x2s0y%i|K-9#&W)VS{IOi$v0M zS)x@XcFV-LM(tQ@pO(|Y<~D$wDI1V#&n=l&CjKVR;PFyq!I5TTPqS9Lzw>Gj6iwl9 zEO?Y!V`Uc?)WG{)M?1Hp0%>5;M$}hRlOUFqk1F^%gh@saop zL>(3JzM|*gq-JJ*6=UF|Y-l5zma9x&+`xvC;-UBnVom>3AWXATH@Bh! zqp+~hg%-d7G- zJhtYY9jLz(mTNfML|5mZtvaVcga-dkh8=|DvsVOVe^tt!tNFPcrWV!JW6uZ9h2o6@ zgzz+RT+e5QaC9kWcWM{cO>2w<{m8EQyQV=7l49TXH)Ghe3LGh+-+$BBfg+`4~l{&w?!ID4zGIM;4#Gk9=LhuryAK76wFjo0RJ zeD0B(HAv}o{}Dw;Ti z1ds+yHyIAdh#f}f-QEP0GPimdu&Eh()GL>ewBg+`@kL2AxpmKI&nu|<_2@iz7oU_B zD?f+NhZrtNZ32NEoRQszWBrE1H<<=2D6tYh`&gUU$TgHrbEX;FeKEs&(4Edr?s~luQGx zcz6Xs-A$=A>8ap?)kMo@8Mi!^MrSv}E$ZB?#Ww8Krv$WieA|si42UM{O?}s<6g62- zwnvDMN!IDoEP8H~%A2~@E0QEqXnNAj06CINvB4BnH^}@D{(Y;S4^DX~Pwv(h0WV~T zvGkuq-@V@st!y`**KW%2SE*Y2V*>!6BVv3=%5IT>vIf+nuP0d6U_gPg#kBAS3&zXa zdmJDPO7z-wW#4^SX=zN;*Ecf@{hj{N2xxvC$o=Q2SE_AS+deW5`+A!l6heh> zKNHCN&C5HfOV_Xhy|fmDY2334@Bg?G&wLVkl6Y2JMXwX-ZYv}F{5Dile$LGt~%6yB`F zB2^Q^mawm^R%uiUwJ=Wu3}t@hO?kw6@^#&xQFIY|)b`Ev&x!u2*D{GWARPo;7zkFS zLA1Gk`^I2B%i{?d@B=tUI<7n5Fs9n-C%^gPtzy-3wufb*-@Z1rt>E<#PB6zb=du^0 zkUs5v<~eaWo7v}=6#;}kCI%uvBgpkjjKW(`{scAvsTz2*GRTLxBi8H7j^ryo6Iyf) z1Z2ri`zVph3+%*i=%{^B@IET;o1<#q>yIDWFmoisHS%yX0>$q>)8EnR z+?C$3dM$JTdVd*#a2YE9$0S|rv$Yb)8ubaAnH$2ep_9e_&j+pWhV-BQk5TJ9bj{UAVT-3yQy>~Cl z-cuhyCS#@7(%0WVObrdT29+?@iKYKag2}p)gmevU08}! zDvO3VKgL3AR%7-}Sw)L+CP6HQ92YIqnWco$6pgj}hRMT0D#L&sT5k|1e}A(P%v6)w zP&51YMHtHcvxaHMb!y*dp1!Di1YHQf23;eu)7N-9g09pxact}7vae-g=&ARRG#~VioEA&;ekKE zoU*oc>X((vvHye6e;^#^bnx7mZS#Vci$CgW*FaAnrzQ*s*~qZOyo> zf8Ey1Fp{Vn^%J(r^2Z!sxmwBKB~j6b59mw;izJ*_QZWNi68fVEQ#^@o6hE4=P-sEw z_e?At-DeBWy+xatbNLGmb3C-plL<}F8IkLf%Y%BN1NnIBwMTlC`g#T?$XawTn4G`j zXMJzCM(w!N5+J#o-WE8WE>n(p_{POvjba8@+T&#|-ag@q3#xsdYm<06(>THqXXUc8 z^V&vdmtJpnuX8K<73_!-3lT1)Z0l0L3k7wXmg~Si{Xf*j_FR;D#giR(^CHq`@5l3t z<%+&6AlsH89Kzhe_o7*bd)k%zZy?xl0CJv z3(2gL{KrMdDW9d@0;PGU)WFn$R*x_xh3>!tzP(JRd1&OW)#K{x!Q=f^e0ksYKpX`g zhZP<)H1t@VwU&n56lf8PS~kJ@gY_)TjLee0fwh`FN@ri6IQ(YBb#MGDDw*%Fj*gCi z6Vl*Kz0I;F{8{}MfEQ_QZXWj7K!pDM`SbZ_D4+#?5!7h+1O+4~7s-X@)2W=KK&qpy zyMJ%)56B2aw_mSn#HeJ^<(c@5M)#B9<0!)Dyw?0Ozg}NJIh%qeL=r8i%bH_(pahd6 zt2`iBwci64-d^Hh>Tb_`*HnnK-0HfvE z^^+M5)RJz4Xz=WY$n?Bv!S+1CAT#?$7lCaFo3=p+SCd`Hx;jBw+mr(h4F*ej4ZsKRv2RavVbbQ6*i8qfY)_JDQY71!3 z?j%3?*|mUzKXmyz^CM#UV;20x!OgGkB(Afl?8s~u2QAIWLJDf5ov)~1Rx~$L*d*IX zf1)!2geAWzolJwSo)mS)b}b~k+lcPk=m?^CM9F2HFv(xg@19nrOD3q4YFH8H)NtPZ z37utjKZbXIM8=#oxPv;fRg7oxdMnx(lfZ`jyd_4z@@_!|d{Dh5R%@+A>h$66@itNy zb;uR%Fh>4J0TnK6U7gSMJypAwGpte^6M@xXVC)ld?Zr67^-Zsv^@imTSO;eNNtGIT zstqMmWfP~B@i%S)`Q;?3Wgz}Z15o*uusDTH) zglO=|>{?c`-#?A&oe-KeQXr`CB4T~sao+89D33YI8ykii0(^X}J+cp#Y(UEO+oC9z3(r3D!|Cv%ap>e~B?^UtByBUD^__y2rHVn=*?4LmcRFgN z110pFvt_mQPoWe|Xe1QXwz`O$SZH76mXhg26896%W|uiONx?3^N)-|?gK0{Gz-2J$ z=pF)dgc)z#!P@O;-yrvPjrDYznnfBAIkn-_a*3WIoH_jXFyXi^J^7~s8eZH$@G0I_ z*in_DhO{!%62jV%f`0`LK4jGkBxQ+o_zjw6>n^6k_>KVRv)T+(R(>UuJZNIC-J(r) zn45TR{?UBisRY`{YJR;Cc1xyfqsM!L)7fja{F-_j^X<%FgzB{Ztcprv;%Xn?h~;)zr;+Y5#7aM!ZRhnbFNP9)fATFi`R&tf0zz z9xwM|kbob`nJtKX{Ja?>@SgQJLXCx`BRLot?48V2!qBOf#P;)f-By$^Q9&OrHDb}y z(vD2{rcZh9_~h_RvbG;!QA`~Xz}_`?Vp0x(%e5tNFPSqkFYuFmZukIyH?5>6bUp8L z-g`^uF(0HI+HJj7qL8x9=fF{u<}_ed_T@+j#MC zjnZnUi4u(8Hd^tnJQ>^f-l-fc?mZ8jyGmFt;sl(IP!D+~*dOL5eyWX{&w17lupjwQ zyNnY zn)W6u$y_Hoyvs}&Bxsy>h?w4H`s0KYpp66AV#~oMJ-M8=wD8dWU!4=Bp>fHUh%tT` zD4srKs*LIWP_xV@oshFTH`k$8uuY3AV;4?k54V1F#_l-YQC%D6=td)Hd2=4jAP*_@ zTUWvmb7VEcc|w>X8DpBc4}?bIZ6TvRQG!;ch-ob!4LjniE3Bryq^*ionh4~6mvi7} z|EY4=L3KNqy}k>lZch{NL@DO~9;TM@h`25>&HUKhlD2KRqj4p$flUzE`Q*-Zx2rhf zvB5`wOAfy)mQq@N?yjPHW&UT9@Si(`W5H&_Ct(eD?&}`0w+fj-zyNovDK^y(8(1L@ zM6bYvz9Ejy#EgpUCbVaCApD&vC3>8a%c`%JkQuQ+Hr&&88Q4C2qtxxF!+L`?9sK>S z6@zwsQ1i12kJGi2if(nBG3FvE^R>Y3Mii)_*qEv9X?7Bi-Qt6|j7G=+rqmw2m~~Wr z?swuzTUaW$qu%^@@y#$?vrS77%Fz;Oxfe4G*0H_l&`IV-9(4kTxJ-}b`u@;w;I=6K zzI>jhkj&e-Bl+nyrb0wg62|AJC|-#W+U;QQ!y_S>Z6cU2W>g?0fM4corOnf@oABjD z*lZ=`FU+K9Nr|ZWOQz{jzfQN!TzowHdYlclU#bhq;BRdz_dBzsqb>IpC>bTwd<^SF zL_bfpA1E_CF#IElw#B${jpV;F8e{T5oM2zxFn0VN?YZTTy5Y?4W^hBvNLlz?JdJQZ zk>GCFA@EV;`9ONU-q#i!S~^ibsKhAixwpxX(HiT&Wg&;Y_imBqGoK2}UDiahcZrVH zW^!0QZ*q;oK7TTQ<%IWJsvx`*n9)~qCTWqg%DIt^G{fUjof4Bx0KAd{M~GPy{)Xca$%cbPZLX4dg}x_eP;7|OgT3W6-Gf_C|a15 z;~S;kp<~CvT7jz^aRa=Yb1An*L;U=Nshm-+cn`yra0!dFe)-y8-MxGh+! z6Px)dg@(BqnO^x>+`dTNK~v=~R}iBYhV@-lC*5!wALn(7VfTHp#sX>>A+zm5a<~r) zK@CBrMIs@SBVE#{J8FDCZ=}%Xj=o3^lpSJkt`d(0PFVtHi1SS-(HVsli|6@i#O|Fz zPpyD`mgaWt#n!cpb$%cZVN{$Oe}Vm{7nC$kx`_VMz*HrlcB z!xPRwjxm%pD-9?N=mwBYs-Lp*eI~b->K>v@)cGhW9~6tn{D{Maa#}jvxvn=AA1Xyc z_KU4P<~Ao2h0wnvQH?;$P^I=vOq&m;yodqDj5~IB5@y@s?;#UPc8U!D+^aWj{{L|k z8nSx$e>4*U9y#MRI&uxp1g~zI5jtCkF*H^H-=Ih$ZcLF-G%>*Mki}w(=EdpsKU{^j zo)Adf1dp+v^*q$olL6-T{`x3lFrIqYL4j&zbDiwz*{ex)WJ!)QEa^_i{piD;A;j3le98tg|;kMNRbKa&+* zuZI(MFg+}i($~1CSJH0IC_MB1o3qc--H>96So+*mWYE@oa?Qy&`rJr#a-9$5j-p~E zWyc1QNBiN2^d_NE4940kJd8N~<+pjGI&y+9 z=tQ?T2|QCKY<}cG5k%ayKtmSZ#*G%-QoN4RFF{8rJv zEQy-KEN#*B$Z?jN_jAY?T?>Y)T|Egd%-?b@#KNCjhLbV$=|v#*Dqw{8#WHU2zK;hC zcfY^2X;qcenCX4x6IcX0WNF=$f6_d+bI%37Be%$MpWX}`WK*HBu5qOkU*eBPb_(_; zo_LP{>hl;n8@H$+SR=)Uv$t%3D5J`t2PVtOCt$+emG}`v zl<3jtW2I5ls-{uiP$pF@-I5j3)8_0ONkRlm-Hm_vV2(rn=c}|HfD1rvNbSIqM_a6x ze={&SfX;08*o>=0rzi+J&xPE|66sqB=!96ezWdV83ZU=O(`# z8vSE4Sy5o&*B+C8&XCW%MZtdGfWlvQh1OfKE6^2BTt>$CsA6YR!q1)cj_pmqQqLq) z+S+q{Sn}1~tJ`5d&aq8WgZbTR<}+LWQx3H5JN3f|>G=8CBSO80sOzEIjFQV3^MWZ<3S9WEdKl9q?`3S{N;6q491YYQxX<5rW@S$)$R2$+h$P%oI1SIKGv&3*xB0z z#D7$_94(EMb>4F&+3c1Y(KcNgCZ(C)XKK{{;~660gS8udB5E(oBN=f)7fqIsm^gS3 zxO9VKVk9&*zkBJKn*QYdId^h&#BhU;0ty&} z7+9M_hi{y^HoJL*)bPSG1?Jx0sJuQ40v8s(##Sp3S`G$lLr`<3$v<-*vRt0kiQY$- zpQZ1k!Di>B4%C!+eID#XRv@p!S)5Zf-aEMzC55FawO(QfC}A)tR2t?ZJ;^sc0#?yq zv%AMChwe0}jD`bD5~HnA!kIqDgtDx9T0e@mgZ8p7t55d`TH2?#tY8AhwBL1)NJ+G4 zD(3R*enaNRZ7PD=bDwAZwB)#@@1(dOyV8_3F}DX_8|!}?+=y=>wT9e1I_bEEApHMN)K*p2v?9TrJ#_8;f1@met8W8TA4sfPLY_ zjlt6>Yno223GGZTSmISOGyGzCW{e6IIwknty^Y|@%5S_#60k(q6o_ z{?`uTSlATX%G;X^r4AIZb=N^M2CUJkL*F+n3s)>Ysj#hU)EX4PG( zj?ZPgcxO(pO}n5OayN=50zQ!e%W~8Q#M{0O;e*7@;F@SOVz52!pweyMM2mbZqR%(?VJu)<2*ie{F{&+bHH%Cf?-Fp4Ro}#xMXF8>$@e0af;n}JKeS@;oQC9 z+7#zmSk-g99BKcf?i)WcsCMr&>YjcDo(t->Cq5|33O@;8m9Eq1l3AV-JS(vZcUCzZ zr5k#n zwV{-;IAN$CYsi23$ucA~oq^R=X*IP#S@2D%usPHRGQvfz{cGbGYCj|%A~QFu6LYyc zk8CO_uw#~UfyyLHQY^qzFCU$5_gcV0j;H`*jViEeGCoqGpfxkFxi+cuB;O^h+F3N> znhcNE{SCh_ABv6G;N0yI=eL1{G8tu>!8Rv5Upq5E>_shai0bLeTs+-Po6#~?ATsa};Msz13d7CK7ln1en_HP4kz84V{PxQcULZo8j zOT;Z_eagRBPcfT!esZl(#!v{@Bi75E(6LEd12uvo-m?=ztFgHB4N`vNk#ldSo4ppD zRw#}7UdVqWeN|9cV8uS#rXbUKEv_}14C{{oCp;2YP$)yoip=^+Dwx|LS7g0_xac}3nr_R@wK8ip)m?km zBCZTXZgELDVwr%G;=00V+M!nEtjokSkwipXVUM;nLH*(yA=rM5pj(YFrc55QBitdB z-~nlH58z?BxhTUj-F6XXao)|eKK6~4&IAs;kSn`g5|34Uw(zkSWcezsNg()cG79QR zi)B|}*q%!UHq8>nJR5e(fj)g`y_Ib5 zz0%_}gZ{}_c#j|qqhbdwrK=gVnloYFwsHTB{37!F<8>Eh>7>G(!tvZsq>T|kam zi@ANX9^ga-afVt+_7=V?ZKMjVT!Xy6>w)R)j{i6Ppp)kU&IRu8?Mx9>pEsCSpK0ir z`ZF3L2Fvz;PwYjdv@$)^G3qV;_`bEXV{YmCY7y$oQxA+?-Ao;m5bU*tZ|mU@3?z8` zxf31Tjof2f;Iw>NQv)Y(^_G+b`F&@0FxFWcI2pgV#Y`T#r<^ouwoT=rfS1Mm7-4S{ z6r(563bZb9H}6JLvEZ9UB2I(6sugH-H9o)rpQudP@40*+K{l&5NoeSRe8WmQwOo8Q zq^$*S6gGd@MK0p1F8^$KYW}vi`{LG16JtXl6?{ihecH>cM)a^|KEjvPQn>5nb>&38 z)&b3XCbTWcewBt);hLf7TCXT?Dd69~0wD?Xu0_o*fDLvZ{K)na)<@FN|ub(i>^(J7>zx%m18A3 z?$#!N^-Yy@u2M84(Lwu6Gz5Qm?QV9$C@7&jx*J)ZbM4&yy1peqd4A(~McVl8JWJy5;#W=HO!P=fE4^XwASoZcM1_5-6! zv!3Xg>sg|HYEM>apWs%p)?0jou2B$oHV6wid;_0P5>k~6ySKpxX{@h+J5r(??Q0?) z9FgzTYUb4r#1tC!D$zVHYEEbwp9(#G6-9^TT=T~(*xSd|iKC|ciz?AJhmJg>gn5dz zQUJYcim8^h2?n*JWP5Tep1tSf(&)(>4(s3IqzS-3k371BXJH%U(LS&Sl5xV|GHMID zT(jIa$14~qa1DcaiFYk<9Zy_BS+zPWi=qvP%n&)wY}4HHvnr@kK$_3|}79z;YG zX_o2zhS4=Rd&G_;sZREbu?>_Kx^GWuD#8t;NNk-gaaUKuqlrnCw}gbmi@3Tw1obr% zQWx;+0N3mw@hF19O%oH7P9WxBceHr^vd42`Vq$G`GZ08;0aSV#a=Zp_+1XWQ8kZaY z3;2;6EbE1PY%4}TRKsIyr=I4i{4~s~7dO9LfB~l>aL`FHHZS7- z>qSwrWmtF9qY15aF`>XsGLIGGjH9t26$|pTmvggdYTDo<5eanug!U}{E2r(F&VDOe z^h!E2H~lN{N_a4N#cI%#_BMqeC-kyrgw;Jh7+2^|*Y>>zcG!t{R3A;H^esY$+qH8` z`<8?MBNBs=kHMcpO&Ex?!6ZvfD;j0k$FohUQh5w4=o+JFrRcktxOlZZB&~S zXY06$iW3UE*7l29jPsRARu3;DZW4cVgFQ8ikNRd^U@UKJby>-aFO^zv*op)cgqlqg zGffq`A6Fcic_Mr=q&VCOI!(UJuO5&y+^~}RP^26^I^q!Tz zKQV^^#&DPvJS$_+HqcOd#g4)Zb~#)g(_n~o3hc{`v6YEOgw=w5tVZCyKwICXOcdE> zSVR*u+eJClsfNZmTce~LQg}r@EBmMJNB0`;J%u1q*E^c#YoGUggDRRe_JL-8s`|oS zcRJx_e)$ffc~J@913jF{;!m$P)7R9oW1{qY0>5Yw#5kSBB1xz@70tBBa{sLJkdtb7 zzZ;iM;C_}C?8oBPlJ79C*nM_n;T%(%$h8iQ{ax2gp}aodVMX%!Yt3uR&E!T`mHNEz z{UdIq4Rs9<-eVdoqKW0^q)hn2dXGGw_2Q16EHP^}F7!vb_D&+4jinQ)9wacv`Hbw` zVy(VXigGHyZ_!_-QID#}kCQ58jXa=i3|fiWm06c|^n-WhM|o5>%HKkux4$+(g3K3j z2VZ$&Da>;Z8B7b_78x&h857~^BtUJ?d|A0Sta!>3edHwt?GG^=t(CojMHTU^H|#ko z_8|L{U!G_cCa9ggXNkAKUN5d7nef^4VIjtq)|rHwf|FGFqcACHLoOcN0#Qz}tMjg) zs3_{_i-hsqh8bHYFZg1E9uHb<+~FCF-<~Z8~-4yt1mw zTn?Kt1I`Bh(ZqnLLf}Ph`qGkf^wg;fxSeKMNm)f8!t@!13HttZ4lBW*;a;|lCNE97 zb&~@y_GFjR@MjZv3=Vh?^)O2^$E1z2R1U0Ky7+9Sp=&ECFwZFc%<9d?RyF2b0BzCy zXs+XD_yohf$w>TB=hx@*D>@>t*fIPW`q^GV-d>WD{+Lq!!~cQ!g#R$aEAD$64dK3p zHsInx7%VBr+sXiHH%j@O<-%KaA&SvDu+R=CC0%`evJ&BDlF3*gKn1(sgA~&Cz!<`{ zXL1es>Nuz=f1P)aX!Y>;c49r8L@D3s3pEP?k6Q>z-;eps_32QVj~Y6eZw&ns9Tjq~ z*`vSM$DBXa^LOJi1$7=Rk$K%@&YtOrr5iuskwjspzC}r8A@Tkmf#I;t=iR>+)mY8k z7^o@r%L^T^r#9ApH+t{G7bJc!Z)Qzw(T(QOH|Fthev`YR0(_u%{hEcGRy;ecL_w3G zJ)06paiHS#{$mENM3wI3Mw|ge*hJ|0St4O4nH&Gcdn^BNM3|peHEKrUk45u$a7VOA z_o7BUZ4TvW@(U#%<-A!-bcUFsfQDuJN3g8hPW;JPw=1cBK>eKR7mZt{Ium7x5;~8k zatgS@)E0I34v9ykb@ih9z0T4wxT|P$-%snC_z@HnS_>QZN zY^B7eUhra*CUWFzcphZJVA8^Fn_61ok+Y?L0z~Z z{7~j_YFKL|vF;{WIWfz4I+?e*H~KT>+>$$k{E$>-fn5dY92`Uj1f(^U?zw6s9EA5J z=rWk?uFB4d7=`##vVI~Wz6gvsB~zf_%oWsu_Ln5H8VXL6<)6yC@uQM)Lffmh)5QfZ z>v)T=sdVJ-C-T35ydP!Uy^%k36?z~JVm+B-SR&0J>XmZJ>W5qO)9F`o?`&W8XN`El zM{_6cEi9~}sPCDE#UDuZHq)!JZ!P|_PsOQyS!wsbr7@z&NPd#pK0FU#d`VV8T}G*kXokdZ^%oB>d)0>a$h(W9NAxNVwj0zTj$F6mAApP-l;z>WfniE{AdAe^T|0Fy8o08vXii_`R}s0%Tv4Ygdbjp z=UBZXy~jb`eS9By9Vjl>ACw_vS6v^J*9bVCKq0l+R#UG@;LM%XP4kb*#9{ z86DfyX6#nryBVot5GDG&8M3$aclE_X8QsIdyD4Y4pp==#X5f-a{ZUVc|(*0dxz=&AveXQ!tLQ-rr7(FRxfm#)| z5dFNF%NM%WLaRWtY)O)(-LMU%1pTGI&2Ej%4loyA8c^%Ggv~r|3^T&RAmww9O=)|tKS8RcR-Pp&+XYAn0!Tb|}Mf*R?G#FgK1N4{j zrd;Tb#eINzdO%(&1(17^=q&Z_@spI4h@D-!>{J~{ zri9*H=L57J(O*l5?iL0{P@?D=Vk>Qswc#&CcS49?BO@0(Jycb(&Z{;mu1Xg&-Jf2J z3Jkj}hhB@=TTl(5QdT%PhlpW)OfcOYbon0Rjv*FiW&#-^G+58NMkv!6)q$sj zw?xNn$Vt)H71wrRpJhoT6ZlO}_?5@M2?fHFadP4UiNJz|yEJceN z`IVjadg8jYI|vbLi#sC!uZTS$L$K;;+RoWoOg!Y1hYo=7=pnc|*|m@Tw}$~dkVyjn z+S{Ea1Cg;KX@9cflj&f26k1GcJzn54#o2Pu{H+RIE2D>OznYw@@YBvWmZRbDUBt1( zSbs=^5p*BGnzGBj&w`Km-(XYI#TIs_vbKsU*S@%NxQuFBJUh)$`?NQ6c4P0MSYGebNmtdk;Dte;FQ-7YG5B7=7a&(adacSA?S=8XiF8|A)*_PA$Ox*dW^yTASuu$~I~vKI+6PcGMeppV5nU{Shxdqh zG3MQiIrd8@ZqMJaRPKeG;G1a;PJ0mrRU~?X#oV_HXr^yeSsi`t>j*9x19oEm6FOq3UZ)0_qbxU& zMAcszeoO(!F#tmgv;Q9qExz_D5Jnj;=vB!8roYJ{1|=|7%|@ujb?RaCgTuoE8XLJ^ zZZQYpj~lmYlSzA8lRsrliY@&BHKpQ_~6uJE6w)mMWX*oDyRcVjk@4>+93=b74WjSI12Uj48Bj z8r7yR!4XXD4*|Xpo1|6Iud{Hknw<8@VfGQwNg`K$ATp-&xKOv`-ED5=fq{XMANQ9U z*}i`;59o^`?C$DLrq_ot;<+1(w@#M>5U8xtVpIdo;em=?& z?onfNbFNW;H0!M%QN8=c&P&kH32w@>*sJzWb@WukU?W&~_#q?k$fMcsv~lt5^`eut zCvn@BX-Jo?WxarJ8iF4I;~P=CTM22g?A|XTZj^br3EyEgP|N72TZeXtDf2d z!wUT0Gn&d@9d(S3qIT z0?^Fxoe>@0aYwpV5&G_+PfXB%#KydalNd}i6cxX|+%s68BJ@33@C9KPBk1qR@$`(x za8E!&_W`fhaO2?sGZd5MYO~RyEay0XJ>%^Y0C|*6<09Ks?eP@LYX72FQ|Y)XJKvW` zLP1T90Ngkn^hBtrxWM^1Q@HRqvrvB{qS%2DTlBw!LH~8hnv+^;-keb}#ty}p024K$ zKkzGd{!+&(bHwDK(}DP*Qp zYd8!l;B^h|_R&IZJpNVhkAOe~bijVO+2yDUc$C>aJ-E-KpXmYt#c4dwlJNTnz)a}) z=qRey^G0{vUbMs4!lGztR({&muHC)7;*D)@8ta$8LO!Ek^3-&c|GOrTVo@diPXV9c zqH3Fskem{1^$&FtLYhP)^d<7TssS5T?0Y(}a}g*Hccs0vf-99jJGQX*ikTDt`0oZ(oBcC-B zcyT<@*%PzgK-zE|i$sA@_TS)sis8=FV&JV&&|l64{}3DQnKrGYKuWEM6;u^})R@O& zA)vVL8t-_&bY17IG~gj?~E!w7Djd%agTJt#B-k zzA$h9Us3Z?i;esPmJzwd0;)H~2r^>cF{(16YY&$;f<2+#ERNNxZip7%TGmoD1s9&> zNoUFbF(2;IiYg@(&LoL$55Dc{mBdci@bW<6V9*F(b@?{*{vQWQ)CuANIXe3!HEGlt zpm#c>wHX_)^eQkLyRcB>%S4ZAS#uLd+<|Rtt?~>L6O)9G4+tuYVK)9_Fgt@j^J_V_)|zSL$f?50Fy_MSch|@eW|9nX+<&*<=Pe;9 z_&GHx(Lk;>Flb&M6?hIxPbVfKCI*p`qFY*8HZ(M>?PmHWU9Eau$Y}Ti5p52Sd*iuZ z=Bx4?WF5EbJbvGur^SE$n&2qg(|WTKAt&$%#QJEdGq-4RNGxR=1EJNb`0dIXKCRQP zJ5S=}tsoDBOzHEXUt?7vI? zIG4@Lqg!XRIY}gDrl@~(95C@9tlr3#{h|ETwpj0JgT8-50~b*Lh0Uqo$bA3M8HPo@ z1re=y+MmpS;qmbcn4mY66cvphcYdV~KLX)XL-uSY#Ds*Y;npld9l&5$76k(`GBUE& z2=?B1bah4))i9@(M4q~c3=50vZ&`V<$e6}oX0p0(Revc^4KHTz((DN%k4+u^Zd?@@ z2wl%zVIN@h&0~_X(X)IBJ+rnxa4^n;CpC3y2m=QB_zXTpb==E@#;MYr-=~V~j)NW% zLOPZuV_;Ux1w}IoN<>0K`!{r5J7RODR_$KpxYOO}qY%9N1APxeS3$lpgT`+LyiheVL^(uCCrt1ikBLaGe7reL&bE&I|DD&g} zb~SU>suR6NUS0EH6jX)vN6>{@(IVX{A);+*n?8Vn|MaearJMcoD4)bW{B13l)^O+BJMOIbQziSCewk;d) zW`_{Zg~5J>W5w++CxI=OlcY`0^r}=RWG+Si?`^`e2DM z3~66mO;jjI(iiq8OKH->m~aDJYu8lpxBSpAaBAIz6awl$YKkv=x0*D#?~Dd6%UPb! zh92vVIAJ18V?+wdu}UI$X_CwIP|q%3TjvOt4g-(SA+>>gh8E(4*~{FyOS3}FpB30C z5VK_j0q%_7r)WvN|5}nnMV(S#9wN!C+hmPTz$4`J;UZ@3tpAxxkJR(fM}twf_ZnA^ zm-@ii%K`eh2 zpTg{yfmkw0PaPJ(x~b)EClv@Q{dj+K5(A_mNL0Y^%> z%?^Yj$&juYgF9^n9>bD(J61ShVI*XGdg2~IhYBHV>&2%=Zr@cwb`_Jf&q-vEG(`=A zl^O;Q^i)4Y^qbgtXk|1z7I)TH3f={;4+TggrpsmfT66#m`g=go>yoD}F=-P1*Mab; zUCF)-y#}pS-5eO%=ta(D;fV;mM2eN`(=6)WvTQt?4?rxgC~t;Sn1)=$?Ap)chW>96 zNo1BTKCg(UEvQQVmxLt6Fa}}WBC;{BJNh7VcE+ZFy5aMzm?gj76WLz8@e`qL761u+ z7aq-d0!EPjtzZI2jZ23uTHej;US`C6F{^&X+l<=HTswhNO?*Wp4nGflPg9cd5x+ai z=vE2)GG`Sgvk#+`5hGx?FQn`9-TgSJcKG}Tk=UcXQl)anF2m3$$;M)hXlAr%<#G+q zvF`z8%k%yw-rNvLQjYZcL`foW;rhp`K36PaW_=)z%jwTn3@YKZ!ObxZkwC^`)+cucIT-`nxrLFV_4Pl{%MTZX@nykUf1=&-1diCOVt0!qdIGrT$lDMIAa74MM4#!-1;GxbiFI89 z?w|-x%J;4EU>5Cja@DXw>^lCvFILSb7)}lfx>&R8)A++6o0i*@%1@=&Vy?j)qsr88 zv@P5L-=n)fX-qU?d&5enPdT66e#8^@bdxz4J@o`c4O+ncv&1%)Qc{{2_DAP(InliF zeRS4lB-ht#p`tb$I`?@D=@=}8TUyr2HXHSstENWE$PgOZpg!Q{<|aGZm3i&r6zby% z8$N0}KxsB=aQEGlMiTxqLh$)v;LFPhPg^^U_bD8Qt^yd+Sgo|+1E8J*B0BoF@|=gQ z!FblORdwL)u13bKVQ&g%7r%ir_)=)Cqlvu4xkiGIp~zIC*?GUBVCQw~-Vo!i!B~ba zfCypK(YGcq0BA*RwB%G>2dceLR}*MPo^pf`RAwC*Hzzy z9tROPHz4IN!6Xyag8Fxp^wTwE`kwUo0%YLqqZeQQV&>=r!7YDsn*f zm#u0aXLDZlyIM`pzybWI1^ZqLeBE-t!OZS(g=y($)yJ#uweq8KS##TEMNxCDiOv$u zMcgY2{t}=(Y)L0yD>}njF9HS^Bf;u*Lp7@hEG098H8qy>D% zgx61O@>+PvoJ_ZUz$S(W&Y2Q^B`CKaMYIjPHw>K5MPW8E9$b0f{6R)=eESc?Q@KcW z&6W10WBISwI5FUxCSy9u`B#*1&r8FXErRgkLI=zpX9foca~hHeRI7#O;{W?&e27w&V;@3{AQ|LX%V ze1Nr{^*nc7*L~fd?*coA5ICaaGPy=Wfw)G$ss~YFb#30`l)dHXRNZnhFDC~|lW1Rf z%1c#MWRF(sF>igDYX|p8vnDAB8A2SMf_oK9sGT-lmVR{Ne32HNR)O>$4KTCynRyv} zA3-rg%x1pN+i(5Y!l7>!9~x?D^k+xm2knLjBa{gI2^2=T*)S@N!>;Xg@gEd$90(gE zY>l98pa}ir`}US@G?t}m-OE5~OEPuuQ=zGSAr^-F_YUmwK~xF5adFRT!*;~x6s<#F z-HSquSzNQDSav6Rn5;Cr9Xo?W-FZWo4%6}vv0r>Np%eG|YN&>*1+`0OAJTk@Oxxtq zxlL+;HLtIy3hFs2>?xUvEi0MKZmlY>99Rpm{LAMu!o9i)RROW4U^S|rsy-q&cO8L; zGkC*j`dWFeeY--1l3vuH#WtErI@X>-IlZsCwx&6ou7|rzBc0}Bngv! zgE*zZPi0&*c?hSsJh*9Ids(9>_OjMS#D9oDtN6q+B8eu*)s@~dMMBg$@z1`mjeDsD zEd&swEy||>SLeLf`_}T5J{)O?bfKC}5QsAP9M?Z()%Z2o&ttqt^~_}S`(&tE5%^2+ zL($MV2Wyxq6YyKlSk4Q}#72?;JYNTvlUNruhUUj%sVm%%$-XttgcJ@=Jgel4wTl%y z86H;q7GWrG&s%%CSB0!JUV`IwLY+BfG@|~I?;bB(#IyO~twrf;^yJ^2TYr>GLPJsF z`VI2N@3g7_iIU35RJa|L`8xK2-My9L&E{vx7)NE~Gobg2>giJ#x>3?L!5#gl#--O- zsBikTPmzXwPFa5?dHYS2LAqya(qhxJeoTJfEdctB%7uMNJ*_Z8L27FIPE-awOJ0~X zw3GX3Qi@OWlk-sV@VT)sO5i4EOHX-8h7C907U4OBy@$UeIkkHTZF^e38(9S%$~?so zj}4h&mC%oVa*;t0HokIr?^x0g^!&VrZd?7J-M!vGhtZe+>E(>k(OcBUNAo^h<<|Sa z9Ofnhs;Ck^B40CQ&Fg{9&{1T?gB(?+BEj^ z!=CMV@pnL^76{JsyoK>85~+E*_B$-kLDaexILcuIAWGt+VVM+Iov6FP4#7cqVtiOJ zzhHoyjI-(imX15rlk^mnnyaW@|0K=A*d2!ui-~3A#T1i4fys=ku1_k>TK{wRBVkXo zmx=i2mJu?GRMEo&e97t2ZC4VNj?aihLqfXpxjWYep;YboLcAL4EU~lMxW5eb*Pt%5c9W|gI&dYnN!awC~K(m1ro7}-5 zXTKHqEY?h#mO)6j0y2Z9CjfXe*7rruRz)mrARlD7)IEjOre?!jn@mB%D}z?)F}`up zn|HdeAyL-`t&(C%>XOrMbWl9Bvw8V2djUyCrW1?nx}>2i7dIDg;Z{qeMc-Qi>#^Ff z&@JtnyHN?5gd!6*UZW;wrt;r(%}5rIwFOy?A4=1dk&k+uw{@B@Sh~;~?@0(P6(D23 z5vZu5adM+~y(yT4s_nd0nom2j55+zsa^aB)6P%N*Av;%MOz&#OchW&|#Ztp!%QHka zZ>=H@0ro>-6U+4|Bs;dwtMlCo$7O8!JtB;}9?L}8Z|Q8i`Tw)GAob1S zf6q(^#)Dj8chpMt$@R2;Vby@xU3(B$WUW4=I6mu0tZXqm%{9^l2KY{0b+Iy|M7tB6 zCKvV+ouk9T*#b0+;m#bAp{E(ujDs z?~~Uss@ils3ODiI<3r>1t3*xMH6Co96pt*qaH>J->-C{5pAl+pD>3i6f>)*aL*dIa z0JJj8j5NCM17CRy&_D{+zanZzVhF`$-ipc8r2J_E4n(D-q+mNmWw9wKp+I>%3uvI6 zss2C+gj0s*=Jd&@o0EC{WL(#2oaS&5kC$job$cNh85v+$Ld z4}EU~!=Y@j!+G})@BM0TpN!UFU6bam9u*R5iy@EV!Q~|-MduW~Ks#?G>9>tywXW67 zP*X!^n;wcFT<>cy`Xs))?VS|BcPhm*>w%!lp1l@^k@;NL$m(U0ULVQvo~`IJGmB1q zv#%*zZll9tn%fE5j>wThWB9S2NB0*fEZE5yIvLinr$wx+U$?9UVEi1p`nUW{@W0& z;QK$MOFPrUR4QO!d?>*GW|}(`pC969-+$rjM4u$1e|^KbWl~`~j3O^&?I;2c$5b@z zmy0;kQRN>d19<|Pu^#4Zt)5OuJ^}@aY7Xx0F`?|zh$eTg-}R{fd*53R%}q=K8NRvS zUtC<|q*yI0@P&<=r6{rtimKTqR%3$(=+nH|>E)g_nN%++-Wc^^pYrhh@2 z$V=47u_1D^&@u-<+#`Mp#md4l;nPc#R>{C>Ew_@P1;{+cMw#PNwvUOb&auv)%&=9H zW5u+x0Hd{t4n7jiD(B3p3lX#tRF&|)X-b8x6f7~ zhjtRWbW?#buo(XQ@P-ER@TD}=w>6k!e_#1CMT|tqXC({@FMbzMIi2razwYPAfV$-j z$VYcHChvFZrv<>9U&t@AMN?rMrk}fS7R@bcsM$sOuG`jI>43ktuZ-F7J+{S3z~?+oHgNK^ndp{8HwGKW7Y% z);^LF^h&QprQzp5FJU27l`O@qkDRI1rlFt+QIDe--3OlR?O|d0~D7n69q(l7atzJ-tcVIgFE(#ac%j3 zra4HSTeZzIbCg7!^u`F2SM?6{JeH56{v*@Lnh))p$Vg3n9tZ>Qw!SPou(0RF3-H2% zk&zKnV7ngxk7p~Sz2fYHY#lTm_5fWwW3?vtii=s|GPLNB&jSPI+rS;o#!V8_u8hnq zotJwA4GR@Ic&xhhezcx3gRdlC41OhEI{c63YpNb2=z9sl^Wqmw_u)ZU>(kWbAaRrG z52=BVxo(1RLHa=es=k~CXl;8eZ{7=Wh0XWLnT{S_5eJ90-TWv?;W43XRbFf|Uay1M z_sqkD9+XcMPSU^cFySm0fo{dPm#hHj^=<14AR1_T1H^7ca*~a;Bl&z+5OnJVI2+pM z2)}c5Z6t@?YUuO9#X>tA((q_ofb3R;dZAGs48hA86H$oXcIElz>555d&ujkcTRxQd z>ir=BVxNhg>^5*0Xr z9~Su|a^s&zvd+qsP+6ITvt4wqef*8fa1+-qVo-2n#keYEXvKYWr$xRK(f+UNz_7;b z0H9k4-HBlV7ywX<=+kI_S#H1%2v7@DBi|3WX1af-Q*&BW%~E+LL&^KRPDb$~@j^!c zAe{|3OPWaM(L9WaYFi4mjW!SEz*4cYa+K9Edu^Ug+sUKH%3h_i11<+@KI1u zl^;E-mh658C53YQto&sypZCEhhtFJbUQJJ}0wYc%-BImX2&C2%rmro ze;SW_G#%_-Biq{EZAGTLldfZZW(b?#ps8)=V;(VzaNncXUFQ2ej>SbgJEOz*wu!Q6 zL#9n7`}&l{f=JjyNO9rKA2lOMp6u{&OlxpG{#{!xzy?aZuCs$g1AN>)K(A+gJy?GB zbaP~|mP2{lfY*mz%NBs09n-zeBm<9IzaF0>x;mdbz6f27aUu9Y)0?}7Q#E)TY6*N8FO0i`~F%^Kr>O!fy{_Bi-<*|s_)zB$R8ZO zBxSfbe8)VM(Gz2nx@6#p_n1C){0UO0(YWrVmuBq^p>u)c^#JChq6K<2H9hZ1Zz&hG zpt&aPrsE5&`B?3P=-1p@K4Pm($3)Na(A(9(Es`4c+bHfemI$MG*|U--oH)LCn{mkgp_32icaef@o2ZRrK345xm)N#WlVzJ}~JDdh+Md6c&{CRNvc0OtN| z41oER5c8BS*%i;crND}Z3j}Qtz@z3k+eOIMdxyWPQ?!F04}%(rUL9Omik1WTw9?G2 zIes;(MsGkPO>hYA2$4og>(S{4@@UF{#3<(IyrT;Rg< zp6HvD12*V~*9o^*lFtNbZbC(d>Q!^xYX)x2`U=k*NM;J6b=WYfdSLDRJo ztht-?Kkxi6d$jdVGUo>18ET37-f64~0u}4jiLyycv)!c+QPhOu>(^_h60W5c#-ND0 zK=3EwF`*@qF2aQXJv@6WH(rm~!PZcZAm|^cd&j$)D8CVBDO-9*0Yaq z!g0gJ#l(py76{ zBYiL89oX2ZyYCJWPIGWVg;GhGl#%)aXOH#ZdPQ7#X)UMv z_hJc+O;WXk>5it`5@LZ%o)ls4MkDyoN0Ahi4}C3MFu8ZZxxPz*Wvq!ac0cH0zUL40 z=bROz^rC1~ec)_s&xqR3e&KRq$!X5aw1Ll5RI+O|a!9+U0*~P$BH^f2=7tx=5GF(( zM@t<`;c%DXI8X4r@5>yo@rUG0Xx0)w5fU%q@kUZ>1-k90ab&pO@v-J4Hfa_WNqlhBaCY*uDd(kCzTe~A!exqF*c)E|BK z=;c9#PB^+rmev=Etz6}M;+Uk`8vxcBMWWdz-wm5xAxUG{S64Lc$3@*B9~HzIn@>qU z5As&RfSX=_6%~IV!YeVFi0L-2az8p2j~nQb;HjCIPz5IQ6lM=+SAF{jU8x2H2J1>n zOAq)Yv+9{zSy=?O;rXVz{YptJ$pNEmQeKq1OtjTTpe+RG8g5$C!Z~wor?lm?atwB@ zqfRa4mbZ-1<)VVXZX24y=}q&UisV##?+n%rz^HAS%Lb}Yo<&sA;#JC}Pm~C~bwLdf zEAdNOrHgJo*R9; z1))XT0tuHfAdXwWVJXe$v*^>%<&!-QbAY!>_wQ?DW2kYIt?YSHErX8<83i-~zJy~o zsC^v_J~-m(^EgyXsAVcE#w0Ol39}oS`3?zXjEtlV7gk*F6Fz!&Q*kjkClDdpMy@WY_MfM6VJKI~$1>xyTQ5Da!;%lqM!3 zy6Hn}A|KzB6tgHZOyTW5-<@D``U#-z&4uBX>3m<<;KnSOymh+5xtemtMT0CwA`BI8 z%gCK*Idm$W4Hs@&=-)tXhM-ArFb>UW;oLc!u`cw;vyWdL?H%CY^02%#mN8?EK8O~R zMQ=e4%*pvWm;H)sRk>Ms4)wv|^@CmGNn)hz!;Wx_rx!uc3Kbj|_v!0&8RPbFF;Ot& z=;9$afFMSF6-vv!_^-(BUqA9E$pB^dvgVWU;w36FvIvLq?B&sJ%CyC~tl|2$?s>6V zR1*HP#+;_&p)$6jp0JFnQ43StgvV+FKj4jX{3$vqgKOS#kr_UW8tS8UwN>I$VU(_l zQ~9OEK@B-1O6Z#NI@BIel74ff)Mv$p7~*jpyx9!-aIP=@8TRz zcvpPpqQA;GWfBRLEa14H2e?QDt z4;>RU;*(FiX2b1K>nG+yaK=|%zvg&A9a;TFFRF#CshW?ni-Gz`Sz)4yvV#HM`u`M8S_;{3U88jsdqda(b(}uSp0b7;dWHVEDHRN+y4XUVnX}Ti@8AdGP{UE}2!z(Xq04 zF(W=PWO+4&258Ov>f+A|(zO-;AclIP_*F(ZmzqQ5&=kKi9uwOk$BsN=s{ZzR_FcoR zbr!XcHT(k!*KlUi2gsUFRAY1NBh-dqTZtUTB2L`~BxYt_l8->iKpZI?jBeB&E}{=a zNtuiXb})D@oy*_n_x<)1Bw+)HG#zoaGjiptA|JRl| zyRLzbj?sb=si4g17kRdeM;9E{--az?Lv5ArA{XCItf<;LxBMo+XU~PZ3aYojk*0>R z)sg?P4qqjlovY`#@Dkxwm6dDsp*x6STf7)z;#d7 z<|rcZ@8=@Fb7!uG`CsFtq_?zxS=KNzGpopyOt{~rxz+y4#N6Kn_Fhc-J;1W^blyKeonKK+x9LUk zrN0AG;|hioz=umj{tl}QMyjePXaMK8ytUQ7^ryr}+u3fYU8SQ`Uw&8$yCsTk82O7$ zT*^_RR#xsl#X$)vLLRSQ0I|Zd*irtBg?LXZ9G2ka@|NMVFENCorh8O*d5ee-qc)_q z-Cq&*^6!thwXq7&KtGJFkh*nKT`5!Jh}$FJciQW%?T5K*d6 zIja4o^WAQMtq?LE7~rrs%t_EvsmC}y4=F!XC7ivyKyY}4;#M2$D?G1MiKf2r^>kpT zrJ7V9wm&e&!E&NW_*W{p)0(oKI@EL3C%gXYAuMxQ7*F$k11+gAm&SZM>_Q-#W-17Ia zuhH;jew^nryyioFd+)~LNp!(-%b39E6VF--(Tc{1zb{vQHbEjBx;Gm*H>bU}w$?T~ z3*=HHeFFpH%F1!_OKgmcqT1S|CnqPSG>s`1c6Kp$V=`8OKotv14lA865w)Zyuo+8K zP0ghWkv=52$RRq}{~7-H>i&-m7XO@V!gOnHb{>`0@Gp+*$nkiA8S!a8Dhp_zGGpSU zw-afcZe91}SUBktwg;7B6T^)K*qq%egBx;KUb^(Zw#w7x{P$jp0~;W>L=j!@4;w?E z1}5+W%`U3T$EdEYTkDoMyQQ^^yzVC*-Er;8#M6WLS9`o(h)bTC7Pg1S$04ym)cV$! zZN0Y{hsjq#G)X_ziqdZ@Rr#n!#YbZ27k<1h5*03d_$#<9pFar$uG5p90iyC6s9o;; z!Q^sB7XIT>?wzQzcsulk8|(4o$6M27RIS%1a$w(EguRguB+;8lr%%;A=fc?RDiPS-)<0 zsAI4c`uacvB{DUtEu8{(pebw_kY{*|!L~GHTMYSPnlh@TpdWE7{PNyhB#UOVI|b*& zkyQ2g@kCEh=;#yU5fQ33Cy2qd+&`^MOHgny4FD$sogjfxQ8>>0U&-NDS6PjX+VqI| z*;#6UEl3Ze680kYzB&_gbmToUpq1J64EIY!KSCdg8QNpz%lOy&yO7?dB1gSXbqNUHl!n@%8ci$^@Du| zdQ;Ahnu39;A%9+DF10|r`JD(trMR!P^@|Nb_Qz^!lQU;iPh5iifxOHbi_`7jyg#kmk}-#eG-7-cy%gI?fUXH0+av3as=| zh9MpL3*;O|-UZ>X-(xX(u$!LBH?Uy1Udiv>v??2el$1a11xOQde-UV#?R?;R!ZZDI z*;LH`1VlR1MB1Yu3nymYl<)X4zsXVYkGP6I5;&h)6$V?saw4olBtvMAm1G0Ee8lL^ zBNX}+S-WO`+}G;9)zz+$UnHsk6G}OzBdn-pv6y$D4`?b3@SG&y-Tq9Pfl%_hewnIR z?Hdg{^TFc1Xnw5Hvlt#)ZvP3l^>H>slw@d{wBqBJ}kE;~^N_SEs`f3F?n zI{}vaE|$ORPpn+1#?UtDP928yj1eySv>u%we~OO^irkJ+ zTuIJ&*Y@ZIP@~Q==lx{3QXGci$SBz{^%gHayGOxYDoWxt(RX@gv<&O$_JUKhKE4Ya z;cH&BRJDP_a!TdU#y36?&w0y9%0EvC@NAnjOwbsB%6k!&2oH%SbylAA*-7DdcLZh8 zp^Erck%cI(XH{!QO-_j#=zkje!Mg``AfC1Sjdqb%Zczr!I%O@He2YOg@D5LT(J2)l z#m5`kc+LI#?Q7A%teZv@I#c3 zY5<*blob`JG*M{bV-Bzwnmt&XwmkOsf2`k+)eTxmUe0s4?LaaUAVAQ(L%T(qy&+W2 zJXeajJ6Me#d}ov)4e=67#cySXEYk3%CA)pH0i_o^q?jc<_ZgCdSh^n9Z`2sak5);y zhIwAYL1I!*>zkxMRK*=vQU9XbcQ5|vMpg^(YH+_1<4#@uePmu%w5aL63kZugSxNqARL`3%K%WxpbO;_%5))rS6Z{;6+!AdoSmog^#~l4RMz^`@FY+NBr_$ zsZir`UZFm(?t;RC!v|Iild=7^Co>89G!grlkBN3Ce!m|jEv?K8{>rEFT7m@nJNa)K zQLL}n(Jr$N@q-%NKDA}0!uhvH_Iem};&+O!&=vF}Z7|I?Q3Q1 zFB83M#*wk<{7F@-ZsDR;NescW(AIxruNg)M)cOgy$J1;f-zYe*UaMczv?D(a(pSlz%`pcW1%s89zTM&|UOS z#<@g~so}OAol4bH!E-f=XJQd`nxz5sQiRO@;#2K*`pw6t!t3J}VI>MZin0W@rPQk^ zeoMapi&WmS)`4u99be`n0;WAfWVZ1R!Ts zIId?*2;q!yv$0XJwZdqIfzg-HRN;{low^kSR7CXsdqzqh7__{qD&B#16$n?LO>0gd zg4{BRRVRYTvW(*zAe79{fM~8x7ZhxonqGk;Hy3|F`32zCi0h3|7h%|vg#1_j^Y9Fl z_wR4fcJ=qIuZ4cRc3g+(#=`t42a4AJkVYtC>R+i9Rs7} zj3KSwCn+;Cn(7EUWSg&GyVBa}kX8%^lRA^Ziv`$aGH+L^waByFRbSV-LP8z3mP0|+ z_d*k6Q4(|k5RXlA7iSL|hlSo=8458U2MO`3{?^wAif`X0dym)0y%u%@qC-Sh*69G1 zze%Mp-?L}@scWpEtKIz4D;!-W4-^&kOdVU}@+^2}!%KQJclP46t@vn5YW9bCcs^aw?(q(^MdN<6H6O#(j|H?WZp@Wg=le+1UT-?n-0+ z4=Ld^GFaR00Y-?nzTP5Q1)?ZxNGrwq`ua)A9a^HE*W`mbTJT|`#>MiGbhJ^cO?)3Y zr!NxX-)SK`=^$a@sUY@MYhKUu=@fxgE%$L|2A4&&by-4+fcI7P6AGv2S+X~Y^f3`@ z9&wUvpZBGHH9!4~kopCRjkPZp#s^tx5Y3W??d0JZ1CX&$xBjZN$H1iCJsJ_t?*J^9c!y;;j*FUaqv-lV}(f)NNK9i8NU&G7o7l>@`Q@#$_DWrP4dF)%U~ga^90DvC6CzS?L^0UUNR zMd{~f+%y%w&!@Z~XLjQeTXJz<%Td`_b%Sx&Ufsi~>to+!K~1J@k9z+4DHX*xJoo}+IN5D)Ij4DCdHS6;+uD9Iy_sJ)dGsXur8 zy!!pU9ZJka5~7{Ub8w2eD;By-v>hhKb>A#QySF*_fYcN!0BtW>^$k4kY{^uUQ2MBk zzluLOqC#QtlxdI1IYL#&My7anY7&0eLi=2W9%#No)kr92+jyaOg?CWD`q0B#hlJZw zH833ZlS6%gC=uFS@(N`<{1RwwV!6w3K@N%DCeOU%blF(%zYhZl(X(IZkDBW1MT=^z z>@)p29xT?s#Ummxwb<-yeY#;`ZeBp!NtKhxeCs?LfrE1F^~x6P2Uw7Dg~Dxv@a-T1 zn{8Q$)t$c-&zY~-IPlP{s!_tx9YA}L_VPh|?r?{9Oi5>{7dKF+`16`T3cWT^?l)jp z-+C+j@jl$OrxOA(h>j{8C|ajCCGYRNtjgg{Q}rtqqA*MI%)&D_k6q0wCip=$6p!el z*gi?A%o@157*eMHRUK5z90f_YT_zTwLHRa^#SK?3s!h_ahf)Sq1d`Ijh&(%K zK(tr`nCokzUDD$9LV3X;JvsKPw|cGgN=gXT4MOc%eZ+L1JJi3nFc(6;8uVzz;}+n{ zr~ve@XNTN>52@}xFL*gRIpLFhV60rskt34W-SY#A?LTsJ2P)!zm)j4Oc$~L$rRts% zrOPoVm3aDbNm6)lxbE2EX0Y?jy5X{`p4K^4CY2=Cpng1aGdsU|Wys2w_nxPE-hei z$&IN|?TR%qHMNqcq0jN=2qd#G9{a%<^m@m4zh-*9q9hUM;Jve9t*?_ZcpU=vc%Jcp zqyxfjGXuJ#2o&!)O}5Z3?>JSq&~s9aUqp!rsUTl5)nA~`OqaP|KE7C;TM-YuYxZr; zpJFS#h}gNI;m}VH;iWouhj>+$+}uZsTWWP&Uv-BrxUpWQlfeP&xRa4~OcPv7rw;+$ zoJ)CF_=yE}#3d)kh#)>BHq(k*)vUG9|J~!?IsLSld~ilw95uXW0Fm=-9RP_NelkIm zi9fgPGDCM0xh2)Sdt!@3 zR64;}cUXGC+MbPNyRRJ)2p?HZAZ;YLTdGugSPX^0MHb5Kh3p>B6>K%ejG*ClFt9f7 zyv?q9BKyyBADq%C8{mb(Y5WcDhIThw%CM{d;!)2e>J3M^Od^PR_8Ep6*LJwM$vpi; z@^i~^zi)t_XHrV$g``(+xyyTG9<~-%&`iV}uK(Srv+1ZV^}xn_r#o7`FLi z7qp)dwGY5?@`Xp^ju&3gq+U=2p^y#`2JWfcpta zq)a@}?X(+wA;azssp^NIxdBAO z^I*rrVld=lj=KRO?!lE~iC8B*`uQ{S$>m}77uh4CusaP5ySgqPTIET7RS;35+aW9A zfI`?BbWqI$dVCzGc7+O9<%;3a%(@8!Vng{+5NS`BYejBya25XtkO?l1#G9r*iA01#`j9PLcqRgC0dk0B7 z!IUq~`D>;x=A3LY9RfhF_eAWMM4RX@$h@zQdn+BiRK&%_O_>QcAl^_tEv?0R62dj9 zXRxiUxJtV(DT~=5)c6K;aI*M;vf$S%ME%zRWo2d7QsThhA&Pvkze0m@?7pJQ#f6iB z=`hwlSK}Kuc^D-ruN(U`v|(k%e-OXd4qPv`SaTN>7mP)auo>fRIs(VR6j0-M>2jce z??!+}#DUSXX?#VRvS=eJm<)8E>K*TT6+o|KYr382{>SQMMN2$7TWt2I0;8Cm->hXb z082pletH1mk%y(kj%`f2U}k|^OSOUoS2djZeA|9LHb*tI|#2dcY&J@Tbo)70V#ve zUaYx?aWf1Xp$)ks-Mr9uUp&inRxC4U|Ce)e!5$kMvm6m!gP5C{^(){_!h?QvKIbLy zY!+Mh(er5lf7)9UPaQRg&5WPCluC<#_vyb%DW(QPgqU1%rpy~_jPP#hlJU}hM4y`Q zJ&%vGHTFl+l4tIb&D{6#14Ewf)IP7T$)kPIH9VmEgMOpmBS6A`Sz>|`*jFkvslE%1 zzROWOQwH(C0gGE=C0J01BI79)&TJ`=-OI{q=6Iv4i(*(D4dI<#Oxc5w=JsDlF;5UZ zdi1^etYh`7fCX#?Yb9My4#)Q%>3pLLvwG=uJbz=gN}l4hNFJb-Uy*xUik2%WevN># zHCx|rjpGF+>wkPhL9&<)d~ayCVh)9hg4Noc4{~0f>({C32>s7<)p+5|uNP=}J<*W5 z0B;&?q^$_vS=sMcB*T~JT;69Khq0-vM2=U8EVTut+X1OXEZ%uFe`ESL-kWshfYTGB z3+PMkspi-e1|yX(+0mu)4i$>~V~Ltg7i^UT&96y8za(9D$YF~F_#}Y1MZVBKHgDE0 z11BfJYHv(05b-Q;ZiZ;+d!QC+lt}}cu9#R@X3N`62aQ+^is@|tVzPD(WI|fUzCZ-N z!{l5827_ah-7@>Uty0rcQwtVc-+lJ4r*d5#Ezo_WF_kYS6-C+Yk>{}Gi$e%Ujq^Hm ze5FoNLs4NaM+o2E!6AJV4aAH}mx1hWqm(S3ElM2ghj;y>*m!rtJH$*(Oyv%%(ttR5 z-w(v-s1jdvM1%yOb3&fM?}7;=DULUnr<-QXOgAdMCZ)Ce#TW(XCP$r9Y!x1-=A9So zPp*%~k$yZWR3Y7Vb;KIlv78*s`H^{82pd%2C$b9T{ztXww~4n!k%=Z31LljbtgcpA zj8O8m-rm5E0gWK)kXCT*69`16 z68iez_$^zkR2y!0LQTDZddS4sB%zhAjqzQfLwWOuKP2TcMS!(g_)@>T+)1jfoCLP7 zq`{rV2?azMx$qtvex6~|oNecRidkhL*`|e4<8Jeht=mZdI|e3s4%cgRj@v&vmT;iE zfJub`LzeFtCs8GjUzD&cZP|u6edxB|$xVC%ztFQ;S}ejErhnX554a0SV^FMT)@%B6 zh;n?5zN$FPoJ9C$sEstyO`n-K5T8+HQcV)l1 z1%6+?Sk_F(O^VvBqWU&f%|H>;Gpzzoj%9qL{J*k&Y|!p(EMmcY_)Rj7pX~pELCwt1 ze?OTJs%mNyR{MS(9TD+|EZk4>OG<-U zi%CgK9`Ed6t6ek86)r7VhFAjQwS7HsoEyw`ludt3S}Lngxt2wE*w~cJ?bl0AB3eCf zu#>AQEZ0uDbRDpnF92+I>}TPNV=}LL51!AC6IhRnoOx^HNFuN-N_3ak%`vb@nL8)z zy0_o-Juiy$j_Wc=`ugeYG^%Gxv!1op^ zT6i71dAKa=fxfZ7U3z3$j=t8#ncuH~B6%Uh#eQT62n5>WQCHJv;mOp^lTkCn!K{*9 zt1o?0>FDcGLD}7~&MCb=xVH#7FB2drQVy9&_%F0Y%HvA0u=n*)202R8UW@zgAnp6u zvO_#Sj=C5zzd-&cmM*U$aEexeBwQ1rTXQ|j|FxHaz=~;pTHg}~=sf0}z4d>5dc1*k z*w0%-!NbD?2(J}nPjPAF|5hYu%$!9v8n6*7AGa`uLKWyB8jq-(zK=;oZ9KHUun$;R z_u2=?n`|R)zJz=HLbh9rD;{TBgbXXP%skm4&rxe(bIpB15 zRfyS7Su7{pxvfrfa@!7YKU$RzYI}V7dgfB-;bzhCV5K<7VH|%4Gr=^YXLg0OZH{E2 zaXuTCJW{cnkdiHU1AaP_oOGX?FLb_wDsOkB{qb^q&(pqs@|yL_*CULQi3Bx{2M?1^ zI%f#t%~OD`Z)apcElthyYv@;8=|v8Fv4{M0Ugy-tjuZ894d_|sZ>3%niDo4G>4{K^ zrb1swHguyu+>qTHvh}LuexQJO(XjVFEFEiBc6No;G^>l`w6>1M0gp~KKtDpFhZ_7! zW7rYdmvVP=XeVs3B4>S=V?gxCGx#*(`uJB!$^q)X*j%Pc?DwwVJsQ6wNek9 z2O2>tQ!Ko}Q5jvj`GrLlffNHu^vFBuq-Kb^#B&AN!z=JB+<0VirKDOcDjPXtHGQB0 z@?1;D3c%u)@dCoevjLF{08&v1?Jrbz(_P{=7S2VP&jdgfDxa_R)L{mEt^>u4?pl*e z6Hu}vy+Tr+#(Y|@t)fEL_q1)KC4iD~h91}Ga=k-$+^1MnWxh0+$}9YLef z4{jE+9Y)eI+*NZ|Lfm+k{S>=`S4*`d#wfIA;1Jv+l_aB`M6AyAklv178gz6KI0__B zqtHQRV3k#alIQm6&2a{my^%D#IcwVe+nq;V7iDa1B1ph{s;aEs6C{$>c8=+Y?5DOb z9q#qF0f3MpDSxqeA`{b?TtXPaRwvZq=1E_SH*VTP{rm;r9ILw~`adpZcxYr~7wmY| z;cQD87&^TSR1Ml!x+Ct&(m*>Cjj%AK+ky)bph@QM4ZrBW1QM)b7(_Y+>`Sq>p?@7P zO~QHoY`p9C)wGEqWiwRWnfYz|6x#@m^9BaM>u-Y0`%zd-@UcvoOo$Ir9pI2*ea~V? zegJnf>0NxJThHfrlJa%|b2EXh;sSweDbL=u@UCt()y+r!j?lzIRpp9^@tt?r5_+g2 zbJebx5uNfA@>EQhaVFC5K?FxGgOV#f8f0HyTroAj%??Rm(tqnS5){b=1C|h;8bgu47rsS7k>&2M3$A6wTB%U0R=>KpvSp#1@!tl zZ_3E=)uc5IeSm|r(|=U+?#k>r?D~=$_OiQtx3B@btNOAEpJE5gO~6bSFNBB6 z6IH;BLx25P_zN}^xoq_YbbybPNGfthf8gt{v4aPg_@c^6@qHIlv6M=8y5~xX` zo~J=jQ>!%~3YrhVrl2uD4`v0CKS|nn4HL$pt~>wK@N49z2G4^bV$@R-_xcLNMJ!mw z^WTU!*&*{ZZ!O~G$Aw=M3{dm_yrU2D zsZB-2|A*bms4JBO;6H|Qa&xtTl_=d3njwk?K(H%8I!Xl|y1nGw)vfK*^8FQTh7y(+ z6B!}gIhU`6s*xeR>Ea&{Q4!kz%bgGca-e`k%wMwmiwn~}JNY2>gN4J!nb!Lf3MEa= z{9&{g|MAr|+%@?x3dF}|-_7vNizaJChp));jr52Gl6vD5*Qf(Pvnaq_7OWM|3jtV# z1K~`{DtaLRQr>WAPJIxo1h{gocji!$m){RYh2>mcD>NJ=!sinR({;m@RKGt&Z9;Yb zu*zGX=M~0!r|B6q7({mSAE(*2f>&OZfvKJ>A8)41 zWBvP9Ca{Yyp`G=#6J!fs5_qrJ2~;+sMcLr8bT*ziw{ivVHh^0KVLk^vqBS(73%H8u z_(9#WwEZ|#$t>!)>Y%6khTp3W;tbF&#-a+GRDWZ9e*}M7X;JxLHb7vjw$)KYDWr;o zk4SBws5IBn7jWAHn9RU^M`$|OlE{uMcuA?uH#&km^nk!8C$00t^_QFwr#ALTG7-hu ztg(4|LV?@U``;E^QK^b6_1ujncVVo2xJTrn$~&agtRK@A`AQW3_}BmbkY&XJXzS8S zN5&#p^&0!8#`=-|RReY0EC~FF1Ys6dK7Cj?F)*v3-HFi zOMo?6SyNdn8go;6M`VuP-br0(syA4OGr(qh!Cg|XnfE)y?9%hLZDp4Krx#cyOoSsN zBj4pE|FRleJiNpk8|DD8TF=-HX`fWD1!yPk7Y@OxsU%EtMTWUUWkn@{iBUoF2W16? zK|NCh01;*On*x(xRk9F}aW7FW(QRV!fnGIpwM7m82b3LpB8d0S?d760#XFUhf5{2{ z{`O~PK`{wH)@JZIt1@aJp9HM6yJ5Fi^JRx8r=m?BaF%~6|Mft>Gpj$oKqF|NN!u20;>hB${ zyqP_|tr>TVW{fY~w>mOw!7@qBo%2UDe@7wu^KwSGdwQD8Re!K|aA*g{N>tcEgzros z(5JUGo`?I8N;q=1W-0-sSCgHyMU?%k&pY|L37RCnO~ezrOZz-krjE z_3BmSXAtpUFCNt=7|fk7hIQn> z-l`Cuw%gOiBWdOF|JPeh%m?2NagFp@UjNrC-O;y{yTd{sayiw={kdBI{`57msYw8U zg&5(RBN@s2Kx5Sr6q@Y4Gc)va=zl!k?`L(AoW`cvcbFT z1Ta_Q*V4v_spRrixX5zBgCxsxE{ryn493ltRgz+Zm8_o9m~RnOU3CHpPM4;y=x2+> z3W=Jx)Vz+$LOA4$&`LQ@N2l>Gy6Qr8D@mtp&dW^h$QV%M;;$sdXn$--AmyR}$Rf0~ z62HkJMt_0x3(Xw{y`v1EAiH}0*3u{K8hk_!!sqjP5fk3i{as2Zb4(>cSRKJ|Qe%ys zS`U~kT@8p&9Y}yeB|+y zog1`bU3^Y+v<-+w3UeKN!=xt#kC*3WGJgn%^c8BA!Uk*eE`gQG=GjmD9|_Dh3P=xc zoagYY5-T(zjA1RywP;p$DtWa%P`Cs8Tjzl|$1Oi>ZU*b)K$!LJY4Y1#I~t_hj;U)8 zUqaveAIJLTy54%4<=bGBhD{55QVQI-P_TY`k0pk?S|Jda$r9Nq;sYhGO)fmPDqib* zqdIlJ<}yS%p#)8bd0X!qvh$O-z)iYKV#LHKmh^ALnMO3=$${F`ti}4xaBnlf9J^bY zF&s%`5XUKpn=Ws2I_r;lotXw2!x`*r*Zd+<~~HA}L|<-V!NZ&@30t zQgJZKbRR%L8Ue}#PAt_wixo7sAiRh(l)d zl&NcVzQeJi3U@t!QmZc!G5M9Y1<`Z*b5}gb%BesAM}&XrfoHYPP}Y8 z=(!wGhYrr)g6SF_V7LBIXdOiX&Q*Vf7Ba(F~t zxewxF@$E*0?5o7rT}^oi*U||d|7+-5mfidu~l*k zIoIe8TG^o@hszN&o4b*L?Mp$c#dj57>NsDY)SCTH7+dy-BJWOuwi{{mszVumQz`(~X~w zgz`mDm0pY5E&tI*u*J^XpO(fGq$N!3bSR0EK-Hc{btsidx<7h%vY)ra zwwTcmCzSXd{=lf8LEfnO_$Xs0I^nH>jM}Q@;y2uOc(n47eO*WnpOQ|A%$pt8bnrDl z6B$T&135EFKj2%Ou>AzFxLWr%@994O8XW~E%9m=4*0;lc7CZENp0^Ooy`3lzTO9R; zcR^HCp2*KtHjFMi+lnHLKHBR zMw&=bdqM3^MXsygKX7~Tf%5p-@%mvA(*?-c^c#A`V;%*)FB=x6B1aS`FgI~m8a_}h z$+*lE%Lxx_7DG6Y{CD#Ch$yVQd?OD93Y95}dka^@^_?|0YlT<5HRn7L49&CFWgc%J+I+z%t1&z<6Ojc_KnVfWC~@X+2$ ze&Nn)%|#>Dy`Izhc^!ayoj#VWP81P>Fp5=j_aZ0|TasME^|}!5Ft~}-W#`Vw`#v`WNcR0S(0u#n#+vR6&M@_i z?`CH}EdO;*F8+rR#^Zyf!T2dBX|a<9j4Wy--S{bPeg$+1Pz6PCcu`L=WY-BGj472I5xxesJA5^=PuA zjNK97zEd*q*LeUR1LJagsINn>ldI48X0^d1 zfo7Po%6FLN#0V_M6j97q2v)N{>-QYGYXYitxLEH~U4yGT!WR_Mq*EQ)PTXr6N^i)0 z>8qe}3*X*tRZ;jS&!d15w{Jsn2U=P-u9C~E9kZpaJX;42h>{U1Y>?gEMU%{mW z36U*XLPw31CNEx+=-v5gGSWNgQy1j54^nmD`&3j$85#-15uxsQW(%YI1Xlr6ZhhO9 z9ljl5cQ02Z0X>#TbJgt{Ic!gw#gT;@TJyIj zE5!wgH*tNt4K2xV^u;%bwD2WICFXq=`0=V{y$nqqMYIrAn61XmL}gu_Kq;c$XWo#1 z&3guh+2hq1ZnKH!u1*i{Dp$r-g5(aQSvkE#}p5%v)cM> zyWQv80y^e)f3)H0Ifz4R&~Yj%>iMN_L?{JEi*IByQ(}2D-whY+w^JUSYW}=FBW|ve zX%5FFlXODnYK;gY4VP_roaL?V|Bbc>;a?u0b1Ba-z=KI9f^D9ul-7W5Pa^K9cLgb^ zd@<+vktkBloA66BJua*GP5;Bi= zqnNQ<4+YwTd_M?MGS3GX8S7?)qK;BP%k_%)1Yx0?rnEBGsfFFsbCkR=&jkxZ*9JbW z9yk;lOUsv3UdAmg-}i)*D6j~{I8l($R2+^wA2(8jd9$YYwd7q(?T4ZHkmNnxi8$?{ zt2MoJ{0e9o@fKFMCSfyAZN(9MLv3+1FKb2f;*#}kXK97MX{&nEkoS^?mAq%N=`;R)pp?OLr{xwxe(( zopqc;n)@~WQ6g-r(TRv^?9C%*y4fVC!bKl!*z4kPe`^}&*bQ!d1DomENk#nUHAXG% zLd=^!&jtg@!LH*!(%y;d3OsZQ1`{LoRa#H=AK6V_cbb!tu z=_Wng$4cf>(tHyYQh*(Q_J-tGq*g%qkZNO0{M3GT`5vNAa5sdBaJm9|=RA_{BK6Mf zsrHH(ZfW}iZr&c$Ij+V^nTyhEHzJ0IH^Fn^O=u~S0BLZ!A}dd-;;`*aSlm*{epWj= zA~gb?S(xnpO`4gNOBn6vAD(Y~RlG+9S{A?S#>ZUe zF;e&WiLc`1@%?@Tmh!)4_Zt0G&%o=a-IPv7uJ-p5uAGFerY^RWn!E0Tfw_&(6{EdV zpO9cxJu~{P?tGx`m~f~Yl3lgM!PlQ;>7u6L>6QzN9dVX#^igemWa;}%GiHfe z%;DBm7A|657w+);<3GPWZ_?E*%wW%+G6cMk}PVA=O~OS70VAFcW{9%fpTD%_<&W>Z#qjcZfuBWBEApy6y{+ZVSS+wDnN zxRCiJbuN5bmvjH_Jot=yR_xd%2EI!<^{)Jy+Bv$j8Psct@~Bd|g)uz3hiBU4*{>;A zQWf3@Q@%(p@%FlF^iBB<`4vR8{e#uQH+=8R3q(kET9@S16_52 z3eFhfI~>ndVs^!4@RwP;1%@-6-kdGG>BcRGYorh?p^lL-JSdg+wAWy!2j`neW`v>jw8K44`I_Dz9#VYFiPbc|E6NS-C7KE4*X z_w2N<;wA0fS(rGLQJ2L%)w@(o&Ec&mNj=}0muIu>_4nuR<4UyPZ@eIDkPSB<@1DjW zEO1?>gZuX3JH2N-*Iu=oIqTVh%JtRk_y-?efy>%+>x9Yj-JDU^w5xHb{PFf)6OoF# z-AA<=juJE@Gs)aXjh76lBAf!}7`1|6FVn-P8I4oldnS>9B8LPAJ3+M&fBoUNj z&?f4})Etb)hU7lC078bc`|vX2&l;zz3-SdB{(G8>Otq|a)<86dpg%uD5y-9A%m3!~ z%!91Pfpf2A95W0A4NIy3lvlAZr2zz%Wa=tJW;-A*qeaJT{@`(a|8lD~OP^>cCn5mV zP!n4-=yn>EA=9fQ_LPJNQ2?Hm#;RN0M+<}lLz5(~v&;RH>c;)b%?`5F=vD=ypYsF^ zC6+>R;1@!Y)2Scf5NEluS#k_pHqR!VxRVsM167M?u!|AxQibJ4qC9a!tR0ri)~;Ny zh^0zfUBqc9*z)nmR|$2{;%^Hf9ZupQeFg$%P>fdP7j4HmeK+^k-23Khkqhu16eF?N zgTpHoEyLXiUoSf!WR+B~NqG;vvac*|c<$>@A$hY>;$OM5OA3$!??&no=yu|stul;4^63}oWa4AI@O z2Z8ZrobiWLukL_SyBm9@5|qwbgT!{YwehcbZRQaZAb;6>-+-98?#3@555U4(EYByM*gwQ$=xt;{+}G<#rL|6?vcu1 z#3+{Zm{-3(jz6-pLgUhP_Wr@#*?#4^EbHfag8J>ae%{x0sC0ntX4ci>U@4zA-Z>xN zN55;~L;fRLW{bMTPfjsWH{S}`WCDI5`N1}uGMKAOgEk^ zT@|8nc-#4G1JBE`)z$*spVVB3#12xC4PqJR+Q52qG)|dv)g-${ynXj90J1*O!%)_C z&g4$=-fM4K?Qpax7;RxX`nE!YHQz?6@JijnFYZTQQ`U0U0@L!2cfw?OJ_Txl#bFjm zauSe#;753ZMKLAPd7Xc_*^Jv9x5~q_rS&c^+vKt$)2F(DO%E0{jq@4u+)rkgYd!kn zF@fSEHHy}b9`5Ag{n)T$#zbp_*PXQQ{}os)tJ^a-M_r(n6>d@iq?|}T%@7R(T7aFM zogb>dt1}(l*13tl!p9nn>-uho))I4qb&;Cg5Vau(%mE7!LMG#EG65I z{*sm1(XoAh?40;*(v^Rb(=~nbMFeTp=mS%3=Mm7siH*?eL`8oe;D&Tt*``XmisItY z+UrTu2Kbwv1bXlZ&B!wrxmk9s%AZ%1{JX}!>;30u0X%Q2$@^*MfpXo`e=pTE^Ht)L zu4Sa9fdCh$Dxe8DhMRQtZEUZGC^DdZ-uZKFU|0(&8YCT1(%&q7+{>$V19pHXZE1Sb z-#Y^c8(e4~0os~p@D@T=?Z76d&?Cj)FOWk5@bJmPzO zTJ2=M4QcDGA_IV0&AV2S4u}@r3B-I-Ozc96p~? zb_GGyjdIn`t7ig#e5QY%@R;OZ3OPDKL6Yq3>~r|lJ^?8yI^bh!NJ>ubZ|J^<$d4I^ z$I+^U-)dcG=abbJ7V7w0Te*KmR?$KDyNh;>5Pdi9qMbLDs31gY^t1Qkj!0#ObPPE? z3^~aO>C&9zxKTHKsZU!y>=r^jF&f40Xv@7T&JNg3{$9qqwpW8)Vtd zSPT{V9FA`se04&+`*sRXE4%jvS?2kbX{B2`@@&&0lK5dC)LA!@y7+r*hi}@TYUvhJ4|2k z=9Gi2#&~Jj3go!>=VEdd;`&?wtOOv2cs@HnPqRLlp&8fsm;4b96AV{bkGc@2k)O=&wX%O3!|on#r$)8%2HdWpi}`<3&xWGy0chTZb|Dd#54 z+lwK)`iR2RR&m$j>)VHR`+Y#z)bFMOuwVV_aL3LufEJE%-@m;1!$&y$L8^Z3ouRt6 zHYz(i`wqZ&sJ%MdO*jT}(+H@kV*$2vQOWT5|0I$UulPS1)XeZEWs1B`*#*&YJtWN& zP--(mQOF7+ldyeo2^*$h`s?-n{%G#`U-$fPRcuOHT7Q6wN{mBSeRH$XAP5X^c5oLZ z0qsW)(CCpEks>~2h&Jn#H@kvS2H}xpW2EztZZVv(50AKsd+=!F+|d?o zOlnYh-e11lH`o5S@5XLMgeae3FM@N*MHr=TUE2H~W76M8lm9(-<97v|l}XpAmPzpI zbmW~Gay&2?EF$>u?L`+8Q6_8r*Q>Sl(_1H5^_P3o$-FE1F=2N8oPgr*LqEGvr@POT zXH8NSvK4isXa;+OskR#*E@o6#D-=Scb?uy!E}aO2QuWre0Ny`Wi8Sq-i;_N^3oS`s-4VPPN3#mFa-Tl+X=G5^l5 z`+dR9Q336>m>BG7A)P%C;D-8Id?T&Q4x60FX;p&Ko#|>%e8?}>8LazU`&iYztaOK4 zP^#3b^uWpLWt3=DxSpDRfzEq-fJ(itt*x~(Fyc2&YL5vhDvx-(3@nU|9rbTSqWpc< zQYfFStM2Lkx)q!}R@8lXSFfDRQDAKtF|m72DZi!;x3Hb7g(z#2na~Q*3}iRUsb?Ej zEcTyKR21ni@#+5VepqF^zZH~swC@Jj(Zl(yI-;b4Q3;D}k#wo3(?LVm5S<;+hv8OM z)diP@p!L*dy(2!!XtYi8$|&8~pPoS-zogJJ&~M9&kT`lu^3@$UX|XiDz(k4ny-MQD zR~BISrUhV5OgQe$xZ@hYndtBTp57L8tk;^(T+6R;6#w2CS5E)okyn)(z(CtP`FevU zr+8z<4RjNNv%^7V=2m&XNoD1MXHUhOe2^HDz#nW9!O{QuF5CrgRjUrAJCy7&VEP_* zI1K>a()3q`CAj#}=|>J1%|Qkert1A(`j{2RJ@&c(kq9=ZDJgde6pVEBZ)a&5&J9l)xMrudDI( z!x5wo?Y90sQ>GdB?TN4N{{0;nG8#6z6*-vt?h4#O2cIK=>8~e^yP0`q%;T3aVbbI4 zv&k}7u*MIU9fUcS2kpQ!M%@lfcu0?h)^js|3uvn_N`!}#?WbR+gPg%9fAosIfM1!J zufGm7=RcUqF1M4l+Kb?QWlhJ{_MpnNvO2{6G0}^m$iPn&b^{_7uYslS^eSS|JjGgf z4ScG2{X)*);y>yW4Ql{`0igZ$9fPZU5P%rs7Y1yN;sGrB?)6B@BP-E-HQhSa1RkGC zXf-+uC#!&pJ$-=*0hyT9BeY9lX+~s$yk6C)jzQYxH+@F8kdDU9&G>{QJY$pl9^gZg z3Ba#;inzdEcu2XYxH>FE6;NGp@19g(tgDs>RjZd%h&lWc$7{b|cr~)grs15vt(~U^ zDUL;jY6F{ysx4^3=+iWk4M(Roj?acGj^)3Hv>XVRsHnj%`6@tlV`o=(lm?h?4so3{ z3V`ctN3&-ffP|d|MW#Nue~@9u$bXbjE@9v6T*H#n=s9dkIjjuRGegs> zDW=iw)B(-8oA+TkO;Qq{R}dfz1|-SZqJ&L#-R;iPw}0%PhcUZo288&+iSA|k?0(e2 zQe83Tl@j7zt8-nv*az;x?ysT3oe$GxJ*ra8UaUY`>q6Q2iO+)S-Rpliy(O8y$>j-9 zxr;pKU`8)}3EbcFK`#+vuVe0u{L*5TEB@6UOv1Ip$`7e=J4RosGtOm4Mu^)lcNs zX@`nM(wi~`TTM{2000GKqHcxhgyiI`hL&px5j>SH6!xF}toEdW24QVVageBOYUK4>up+>P|YtF1m-D5Ph@L(W#7}bxF;fg6>Qq7NKezn@t94)Zm(d{W>Du)*mjuX zk9!{x&8Vhb>)B5;*lc{%IzP9Uvxvb3Btd!{mgOzz9g`Yy&7HZ5`***>fp4=qR)P#` z{XneB%=LkI*(UeM#9`7Z;c6-+8TnyJELk0OR9pz>fc+ww44)hI01s zke8Q716=y*T3WYWI3Pckj+672%?L2=5{~~cRd`=df3h|=w+-SisQysn@fZMa6c-n# z?E*2hUsnJ!p4HBa{BgTA`yV<3+bW+v8^}d8e|aVooKgei$L-k_mYc>$5FSqFOg{Fw z#$5f{?1$xsvxVnrKT;uOYo1yCHlFYrJ+3P;9%X5_Fg`x@yV1u^c;GIGIag8sc3j(d zJ@q$1zk>6~S~Rg-FIWA6vI?JP;HL<}9hH69$5MXB6ud|4ga<2`R02~^PN{#*e?29n zW*=(tqq5*Q6$K?%{~jhIMTIFTDQ{6^2WMyR#?OJ+@?cCtrp0%Lj#3pSEzg(1&dxkr zTU*Z;ei$&lyj3Vy$Hv7a?=Ib7{<&)LD{8&n9v1GV3o-g>&I-OM80eo;^urQ8Qbb%2s~Hb;zOK48B`~3`9$X2+!q^?$vX&Clo)c@E!IQg zJ!3+X^Kda|YUzp&yK;WgM5gkhXh=|h7*cNYq=iOspM8|k#S*?7(>@R-RhdAzi_gcT zq+fuK-Wn?fsYZ00qq19*PL=#;*Omh*&&ffi6mm=)zr0;<1AgHi;382}QhK`r`1Z2@ zS`;_R%RMfVsU#!XJX`-{O_4ucC;xR?%SPNcx1=m}&dD|c5OqFknAWGr#}Ei(K7?jz zYUDw}XoBdStIY?tL?KD7AyKNHKpYYWjZrYMB362(wrHb-+K74qp!FyrVd&1)m89V@Map;{{7&fkjpRJ!+5p6Q2F$w z1)lG34(O|i5sUu}8UX&wmLjmjdY%IZE^(`1C>df258Q@M>vspp;H46FzO%%5m917! zy9}dhZ+Nx7>hjCac4vlb;uf3?Fe*;4VUKmbh}@#f$^(oSSM$0WM!Pm7a?l6!i2J=J z4qqMI+q`FNA_9N})Z0HI3MymRN~ zJz1yG^-Sh}$07VbG?f4c45&dlR@*^`zxUldTxVM~(%EyO-8E>)DzxG|gctiduNx~L z^r_k1{*Ch3bTYsCO@#;Ptf3}4heCy{-+H2^IL~*|9z-_&0>J$_i~jmK<^nKYZ)Ms3 zmTLhD%;+&00xD;e_O@&AJ%8ihFZ3e%9oi)IlzjoNVFzZWBrbl~WD~kvTR+VoTtV!n zGy-A2dzVeNfkzHhO1+Phju38}(=5+mo_D*t0OL9mDsE@ns|e@9$JC}#ZRTX*5>u}> z>%xJPP1Vr1t-nkZt^41a)?+M7aOn^O=RT;B8hox5{_%Dzz1!%%{ro?|*)br0>Lw^C zXzG(S-sQ<=2;j0mp`^kFa+ecVb?I)=xwe3_kKNEXK;$!*;Kp*1oRuvxo12et{d7)k zKCXav4PTV0)+XsL0IB9Ga0U<_qo;0XHl)kFqn zyr1qv*x`#GqRx`%@jNGbsa1Hl7MV8e6hQ0>9sZ>Jwhg$WZF+K_3I4^lmiKc4Pq-$y5FS;i;2x3`cWI zmy)d9blt=w6b~v+ZI~Meb(1SXywq5NyfrW4V4|4xa4wJSyuTA(gduxR5*&ad*#cZ} z$B5uKriPW_Mp9>o4U`ngHY^VkrDjF_^%~Lx+h9^A(2M)r{his|^PO0xX_A42;d3yI z7kH;(O(FHrken#*4w{+3yrqUIpY^PRR{CIKC&|ztR6`epZ=RmV0ulC(<9V|VYaCQg zGT=QG(1SH*FP#Nj+88y^{t!Ea)sfKY-4rpTpWBJQ9nk-!%>BoWB8slju<-r+vonAh zyj22=kUx7_?Fy=S3b@zm{+O&(_)-j>P#9{*%q+j zv1QnqsXdv3cwmw~jP;^Hf#B0V#FD zEfnZHlJlsYS@v}%r(yu@#S59$Js==_`oGs35da<#28dIl$V$q}Ku2tqDP7F-X|2e6 zZx)W{VK=qF8t&E!8`d}TsKJ!!40akCTR3l$8__z5OhWQ*xbY%eH?Dlc!XA?nb|(}Y zTLDS~sU(WJVLIM17JCs4j(EC9%9XshkP2L$Ot7Z*Dht|7@74Wt_%MAZ;)K)nhMD2} zBxQ@yr>awK@RxAv2xk^J^YsuPQ9^Kwx%InHC(Chmjmt0wVYsUJ<>h3gE+qN5IE1GN zif2?dxKtt$4r2QTWR8sIY&2OXtw4L|FU}Dml3pCrEwkpPFjNnwzOTS2H+dIObYPP{ zgt4DA^i;l@DLCI4g&o3~_bq4W%@l=yv4j6{RTWzP!FPUN56<}P?g}lfSP=B%r5jF} zGJQReD^|r1fAD&&*()|gtoaJNvrTf|*>jjI_>v(#M)xQ6H(A?QzS_zl>%}`(5ACWF z@hXqrmkF0qNBU+NLR`4)nrna$hz}21QR>>B8LEk&Y_4_Fh`yh;!!qM@uR&>hhr|X0 zgSIu;8tQnyXl0rupa1=bh%Y&Eat^TC+ka1E8eZ1JpVU(qoRRyx5^vW443bT&|B3u!PW4CRIzpr`hCXxUXPAn(vePC_% zu#qhmSi9F610bXPA+hO=;`_!)^bOGJULHX<{?4*T1|53UA-X4895br)-DhBfYiH#>bD!1d8SQ8va7|PzaXXO zz9DjT-y`$7dR#v_gc2@Mi=^D~s_JwQwB#>ymwnz30|kp~plEVu1sK|DDsI^X3K{Q# zc2YAnxzm&Xd}BiQH5w4_tuy0^FXg@<>NiK6H!R{*onC5K8{HxkZq0(1Y9}GFA!sgH zOqKvMVK`Ygw^}Q1)z})JXcve76`hMh_$;j78v2F(BRe1AV73BS*XzXN-FBywowmTy z)1LnsS`w4%aiRgKI34>rG`4J}Zn;cHcgG2(qrf~7O5BIr5(ThM$l}TkLP#f|v30Gz zNlCE(n5u4Xn!-~6k6^V1VD+;Bto~gpPzp!1x!^BfIK4YU|2a*+!ek~yaW)<@OBlu? zuF22?)bXn(Z)wWHion zFb}An&7q{P`iU{yPunG~$ejjM-JVGmFo)D-1<2)p_lga`RO2=b^d;qJ`@Sx?xCwt8 zZ;tlwRpzhfHE;i-V14_;U-z})o=6s8Hp~>+0$fA894jwN5eN8uCF%HH+rogU4wqi1 z%4>V5>NlA4KX1;C5pbYK5-{EdO@OW^hHsewx|$78UsKZGe|Gu?54f~HS3CvGX0M~& ze+j=Z3QHduc`Ie4)l)Q7R;oMxdFTA^rw}r*vgF~xzwIVvN&3G5xT%$fmrH(6^%F4R zxaGCg<7>$>+ZG{QnFd<#bg}_gWk?#Qo&A=&rZyJ4J=VripZQ8*{MTzBAZBsLD(=g` z{d#oa_JLWI@`U5z`eIvJ<7iqxdhqtLiz$&ri*EZ|L_fpy`&Tm|4e!bS82>kZTG9ScW;#u4!VOF)p!hhbEQYNNzofl}MZcV?-TiX5 z#o!K(Ac!rH)EV4eDM+Ll!Ev-;L6)n+!y*mEfeCb$mzd4o)D`eb43nQh&g=#fNhAji zY5)kyPQoF=-bD6U!0;9a7LV&1Ur z%7&DYAt`DBVDiYvvwTy5E5>#hm-OX}bi;_i&(9bV>+`sE!4-%7JqVqUNr2-9T7;NX zvQ7PxCn+Ti`Pl2>`k}V;pyuvGU<&&`#u1d`zX!?PmyHYh!@e=ydvihkymRl-T?*%L z_tk`h=zHP4Pl$ym3;Wa*x*_hps-n+RzEe=|+}OT1Y-Vth=t*VJ_nlN*5wNS;EH zfs!)RLkw8}^?Y-UwCd-KoqNwI!SxklaSbz*Wfp-aelX^dSbP}%nGE_hA*e~sz}qnvsQj$e zGpWBDAK`p3jTvb?=>hlw!U}|_UXHat)Qbzi@Mq)(u2~&O=0R#DGQFij5kanov++6Z z7pA)%Pk^OpsgeI8=*spy{IW1!XTxk?EjlJMM1!FU`iLMc%Q!|qfyw-BqkCy5yf#-u zlD$14d8I~RC0pB4_uDk3&BsI7 ztdeCGMk)mdo^?ri<`XrV)~#&VZ(Wm`wnw=g%8j=jPl&m!6cC$AbCbSb%%p~K30|kW zSn5o3K{}$lqe=EmLOfyC?BGMWqeG(E>8+iB9Lfw5PsEvy7aN!w7ktK0YkC$JdgSlR z{q%jAT<2^AL8<&dCPmTvSXfvCX+n5F^{k6APMpCKAVYO`;DKTQFqk1EncEZs3|bZd zZqyZ$a`m4oHGo@f3;-x2v4vvwbvXT+^MS9Uah^Eej(O4m=HbV7Of%0>CM!lYLDU5; zgM15P;)^z|S+Oyci>iI|(RMx=^=g^(lZ!~_{`UF0);5B8sbXhpK~nz9>~@Nb*m{d! z(?Lcue<@>D=t5b`;znV-?w(HaM@Gw;Uj{4{-tRHNqlv!5{Jn(Lg`bbq0{em!gljG^ ziLBCE(V`cxRBZru>^7Z*3evDaN=W?1VOXW?SwRT1E$MeA{aedu{ybJ^VJ z(fw}nO;)B&N^bdf5hOLC#R~Z;tvWg<-#r?rDH5o2X%VEG`z%)JmsHXuc0y-etVkxi zFv{|wyJI`k&df99xFY_=xel6lebEdi`zPPn-}oB%u_H<#09IafrwK)tg}*I}P19^;oPA{Xv&Us9><^p>bv@WJQ1EZ97mbzmPzt%kzwJ|MB&N44VT%_hc6DL^aY42AJ< zs=A77c_pV6wx$?;LxC`&j1K7rh5gosZha83J$E}P@sgol0_?eVR%APBe$gX%*B{Wh zyY8F6Dp-Myc8rY5wS+2E$QWD;;S6>4a^8W0EhxIrP6J!~_Diz4g=1fC&$oj-6Z=`w zEUN-~?w*LlMP39rM6V~u$eOAdHYk`nBhSEFkq|MwT0dxyXDLb>*K*izDC|xyjs0S9 zuO=nKk`_v27*9`yucl2ap+kJL^@+X zFwP!uW^}l9HwlMHGcLK^`S<3k=Qlnohg@Atlh)>IIs&tykr5M?(GfuM-m!7Y~*?Zr$x~6B2IaZMTUf-frH%<_PmBYeeppUy#= zCw;6lp#A$idcY^rb`5IfGvFqSAja4#xb>|eO_aCbpR|b`;6Uq1s$>=-hQUj_8~MPm zbjsT|d||KUlU5lQFWc-+VzmIEocnHI(JRVtyQ@Ai3JCPQpsYB0AcCQy4v}uXWMfHI zhnZ&XTyM$LIK2^nb8MZgwj-o%G~C&RNgahYuhtw@gLQi<(pdZSScg+b7y@*%mKXMF zOM6SC_j^#wJn!xWz*S2r%Fu|GbAn#ZjJ-^ymus1Pl#ntd8K9(JMS$g0dO2w@D-Tv%XmcQ8BmIY4qn?&}Ls*zc;jdaL?H7#3ZHzg8UccmgH|qhM;H}!CZAYYD zlUm4(I8bgo*%S~a8Vz!q5&-OyxIGDrQm%jm0c&59a4^L7tFRX<_WW# z`=kOMLEZKo^8r56x9#v0D8A?W^0~oAIf=+=AnBrVH>#>Xc?kwQgh=pQ3w2=oFR{&M zA=RONjZUd1Y;FD089n4&=wC(@JGN_4*@xE1WKGXg%C#)V;PEJPn6BXT( zNw|i+WP=#vXz~v6wBpqkai^ph(p6?F0DN$gHh8z0QQ)^IeCpxFw(qNb>2W(%_laBW zMGw&}sngqK2dz(`J8Ps?w6xr3m;GT~f^%#-12J+5iqO21K8vII0ET&hzfzhJ33kah z-}{6|2k+PwHZ=2*>xH@)>=4d`3-|J?%snSdbI>&;Ze89pu?0PRiyg z?BSlC1{}J7j9PgF*n(zwP|<0M!CdH;I99oGHNKVul>!?2&?|ln?;}HO;+dmyj7{|C z0f!%te2nzxtosj;@HZ>gm@O*!8W098AmDl(C%-HeZoXO-S4n+@#SRt4JbZG9O%sL` z{v=W_KqyDz(XjQ-7c>#4`%H5!Xp|mSEUz+ncj}ZAlMJ3*7zzz&$L-wgTYQ`AyZoeM zp+MX|W6*%{7D7f?l>mFvwghSt>@;aHh`Hy>Zmo|DnXtXVk zuU$bYz240wD;vnVsILaKP&h|*8iUmnh9_ItU{QdlGrZ=RB!3LI1C#cZ;a2U!vXuUf zNkoWK%WL0#{Oz*tpZe<25p2>V@bBbksp?0wsm%euU`Nj(ygqa0%loRttBCUNZ*TRHKsfg z-RD1yUbhrrokU1>4UpnV`&ka z9y<#+K~&4@*Am12r;ifBO{}kc+KUdMb8OWv%e!*IzT$&CTwbW&%$)_@N~_@}bZlMG zJsz0h(N2N%I%$w%!V0?G8*5Q7;tP^u&h}|;9XbJd{}%RE`FVo)y&@ie)gQrm{LTAb z6!5xKts=*#an{4up9_v?y6A0ZChaP7?|U-pMfj4IxA#CJhb&lep)OPEQZqVOGP{>Z zWW=T7wEhf&h(kGtcgI8*E>qXbpQhgDod7=PdHk;MJfpbp*9;Az$b z{}x}$A=zH}s9s3jsZ?h@5>M%~$b<#Qw!Sd-Dk%u%DEoTT{blJeq%rWFO=BkS@((C|3ZOTfAL5tFhA&&>I!%)`*uFsnY`GQPy z8-BR%aQcD`ircTIR|T=`Jqi;Hiz662KXFCQ#ef4!627iH+_d!q?*@Ei^(R#`qa8N6kZy{=^8F3B~tScZM~^ z>EiU6@Z2MBw{1#DCc_SC?9vf(c<%Yo_lhdc1|wOVq2ss;3&VWA;d2Iud~8#7SLtbl zZmHHJ_Y+WL5-n{Kl(-SqC~ci}bF^}IT#v{vjnUMS4jpuTgH8o9;mTs>D1B~qUE&K4 zZ|~6ljM{7KM?bLkaqWY8Guasz&n)dn+a{AnJk6w`&9Mlf#XhcYe_tUn*!cqB830F@ z_?zX_(U0>7ObBud6Pmka(&nTE{sI%;H+ct0*Jgr00#L-~dqIWd{P^ReNSDoji)adz zY5OChsrU_aT?W`2!oQro;{#7(61@(!E>NHSu9iQq(S#XTmhhd3N*+%Bes4;glvIyh z)&0^uu^;P>%EKHj9m2^rrBZ7)`yn~|ZDp>;2X_m-s0->cWb?WS13qObtY%5d45wQ! zPIV|`IHRyWl|8Ep-%K6vvit64Z&fBATqO;Uj$1saW7a5c=H9cUl@dzuTZyg*1qU_| zI1gvZexE79AvJKb(e6F>#u{^TPBIW_l|%v|&(kR7Vs@t^C;ji!Q!v?sX4>%7PX9~4;XgKStyN!X8nNRPG_ZxyoGGA?44YqyePo!$KhdYZQxcpLKT0Q>P16GLw{ zKBgf^N(Dk8v_vd`OK%*QT1w_uErM1sm`uMuC3JqULiSt-DfKo@Yi!@Qg%5P0u%lB! zQTfU_k+bHLokaPG#Ty5lco2PNY~GV)Gqd2OB$vridQ{lC$Dc@f__q%to*|zGDh)N(fHQ#QTk)y zNy?=kr__@fh0jF$F)D zAzc69c%0cm)3Jl4glE~mZC|-Fub=YBK93%Ap_VjXoJS#J80~1~;BW;YpMGRudtG4m zm0@(KK`4I#DDu7_rST>m;?x=J@M`7m`nv9RDmr{M`m8Rt3xjs;M%*;;k}`fwEBC<- z9sKwldJt|Kc1~mk`M!bYA2^ar`_d=vg0;MBlw(Af9kCtsW+5{58fSXwgiotzsJ}g6 zgd|aF?C0d&P>W(Rp~YYx+Ny9|RMzm`ypwCyK%=I1Y8=tmB|cyedPdXFx-QmHnezwu z2m;OlsdRej+fvV;$Cx>wZ}^pyP&x~w?}`K25%+%&M39})4^C?cO%+52K8_!k^dH~W{NuXWe`P*@r9X6AX?!!sb|58oFC6VQFj#p zUSe;xyBvPhb4r945%hQ8J^voFNce~O0$ z(kOutJol=xmq@VuQRzJ;0QZI2DHYK;vx_7vB?I;N7kPhi%`H^)18SU#Rsy~;pRhuL zuZ=(FooTam8a*{kqOWv5)D4{$Nf>LIE7p5LPrZffA03K5>R}?A@XwOkx1n9TN{mgH z$uC+Ntfao7KvUU5EeRH;GKOKez08D^~}PR6yy6QxY5TP>2S ztJlwU`5khgAt}~3DROoGkQ;(&a>CY%@0oJ$L^)R!a$Ds7^VnbmvP%G47a8l@FO(&m9Yq;w2Xj$Bx$kbUbdL7|9ADS%#2wOhSUdTF z!%_G>z-PJ{LHF8TSt3)aH#jnXVc~~#x{oh`>mV6_XOerC)`aR@sQ*5~FqT|T?Ht=Y zzO4v{Ki;yLjPBYUJL9`D^&^G}_)rGv&xz>3?T{h5He>44-g&+y#B>v3eR1D4c#(E5 z49kcFNnh@b9FeRGs3IK^WGuw7IP61Vy(Ln>e1%BH`bFltIBeFJV9);>?1JX`p01egSGG$K znRp-JI_O*Y{WS>>cX|Eo25$GcXWNs`*y8X5qU-oT6er2pS9{9YgQGv)n)7h;1( zQ7e2YUx|GkY)HjsnL1D8bE>9LKT)6W59{+S@|YRx_Vsjk9Ju;)P!^j)qaG3pHj;An zs0hbSDBWF(bI7~OI=s&^(4$J27`+eC>XZ|C|OavlCQ156nAy5!iz`awrlD{q{ngX~l?wER4X zt_l*hKF+0Xv?E-S+rREqzD3w#UT7qzLbQsUJif```3rGGirl8u5kTa;Mo@YYw3S<& z9EF`et1nJ>;U2%dLiA$s`jM8-j&;V9;eYPFyijVm^p(`ZJwNk4_t5cj*n>8m895WR$V`EROL~o|JD@Y42};N$S8~E_dGAx%J#PXR92RWmLtJZW>!%03ODIg^*+JsS^DKW0(OYmCS*KC;@>I$&pYhS z9}E)$#k;n;dTp*P&?Cc@lcjR_^%VHRhb)iB-&Wxboh5%eHw zTUc;3VZj1{<$Hmg1oNE~d`mW!=#FvJUao5F#QZ%CSm+NCW5wQK^pUW*0S@!W!av8G zJcI%J{N#Sz9Fn3AbCgdwznlewFidNmO%J@tF}=#1SQ$sM$N z0Azf8EO0+vn+xtuRRfD$L1N~;;QjRYqVC81u>hg3-*c_TtB%Bm$atIOXBuX*=6z5X z%n$gZY%(OFpFI3s?9ITp>uiwGzGp*DA%nmbzMBC*LfUj+nDA3HRG{?)3#}vkZGVlS z+NO1zH)Qt)M@7rb$O!XbyZCPFNXIRMA)8|r1acJ3 zTGs0WCn^elb;%q}u3>o9=x}hP?fKeLvf|0~5k!ss3OU4ieiqG@P~Eh<`H&8-Sl6iq z$n7Uz)c8=TPuGoV@<~2ZADl1rfLliS>z3SW3io2~s(zpicA2Z``Mc0!MH`_9yIXRA zoP;xi(oUwbB#6&%>K+BGQrI15_tqFY41Z~V@g6BWSQ9mc@8obJ8@V^~;O}uUQVqt9 zRhBFqXV6dn<=1w(CT0QaCj6+gptP8F!7kKuoj-Uuy=w~lZ)b78YvbYXxP<4kuq4x$ z^Wt>pFzx+z5jSgtvW|UL|Il?-A2|=z)r+*23-Ut;^tR-MAgkO(-PAx4e>j&gG?AZj z)L8^7(2g`GH2OYcsH8XhI0$g#|DE!|`$n>W>&COYEGz|5m!Gd85`t1pitjj4|0?V^ z3qs5tjgRbDhx=(C*srmegd1Uan|m5lZphcv5+}0{sAkO0Y40!Y3N-W6!2-M(ACBw? zZxbJFqwY*$uuUW9R>|Oo7$isMC=(T;Vg5VZi~7|67%5sitZQ#tnFWlS9i+_@*h_zC zrb8+J?oEWxnkSiFAf)r=8flcZZIy~?U_3`xA%g(5xFCUdaL6O%t{&^TIjh8WJ04h~99qN?y7S7aDSVv3?Q-jTxl^SmBN`=Ya9%UgXH<6Hk(Cytc)U?z~@3+IG5U zO5MZ0-*w=EA3H@JY1G^C-(LC(+)0n+dGBLdE&tZ$fP?3ua36P zJw3$ImAIM@JBEuE)c%SJ!)H83-rMs!a2JXvTQs971tqt2!)2B}dx_|qq58R~3n{oe zE=L3sC@AvE$E*{w$S@**)9!D-NLJl;=zo?JREy%W{3p|@ic@P7R;M$A+W)xr$xp9J z+3xyg_8(Jy^Aw|qbbP4mqp@#w9aWo4z@N$He>q!k0AZon`MAu?62&~`*Jr)R{(fty zy;;>nwHdqCw?AT4|Am!N4`t*y5iCcoWuwKzADjK}zeF-z+F`aEgpn41re9!at!!zT zIQ5-+ga74$GZ)q3yNcPua@P*`kpiWXi3Zr>x5vAp=L3*3?tS(j)YLaU%AYq|$a~E_ zu=U(?^G&v9z?EOh_keVK{JF;mAI!?*U*&lCb!l;4rFnrtwd^Mcnv?yQaFPFSnJ}64 zx9P+e&C4lXP{<5@(GNy*vF9RLIA8M?Bvfen_a6aNmA|9clN z092=swY5}QT3T#eT=IaLvOj5+WxCQGyD?Twd+aSWR$>TcfAIy-dbCbECQ6$walwY?J$fE#ro6bwc`@$(hBO~}WjpPDkc#9$<7+*SBR_Hi7 z%c%Vv#p_84?Y-}_mn#P0jGbzU9`E$~X`=zFjf=TT%BL=Z%4aWZ*0uHnO#Sm{VBT6a z2u!GAefH7GxjisKLCM!CBR8HH^oFZ<3D%gbLo&$NGM%v#=X>+D5f~j zQJJ(}log4&j4;up3msM2{tt27KfSITsH2C65->B0hRE>5cMAg7&$rjm?1+d63#LD$ zQYgP(u~w%Z=>R7O$4b+e@2V7Sw9FVFWLLu+xSr zOKI}_+DuFS=OibL%lx8wMBc*wQFdL4EzFRvUoVh>MSJ@Q^U{3t{y~SM-?EX>w-g_# zaSJ;rza!@%ici_P7RQ4lXaf z>;5Z=xXB9%2?5cbkm6!)IyyQF1%KcqfB@Pf8{?%}Dr-de`0ZoG`qvh1sr#_kzgU3G zI1><{S0`iU^Ij@Gzk+5x)6!yDzds_}Tm1c#sy)*%tfGuU^GSVEZ(xXZE*@XV9ppmMa0FPPK78P^&sCaa#9>pLVo3{y}<7SRm3gs9#ipH>!5pyUK z@P_M$^`RHN#WM9SoR|u#8X`&!54HEXEf~6?Ug;w=Con(x?*H<|-!Af=0tg{$qTJjH z*RWb+TgHFo?y0S^T=ggU3G+3ZqQCLfUpUT9Gsd5^X*7LH%#4 z>+oAwu#*;olZ`rP_pW4oYcF4L(fsrl3xuT8-7vqxq0?Zdw8Dh>P@1X`F+U%NMJET; zPH@XcystO3t9Jin&_w8Mq;*`_Bg3z-_r^wA%aEFR9nN4f?27l5MiS)Wd zy4&HT)3|h~{q*le(Z8=nL}Hug3$=NVccv-9lzso`C@3@(8)(aOk)aeu&-3!w&cURG zpP$6Y$OvGUx!%5g%V#%r{}bJlV1n(~%*^P;VYv}qG)f3|9YF*04YW3?Vc@iJOtVC| zH?+Ht>-1*+8IhRkwjb8_o>P$h79fk^Wj$yckmb+?erd2|WdLAP(+7yqsBAWIp9t0J zL^MiYIw7|D@1;lx-?kT49C_JkJ{`>+rVQJUi0q`Pa${Ek;LQ?gRdlT%G6gyr%pPx5Rl@|2;E%Qf<9D*gclc*HwDdl*_?M99Kf4ZdM%U zv|BW*S_yj5-=AO{zIbA4ZTrxL?3uQytgcZNh~Q2vm*xI1*lJXEVVR zGu3vK+D81pGXiOvbXEUi&YeQvhr@CjGrWTeaWvw|48I(RLSMY#sg^|1BCf(w9Y0}> zQKP5}qBxFG#^(f)ik6igY!64fKi@``-7Y*!mV?|U5Ad}{Paiq2n^}~4ZdWbbLzMF} zK-Z~YJ4ut1$aXnO+KQ65Dkn6+W7Uf`(Kyp*;kocQOU!_lYk>%+{CVzX9HSPVvhs08 z-i!N^aPc4tv z9)=Q6;_cv$+i@4v?80oyE=$V&YpBfpwkVpr!gIY}yfl=!9_e22uaAtgl#)5BV%rEgI)+)~@S^Ns-QpF}Zl4c#!dw*%k4b0AK(lizH5 za?C*gW&zEdFW<80P?Y~{CgwFpL7An)K&lOY){BTX{df~vhTyXIw;~AvHmF|E^tLvM z7b{akWZp1Ahv9P2;u?A05AtvyNF5}o9%B_Q)6%!~!#p-KtRPT5>=sU2N{aqaeW=JK zKGnOte4@ogDw&ByNIQJ6Ax48=2NESC4eb6xg3k9#ZQj4;>S$5%h@^ppyq_Z!y=;4M z;s%772HGtI0`fi&^iNLe`p3S$5cqSb{&!Znejgbg85wB?F4|ga(Xai3_4?^z zGniQR90faSPYAK?$e9xo$|%}Rv^%ER{ZuD3psAA33VN88HAD32-ddZJ>@9RZ1Tod^ zFj)^g3wtjznFTHU6YIyj+E_G#Bxf#YbUyI5aaLl#OEz;Kcy_&lSe*adyYrEPqd0iS z_Gi(Cdb%d&P$oVTHpMgXC_5ReR%Mnm%Ehm&K-DemRwOlP!H-ou)))NGYnq@|bFYz? zRIznFw9ZB7i(7k8X+Jodd7^ub_iehVcW0z5UOY?Px)Sn4}|^+hUSTPm!xqac?T{1u5rv;CVX zg1}-y{3Vk;L=d+|5kG!8lwccMhLQ}oB0@c&1qXLEeL=s=YRaR;+^bHP%Ha1GB zW=Rv|mXo-T5mMegc>%ZHTk(hbKyKMddvz=BJlE&oEF7T#MM$j9`8ai4i`zcLgO}xa ztPtsIB%*41U#*6QpS$^aT4x?$a)ZogsU0B8~242lv#Kfaha zYO9%OU}gvpRr{#17b>f5qvKJd@cYgEgu+}B(qNo7(R{b>E=-p;bwx|zJW`PiTQMM$ z#Aq;ea0m(^d)#evp|f&3`n3mPpddb*@^s9OevMgIiPWP~i-EqcbjEG%h_jjwW7g$U@fZCHpq~>`h_Sz0Geicl414`CG$8 zK|WKt+Y?%MS1Nr^Ux$=`N52ewvtL~(zt(j7cEO7i1|b}z0ZnZEmWwZWR#b#|uE2Mf zf0>8;{Uf+t(=DhZJ^3EW$t^A|y#<^5j}(46mc+BYc}T8e)LTINv7PtXYXnwd56*UH zEoJWBmG6`{PTyKxy|=zKT9_>9zSNF03CvtNX7Rq5Sp0Cj+exnlsk7seCM?@|83lIF zkp2w}T5L|8Y5fO#wiq#YSVe1pFK*k#93p5=B1@n>NEkZHwVac>O~$=Cm|gTf?Fe>B z(mhcUAM_4u#islslHF{y{X_b&Cj0(8HlBx7QIL?Qwe)S0#n0T1l@KYDho;kzHbv}~ zx+P-a?e2$G$WQHm?&Uw`>YE#YOS8DJ5D3^4K;hyJGc!hYb@d}I<>pvTyFP zy1Jz#A_2zWm5_x{v`M8rZ4lPN!_ntvdF?ed0ntWP6N;P5N zbk5z{+9I&xJYsy|#Y4C=8S$>@6yEHed-LYaZeGUZOQwHJzW%IWSAI~~vGMR|`HZXO z?q1hLd4<2Q&3o-yhG?D3mqU+0@9fg~c0y)Np8E0)Ds8fxkNb*eGHDaM zuQD3=S5AHS8D$Cn0iXL5T*Kt1t017SRUqX@^u89&l%92LNU$q7lIGjk`| z@`cdEt;Sb`HUamFHd!oIs)tNpU7U1iM&a zw5jqzN`^*v@i|DOY}H*=s1S6BGStxKk6M4s_{$DQZ_Bj@Ntm4?DuvthUEr=?4Pm(# z%Sp5DT<)6blQ4!a4LZJ;c5!0i#?J;aoYihO6svTfo03<5;^Y^qGxpiG@vYoKXrj+i zA=B7z3A32ael2HH&!s2%AJofSvhZ^-SrVw5w-8uIPE1UE{63Y=x3jQtC%#W1&db|d z{PJWgw5W(nR9w8*>Ez@@U=o&}j{~F+&3_%6pLR%sQ@`ab6tcHmIgC}OPVkC~ZX}{Uyw4cn zC^yb~^6+`Is1jbNy;X-A##}$G^$J%McTqr;X6B#Z{`(KZ_j%2w*VNmBy{!}P zo0ynAxL0OmJ*(V_=RhQHMKm^#w{vQ8vM1t->5cKRl%(W}5uI_F$s3hRkO8Q~obSFI zNM|oRgL`4MVx3Y=c(4(6LE`OVCs0E#jz&1YzyD+ItK^{%x;r2N0C}8WiN8)E+Xn`( zO(iT%-1dT-7}g4qA)8M|MnpblFD6fZs2VG~z1Nsc+VlJ3(0K|JkPqyx*9;oVi`=Qr z3A#&_W~rK!H@S?oqz3h%u=;`-+v9G*uuO;PlP87)}@?vBn`FuY@=!#X? zB&#W3=XCqIVA^^UhQx%@HrR1E7JQ@&VX>^7!w6!HR(d7EZT)MxoVCz=9@!0Qvl0~w z+CR(mZ$H$P?vkDZWVas+UExtVPrIIru|*ZA6roIEViT$yoD%M4G~inxD`;rM+d}(IRJ=Uz zH;fvk6~vY8{?bVZt5&+bTQ7K3IDNOT>p~ON8+LKO4neR;XVZgg?0RODPgY{Tz>94tM*7-6D#O(6uXMhJyB{H znz8>ph|Xu70Zq~rtZL(}BXR8xMGB^eYC6+6r2pgOAx;AogVB$qJ3lLQFD3hbB5B23JRE~JJYQ3=N)D@ftVv8DRhg;KZMn)@|X5lv;y;b%Q#;v zuAi^LS!5o1YQ}H1_;D=(1BfrM|0QWzT>jTEoP*>u_nC z*<279QtgcA&2F{-*dH2{MMYRxg`~JUGBE+LlV1kFJ6#w z6&I<$&_Y)dQQN*a^gFI|quVx^dFJ>1meyGHtNSB;O^Ug1f)$~?Ig%S0-#P6FiXwi2 z{~QfSh&EhZZs}CpQWq2!lF-s}LSD3=ZBH_H0ZNAX(hsNogFVKWM);wU^E|K}d$fY} z#HE1v_9}rAkre6pXC{jxA{y(+R{}!0O}!r_o2uxvwO`BnJLlVayxcLWgVpKU4L^Mn z6GpPw8}L6nHF?ZVplj^4$bO%OW@SxegQBjKV<5E9;SNWFdEyiO_B53!fw_riyvtUX zz2^-HauxH>4B5@WE~W$XZ&aBf!ove(F+||IcQ@;ZWo_Nu+zt<}yUWt>7544PBsLLs zjU(UA?}~Les~19|ZlC08ayJVqPhiylqO-IrQ?V=cM@ZHjdJpYdo3pM%kf`j z;vKnz-Py#_hMn`A@@rz-uwhKL2R7r`E1dL(?PvN%L^Xl-uk5XXE-E2mi7;r@sSkdk z08tyyIfW3Ho--s|C&8N%X+bG&*kf~6J^rug1%EIyihQ03pASI!t*oq=0M%S)nBBCn z)*g!d)sR9Q{0x;III={OQmeDbF={p)@mXhwfv&x}1K^vq3S>>bC27$;`YSeHGT`wK|w*hBdw zUf#YubL^b(Z|autr(%BVWBMcT2EufAwgL#{4($N|KrkL<&{DiM3S5JLJ0G(W6mM+AS}=dWK2wLO#a=76B6#vZSvI?Hs9cYwb$d$j$4 z{L|Nsw$P`M*)FfK@eh4>U9%N;j94j+j}OX%C|E{rXUe+g)4+h-C*Ec#T6Xp=930J4 z##_5P*jbrI8}?rx*g1)95+t(qs%r8D2O9#hrmk%% zkgA>hd>u6VxwP*ObY@`b~TzTx(07&m^z1JcT=YujRd?F$u9bMg?0tAp1mUD9xii?X|*xQSVizC%- z3;>6xL&VaOS&9k^os_o*4;CAzAnOj936N2rn$oNCK;G}~r>`Grd|@KmsTSVSjrL~W z-Q{g=2BDrZcjcJ7qpN$U+B_qbgd1)r5nf=t02l*x`Z5`QR@G>^c9HzA*9OZSFwb9c zD%OG;HF`6Oit1D=I5$0NaCi;%1BR&OCN1bUv9QdR+QS7VjoX)(mK?_oJ+hTz7(kaK zrD#e9aLe9>hAxZ1E~2*aa=c-AOT47#80hFL7k-z=u}4ocC3R0bB%u`CacOy*sBY$% z?t-gtFZ<(MhE9e-D1djCXu}tR!%imFJY_CQ`&P=&Q8dBlXhrm=oX$b zedW>@3<^CRkE3^`G0c&{b!;~458;L|=K!dC!9u_nXH*PdG!id~%l{TE)lcN5NjAj?B{R8^?9Fr{qJUapILH6RJMSAVmBjY@ys4+ zIHnpB2TC~?GkF%)#Sp4L8`)h>*kN+bmdm-`I1DlVhla8ekQ#=ABR^;bFquV zpt@t34;#Rl0GPc-X(9)I%_YLQcQZsjUaatEOf{-D=JMV9K`&1A%+(XaOs(Lc@MY-7 zSaZJSr;R)>2qFYxmN&9h64IEhL@^0lnx&;TN=k0SR7~f>N6mKa&+?n%RBDal~>0+u2 z5STfGMa?(Su&T+(Wvu@NN+2QbLB^Op`|Xi}TvuCpFFZJ|w46WA(0YfJxi_YZS^686 z^IqAG8vj>auG=^BnKdMj`Qr7sCu2t0ZpwPhtFUjS0#?p&EK<=DGw2+Vt0DA-!w_osc*kQJ57crwgp3~{2-}3lFSM7~1oyjm9>;_YS?zZ= zoE=Q=NlVs0O)X}Csk-y)9FFag{I0cjaDwhrzoCrd}Q0kuF2@3*4wKR2flr~Y)YYnh0!h=|t8 z*T2d@G5{z+7Xb<~vLK1wT8wK_c>?>3l>=Z|YXUrzQ-o|NK+(+#Cu31*22RWT0G;EN zDav!YME9UFSOH4WQ-{g_HASvHiCaHJWZw5hr-CgIXBRk~FptTg=3S#$4|C#P#|1TU zZMvN8(fVN5HD$f4n(phj`(@Ac=@lG#Yr|LWDtN6K(d7%*OoLUEH%xWkggAsi*aS6< z9_D?-v^zGfR=r`Jo;HDM2gA&r{QatK<$lfSV)EQCMw4Q7=4E0-0}YESH>i%(7CzFv z?jQOj45HSal<;aX#d+_cBx1kKSzmO|K5}c%+USv&G^h5v=z7{C2ELfYX^bPsv)X5( zHAciV0;}5xP`fjQ7EO9p5uHnZi-J+?t&NmR!^s@S4$cC999`-pDsR7HQu02rVeNUUliXZ{RpXlwy6+SE>f$QolnX z;ii@+``krX@+P}!0i9`EMlG-=t!lTy<;m4$;vubF|K3o~rQauy1Vxz3ne=N%Hw*f({y|c5`LZHQj?;5h9tE)Tl-K{V(F(IM3 zs|y>5u7W;Atz>3uYBx!n2M*<%YaF&wI9qvAAcPgh`zXgn|ongR;R?I_3 zCnf#Gk87I^i2pfSp;mF66UlV7U0US5yLZ$7@5x5gieB?TM@BU0#GK`$$-AyMisd-n z(86iR%9@F)u#IHYTe&q2WOXVT9J_Yz#EU#2h<2Wm=Bh9ySZ-|D z6#H;`)8<);u*1#VgXc2W2u2YMdPG-$n;%(7^Ym|94w%+n#9XY$@|^yFa^v{9`HY_j zb3qN~aj{EN@v-9$eQ>HrXpP!WzA9MAVA-+EnfYlw^uT*@Rk~$1;x~pj8(i;`J+M9Y z))w2F->hB~JbJ%nA_B*pfxN_)yTocZD!g~f**VZkbzu3Cg?bBh$+t@qKDb$ZE_L+2 zL~(s1{C$t|{@6GEUXjmRE87^xRvCwYe>T6}YQDenOOW{Y7J6aQxV#PCAo0DcG23GY z!Il8>D})t|~Nc}(MQgc*`^YR{PZI4@54gGe# z_6P!y8$S1K9cmXhx5V&caLNVJwtF!QQr;%#`-|Wtn(X7$U^STO92;0#%FD&YWnyPX zkUM-``+BJ=R|PzXB!7HX&67kW-URvbgEsVm`DO14qAirDkDHfQjpYP7u{&G8>PbRb z-rg=hN#Vnw^?71#xP%uf&j*gAysryf|9eJI;sR7Hj=TcE44*>l(!|>UDa6ZsD9T9mGDZH?@OHjyY%*4xSPj9E3Sx`kcr&K9MM4|>Us zWDdNS#t8pS)KWgVL@cxMeoO6{hn?Tiv!+zv(}0Qh_JKTiuwqnf)~g- z@0UEi1c3veDKEWy-Y4WDhMv$6q;&e-vj>Jtsq^paZb`AijAMFW;eis7-IBEmQHi;V z4WpU15G!ox{qvv)&mPUln^0GdzK zI$=_@5@J|M$0QnuHC6b*F}0*6=ovR_zonBPH*C&7TBcX{A$xEoN&PN-9*-o@gLbuU z7`a(f4F$S82LIM%;`x&P34fDL__~#W=RJ4RZ)MxYSqoc9PKO_?Oij|frWsQX&%MSQ zU*1a^jA`(+^c#OAdDzKn)#-q+xW`bxgB#bXOj@>fG3b={+*NW>&_Hp}G1@3>UEjE- zmcnw^QV_fPJH^Qf@pM*e|3Tnyt5OB9d9z_>-7~8H%z4l=Zq?;me(3cBxBl(cE`E+V zF=La17DF?(vdF?lzT)R!VZB+x3!|lK9P_pbHN_6+3LHo4CZlIPc_cDhHK-7er2j}A zHqM_D;ZjmkmK9BT?eile?^05z>ZoMt&Q4E5KqYIyModA$6659R`LUn?7g!NFy1L4{ zxm86%Wc;s-eexP!lYCCuIfYeTmngWKF-xeXqgZ{!77W=xk99pr<%)QSlXf76YT-N%NHVd z%OQL@Gc2S57ciLVFycao55py6Z?g>$zyypo;$g4wIHP^raVUhKs%eE5h{55ff> zcb<`%!FK01zPIg5eAOJU^Hcn>|2Aon=c2#-sdGq)WqQLJyc{uWx!!LRs*5s+Rhjy!GM>{^h{Ip5%*Dy zAA@nF*q2cj3MT`ME`Q()aC$G)eQ6_AUsk8p$pD|Bv461PeqNtR?B{Vp`KCnCo$F z(9{3mPhH50_|+@-L1j$^Pt8ZjJSUrBb&bOC;qYbh!C1ujv{<<@AJfs1_P*v9daRhN zKpg(zTRTQUGg4U#9WnuLHQW-2&j!a24z3JFHj%{Cxsmk0v6oB6%Uw~a+o^@Q>F{=$ znmbig`wXPTlBYN2*j^+?lVf*(@V#2YG50^>x8JwNhZYHpq_x0su28)x=jfO81XZtv(MH> zX=5Ni=^F;7dI{{;#;MH7YeD-Y1AHs@7TT=VOn!dyDLYQPA11_@$!N|uBzepI8w&f| z!^FWe%N`xnWn1laJ@|dywBf)~p!cKPLc0>50=-XvLe|+MZ4BH~|1hgP$|K&65Ld5z zw-{!f?=9*G@X}<8V>nlr3dFo9u^bRAER#~A-l7YijHxy%k)(}n>D^LKjueUsUuW$c zY*`W+Uw&p(CB7zEJ>XcaxrSOKkn|nAJ9D%zvGxS? zBGWz|7er()-Cf@ctW3{yhNG$(6qmFl*Hy+8qs0pS8oy3($Dw%Q4g}|YR{O8vfzm6_X+JkaYV^YeG%sE-(wvWn!Zi?ijt`wE-n zap~8C!zHJUE!(DLoCWk!Jgun8iDNyjVKBZo}Uj6Mg z@@Ky#adCG~f}$Z12n$R92azP}VdgpBs6aG~m9bnUBHiEfukPnmRFGabJy7$gcQ|A# zbf6oOWp&3Jj@|MrpB0OUD&qLqm70>l+d6Y*zR?8NK8s(m`uC;okMwbv*iK5-6f*Ic z;SEW3eL4J=iHIYY8G1&-N1U%QNJ@$4?Kjl$sb%Q=qh&3}j1Vb0civJ~K*GwGF&00m z5AZy04e(&lCNjwC?d7Oa03ZG4{rd)eW}SqxkVy8k=nxSwojxLXBqjry=_SuzX1P<4 z{QdoNO}9f<-};@q1$w+#qA@P*DnID9BP)4#0S9RfVby&pqFAPBZYQ$ATxM2)5 zT~ZG4Z)F)TUoFtIOUYpK?g+(L^CS0+%}rCBZR?!35f-P|+TEMT*TxxXk^Vd<2l$v_ zK6^L~$A*PjLD&gLRyT8A?s3+xd#ygf;%&j^RcO0sNw9`EkaJn`ff~gu1_g993%W_M zNL4=}P;EKnWoVJDr}^Y}CY~iGXF`lqPY2N9yyJA)Cvr?c)ait$De zG3Zy3@=GObrG7Gqq1lPNBx&y(C{^>s|Em_(LFE# z>;YvqxB4&C%^F1Q&CQw3!^6WjrfW(Y@MLx5Wzu`QLqlsgRVfo&<~r4-cl#9^GMA!n z?I`5#23XRFy6&;+3%$k^on_P0b0wlelNrX}!OQBqciKkyAjr?cOva@7cf;x9KN$5* z(&Hv7zx7w1`dW;y&1u7tG(_^Vel;rFA^@P!_aSEA&7fLk!(&5=P>=;nu9UDbkcTQ3 znUNS{LjCB`HX{7+SecK>%3}+NU>4H_ymXT7o4t`va2s=K2IR*45R;47?qIMMuX#hJ>Yx?OwxC^vu^UUwW6# z8mQvmzrVAbGwbXNAVU@0Yova|(yklCpsm6@2!%r9%aabw=1IxGCvp_MqIv@Dd+*Cf zuHbb~#L^5E_3?qrx2c8}-%yj|^8>2+F^Ywo60BM5@JYL1KO)=@_-K;^tNpx1kea4^d($<8A;2gnzxpgXWcsO5sj%@a96{3;p@H zD&x?%LA3h;M2%tE#!;acoHl$7-=Ti&xJ&I#cGA^5iEkW?ZnzA#IheRaqq(E;*9J7j zct`$cSLCg6i8D-<2wO?X%O(U**eApJp6WieEl<5Jaloxq%{9_6@#H)BG1U018a-E- z+kSi|D|hktR$mR&@oO@z@B3HI_Y++Io8r87F>F85$uW(e;+zJ2qbT>XPW^rK#{q-I zg7w~Fdd`*R<43(D>#r7vile5GmwfUkE;p=S5O)jVnQMQI;WvvlGMfEgMZy;1jF*OSHnzTuCBsB z=0iehp3J4o6!RlEwU4EB9~V1cx?#Zm6N~9(?xBJE93klYIRXQhAO9V=)^Imx%RFvL@WYY&tgG z>e;FEt@M}Cm7)DTV!Z)UBu7g&I-Wkae5VR;T#inC2#gmBH4C;G^80dYQb#kP_5EE_Pd?CZ|awO!{NLI6)4u;fnqHRy{W8*+y|rJ=%*u> zl9#IlL|)YgzqB6`25m~W6k7W{ie_Hs>n=LwUp*cB{>u+53F0%94bGPs{D$sYn{U?Y z`cOm#T7&af*OKV?p<@tc=gX z(z2&^1L_F?gLKShOX*6HQ79Jf?ldS6y+) z9KB;*zyW8vb|syof=^Pki8 zN9Wn;1ox=X*Dr6|o?9q=RoAS2c8|AfVc=>(Zo%HNXk4>K+ zbNi_@HW2qCqc+xWa)Aj#DMwvIyn5vRi~6+uQXjE!P_Gix{nUqbP8Uh#tM7Jam4YVG z4{wU;(OqhylIG6WZ$L+wlmhm(ljpB8YN2CIG-eQkv&<}{4%c6Qz^kZya2YBSY<$;i zF0hi9()<9M`}e}Ir++``yWFU)S4Un3+u!B(Ckn=ie_^mq{KacuQ<8yWCgH={3&M_1 z?Cv&&n)ht3lk8->>x-@Hd9#lns;%m+puZKa6!Ta&7qS<=`tHdmAA5B~EhxMk+!Y{z zVzBG`i$OkNxHjLR`68gR?2LTo2(jw#{ZE8J-Z!$*vno9x#BDQN<6xY+%^P>Ba0SMp z5K+fFhet=2W&yy2%ll+An2c4mxvvk;yOF`)-#-lOWodZ}U`(ihiQ3+_)zJrLXuXLQ z9|B&#&i9oxHa5Oi4t%7d(w^Zl7oI8Q(`(Maz~DR_cx`6g!-2Z?6vo4DKcS9NtkY@k z=)lA#Vvq-0W;t*&)ja_lEfFLDQ7&1-3G7nhp&V1tFVqy)-|=IyX!bq&J3 zgDyg|gY$<2Kg1b)x@+GN0&!6JLq#2an$1U%RRYI({Iz%Jk~um5%T3m0k%hj!LFH}j z<7lc|R$4o(n*B=iOV93o#Eb51H4*ZhtzP~-&)X4N@BB>bYl#0nF$h=ZTW#Sxb!BVm z0nBz&mjRyezMCrv;q}ycD!m@btroVPmJbTsuTB#pMWmm;?^(_?r!-6YFbG3J0y;im zVCKE9d$}s!TR~cOl_>Pc-py=+go5-Cx;(1|855-W&ecs_1^U|u*>qAWhri`4o{ zs37k@_m+Z^PtLGM12q*D;xFoqHC8CiZ<0{1NAzAXEgIk5g^H!8r<;HvjNjMixI~?X z!#`GyT%%Fr)_;Dk@>un^+rKfs&Y`NGf6YpfqvVmhhG%H^{{^8ElaS~m@8K?t`+Z3r z!_p?rgoVU-NIYDBGtJ{uMzO1^t00b1SisdFTW#vk{dp_nR(F@-pwswa+T68w&Hba4 z$Ta6N)GLPbw11Wwc{bPJ0p}*wukqpV$;ruA*4A-2s~~j(w0P|3rGmlTO(^aKDC7ma zjN1VVfO|PHF|n+&GGV8(^1hg{i_5pj_4W0(xjCcg;`{=I2lgb}Mf5uNk8mddBr}+7 zM}c-`KB@{Xi z+MDok9Hc`6c3~vS2GP0GL-|x2)YThvT(E@-7NyIP6 zSacIpQ$D@~s1P<@-Y($aVL9K@@*w&Mc-BGDrD)-A4M{S&8qTZvlXe|pEWC1!H-^JX)qeuxZNZNq)*~-;>G?iT#-M>KZ zD!Y3$fUFWk^{dR!1qac28e}@CXREflr7V&vZXEexgwm^!a&hu$qIFp#wbOlJ>Murq z!_$qlu6p-0l79RL&^?D|BROxzSWhnk6dFAWH-OQvl^ORaBEvA_eOlt6^_AVLYxc$O zZ)h>^io1^w4(CMU4c*~9wz*Fu78)P_D^=n~*pbii#+%VX z?Y;=)!NEbw$&iMqxWvMB3?B^zw;K|-KZKs<5d7XdHBev&K5e*v01E0hz~@}(f5E(6 zVL;{#f$$Ye?#?AyuhG~Z*RyuwV2&Y&^JdR-o~hM~d=i6yG6D>fe~CE&HMIW?lOs+% z){jHza~uVnPFhj%o86R@l(Y!;2S?P@JP5$KbwP2FOpoVH__}eCty5JtgBq&=NBtrP z%P}%bX%0;-fV#BGgr=>n4KNZ<2QETo5NLf#+yFC;>3?-$g-^vN%Y$_ufZ9VX4oK|D z4`xcK>*;ZHeNbT$L+Lv-26sUM=oE9+PYVkRSKY2%y65Ok`acK>%q3QWg$>OYl>6ZF z6NCsmAVz{>U@QgPkiVeg|0w*$#bZbImY12y&J>vZ0G9i0P>|(A*n~V`hxC$H|gpxufh1TJzwb+MJjyF%+Yn2_tqUU~_~Wa6#q381(|Uh_CuCUDn6BtL?&U zUOqZvXE`$_{R2YJ69PU$1Q|kgSy0k{d}8p6JJ-vfn{*x$}m z5_QJYBJDeM1njDEO-f&yS6r zs{8on}{C`_|XoYWQIW=wsqcHLR=2O1st4|P=;BCW6MNS=QssDIWL z0Ed}dn4jOWQ!~#~cuYx7-eZ9Z3BgMJ6tGoX)7yUdD+TFOMg>h+ysw$GIn;XO;~ zI@n)Q&}kB-@fNxkhWhUpOgi>QR$^jshJ;72d_Z})#UXh7=E%zvJ}P{GiaPEn2d<=E znR(s3BO2o^9sShzfNBVIZs}uXdCeHM z8Sy18`BS#8fpZnDeGsMJ@wGr+`)lF-GrywkXw``X@{~uv*9TsKRy??79NSB0kC?Fx-rF2OM(j_6?-CfcG3Q__p-QC?G z-QCjN%>4FvKXJ$Nec$;*XATwTxME*xuXUcEvy+FLyZghjNHDsXrz0G~DTYYw{ll|! z|B84tU>XbsKEc+W9wac(*_yB88W|ZetngNB@CMX()Y|Vt;+?2nL)pGy$qf%q{es9< zw9oC@U+?164^!7xV#MAs<B=q@xh zHTyo?W(YR{U7WTy$?@^A&004W@K1EFf%kTX#>Rat9UUEZiaz9#9GslJ3FLTiFu}2* z7br6rKxRz7sF#-@EZz0`)Kpn@>}zc<0x%D8$0uTBrenpgzml2(r1FO-s97I0e zXs6{Bj=`SflOW_P0Y)it;P}7p`dXQ{`v)*%ey25f{DxjBDk`#G=@K6dX9g3~<2?YT zx0bFhi9yA;Zv#pAoVv|m7g$^P6SiWYcHqA|9kuIcteSgpKq|1jvFn@0Y27yVd=%?3 zLBKnI${{XVf+SAMkIwLF)ixAB9*zlA5zk~k0ShM?(449iU2hC8^xWaaW(Be1uWiAu z2$-JB(a|kjy`C6FoIBm(!i+(?gk)3MLOBp+0kA41_tYX_psz;WkrD!&=x3T zVKLnS-ikJF7*H|WSCe@ikqZk8ZES3!#~~oP2MKg9l~q;y_>e%(bZ?1%_*PgTe8#o6 zn_F%8B13y?=%+f$a>TF%KK~>cyS=d&73&*P`}i~TEsIDo82pimRhKREExp97pQs#1 zXI(Z%pXx0v9!@`XCid7gB5qixkR{tfYfyQjl=`7)!R?88Y(2|WkIK=E7V+)1cKxko zZnE@9utCemnh<0ge;v<|nH6{sNbqDy#~e@z)Kc&&0ab!Gx3~mqKvnFeKXQVZOth^Y zVkH@)uavk(iJjOMkP?mbo%JuO5SS}|tRT~@dX}Cq6_L|#e-WIOiLMcWZNl23pzf3D zUP(!jx5|WNXy>iUK^pZl!MEj8j#|wIM|;lj3n_c9ddMNU8&B>X+dtf&WAT91Ek%6+ zY;ir?cVJgjs^0|0t@(sZoH1KW=P*TWPtPkUsZiOe#d=pZP+)+_J5UJ~JKuQmpN{bx zW~H?LV5-WAdO4Zf5PMV6cz^IG$Cz3kta=5On0eIj?(oIXV^YOx$M%8{8_AAO{;D@{ z_yINEx{);^b6@kMx>8d@C8cCUUX}69v71hnav>7@_Fn7RMKxn?>hIoNk+bd)50`z$ z5JtRdWpSbW@oq8L}}A0;Dg9aUt0`K2~%%6ae} z5kj2<4RHQ*XT_{VaLl6`uMSqi6ui+!qSn)m)csGE>R8N`zp_^05u$LIr29^EV(B!9 z3^nYMkMO$e*IXV`s;~e-+pqk|yS^upb>e3t&IS}KQMah;vBr}eE?C!SHoiHu=u-4) z!krj-HfCL2y_I+zlhuOL4t52+U0t-5DacILUp=4|KPCRQ@J~uS-3!~k{QmtrkU7WV z9s`#|Fi53_?Kpw6eaNihIAJU7!!=>VhU`dF_76b&V8VyvuH#J~HW4;*#eEaYy0pB} z^B{JzXK+xiad1y;XR_|bK1c&R;d=+-=a|%53Kt7Pw&zKLZndZ4Y#e*;{PBds9>NhT zG(xp+-%WdCIvZE;_*e(L< zA|lwZCrPjPNZdz|%-!n}FUh%`>gW(DZu>5-scfQn-zsbb&XiVFg6b(U&I6Knw35wL zx}H%a?%2@@E|@(v)Gi1v^kj#YLpGF1uEz#3h(Qr#51jkxzTIBxdem{?9o=BZxIEQP zTvSce#gGVlvnwye<{sR>1}QYV2NcSFvFSTB7n&Fz_XO&FTMxXWR_4y3uEo0ou|0o} zhHWYZQ(|~T#I}hE73%BB@$nuy$i&11Yl+s=n=mh+ebQqlz{JG#fz|Nv-ehEC>gqbg zIH6F|`G%#PQItv*r{YOISS&_qZj%}&dG7V*`;ER_h?UN~?XlVqw}%eTVNSdI8qx*W zNNxdxP?XdUMc_o`N{+6m>>1PhAi&fu+lWYtqX@5Hga ztRDBBIbc=zwwp5V*Y7*WI!4RapbJl3ognhY^lJL47_1?s^>69R<6IQnh_~HSg{NZZ z#qsp@@j}y#|Ixl^#9D+sd{FW5d3PbEB^)84p~5?)g6w^3T2b-$Pf%ZP(4rc3chf41 z(-{+5S9ZiWeBY3}!c4o{7wgAOx<0m8^Bpb*z4nwCTAea%;YF7sBoCkLqZ}qM~&Zb~$N1Ztk+>d24=)8c<2< zK98E+G>5476LFd4f(;e2__})iiP23THLBN|b~Pf#8$>O{*H4M9z47lLb8h=p%iHcP zDCQeiv>v3_*llsP`X23RLLx;WEZZ%WfkL&|y4G_cMT=@7Vg1s7y-UZ8LIb>F%5~qo z@dGtkpD1{rmYDc_6%-b%pe=z60ed+U6O-s9ZWU$arx%Q?9o!{)FHZwMASV(BeA(u$ zuI4fLSt+`^=qdUF`>QS~*g^RwW!XW0^JZSzK?23!^?G{heQqRy&P?-KLitPWn$Uk~ zPEY^~0a9v}zH~Ls7rDJwt~$+eb&eqY{&2x9os>`jJGxIN-#oRd67cY${?=L@iuLm6Z9TRJ=MEp}EhQ{JNGSGo$*^ zIHwl@=du&(NxAU&Fxip84>b)M<@C-=^mo7+N~zzHc*WA27? zVqAT!K|}+8UWe93cd?u`n(?h3Bcru-*)_3%C#hu9#>aiMk1DT)lutK{1#s@>z1yHBuT*t&7Ly74o^&Wels{DZimHP=+O z$h-8w2pL_}vKQR$B&tR*il{YeNMcxO=4NZ3W>&j{4XOTq+O&s-?e?M9$#WM>FYkH~ z2v%8ap|1Q@tL%FtQL>2jEBirl<@ky_&&}ibo3`caL;J1SETa6M{1PlxC|b9*nJx#M z~}g6P@b5r{jdJw+6GqX6@elLv@R~w8HZb5*-alcLOa{!W&Mhd7tHG1TOn(1 zyS;BQ{#G%~!voOC?D zYI$_-=v%3r=-d{?Jza|a70$p8TGW<2cW_T$o`@g}{x@Wbw4lhB3^6lxKNC~S7*(G->>V;3`%G1Uh2yT7-s!0BH6aM$NUXM;4l{U6~ zb45xd+n%?RTp{nAhYldL1wCxZ*~VPZXn-&3OK|0*Nr!y-cyreK*^tI0udLW;b@7O6 z-Hme{k({m@$0?GRop{RkF^gKtthDjNII^~xA{~X))eA{B)K(iZ#3?mR^35$BEzihW zq1|AKmTBNnl2y0MTZ5!;aSo9_(-eF;E^J_Onazoe)7`>b#z{dT_mg#CXYO zt%Y6FjrFq74E}`cZ1iOj&4B&EOlYeTubRVT#`WP~S(5>K*)pFuzgD?X_ucuTj!Y>Wze`lJpAio^q{bUGa(J>_c1ufH&!(LOe>>TU zDzJXNAJqZuQW&{O{6HZfH-;#O)0$5Ox+irDN&j5TnS-ZtKlZ4ZzrhWF2SWzaF*@UB z{nEMC^t&*EZCj2zenS>Mx8&LSlm+9QGU7JJ^)r5^3f4dLJ~JwP3k` z+V1qGgqd*b!^xkion~ilz4p#a0hh*^9?vUdsRmi`pyAGw5N*#$Ty7T^E>=H$x!R*WZ0Ukyu7?R!yDyo{P>7J)reVByOmiC0EYR-()0*bFW>>rL{bBr*&;*k(m%b7> zMD%WC2<5`HN6f9fv3B$iF|MR@5K&dBcYtJsQ1z%k1^-*8)x8FsWR1Z$k%U$E`KXaxH8;$niY}*7|jJ+CvB&*%^ncDMYV;8 zw)AENm7P*3F&hZeYB|2`j?@f}ny`5FrsRIHZAWy^1!b=YiR2hH)$xc|dyUwPP}_*} zLD#Olj!5z@hJRX~r0+pch&tIy*q<3H;dS`E~OOpkE*HQNg<`en??Cm z1C9~Oi>apKz2uUP>?>TWYQ0}K+^~{G1X_wz#h+;fBeaq>y+5<2vNs?kbVxl+yK)x2 zJ^1`6^^B6({W=$JuylJFNyg}a;A~~u++=zK-LLv{atgrbefmqk2VC`FNO0!XAUlO0 ze{64Or=X6Pkd+3AG85a z`qV%YSD%ZFtn!hN-C77g^~W=q*`mh5z?30j!CT2b4Wi5kg4rrA_tVH$^=fc$sRg1g zbk+TWH-2{cU12Qed|qf4A~mlg+KL|;2VdxLI$wAboua%T=B|AdxL2GpCdqNJ%d{5CwUk@Vlda2e}eJQSDvGGE! z7ub8}2&eP2^Db%y48*9OpOZ`XIoj;vM0#P=hlNO_207++jjHL)HX#4)Xj(Y|m-^H7 zFzFj0odP*A0hyUp)UUt5Z0Nw<*gFMFG(PiGG-?9&h*IRH>@}vri=(5M_*=1c$aI-; z-zuQ?!RD6ZP_c)1i;(jw@bjbXL#1!@brc(*KfNJk`Q-<|EJ}aXbhVLWCuBas;OdEj z$IyIxb#gRk|FZ`Iy55m61JvtwGS@Y%t0|CaI>Js!-9I<>VWKI#N~L~5F7z&UX3xcS zdUndLp5Tx;fQ1EznSz=y{RM*IkN3I$g-RPphM%^V1erAwH50u(;OFu_9*zrrUYS>R zL#e6Y~R4Dm4b+xja9O{B5ci&&(4W;#=CA0o8ERp&d0eqhE{MGa8GWp zaO}A@&FgQ21FO9Yd7*QQOI7mq0ToDl5Ls}I@G=Gq;@B*%DR2{&V%@CsJ}p-)X%frq zznW~Ndit2utsp$Kae?h|dTNHX@Y}#^XO$}(CZ0@F0xgrUaBUYPhC07H{8id+Za3?C7*%p7RQCHa?PA#9WuDCN!57 z5tF`882@A9$2fKx0Q`->S4Vn25%kyBGc_n8t*(zoR9)JMASyWu!&M{5NBCRQ-U>V8 zxKSl99_ct^1rkjmVkicI+}-p|!JZac?J)R5-bEN4)U81$m4*|@7M1Vt$FH@uwOOp@ zxNA&aVs-`iDpCOZQCj{66L2NN-@$xEl~dT*pxKZ>JFCx>dlyzY6=pAb+_)81$zApA z#Rlf)2QScI^kAsv4nuN2w-QV-_fpEXjE~<_8T|;(K&=mqTRa}~(4e<1bGhJrMmavf zF|9L0v|J#=W-%q*rdsk%+42~=2SocrExAI}QqP6HgM7-a_Sc+0uuC!w)LW0*rI$br zQ{zaTa#pL^pK?q=eUabM;@H&I*I{;;Vb!r(<`wmbroz23SHxu}cG70QR6*d!eB}c+ zII)In`*G4cd@rJ#vYN~q9H!g%2!8nk^K4(}6m&+>|WF@iTRl&AqImh};VJ|r=2lWYAzu;zVewSB}ui~J|&7|y^SXx&r7pJ~k zbd9Ct6{Zrjx^s@=Ph}){TZuz^tkqgIi z2LQO?Va4;5loX>1Z(BJF3x@iJ2BXp@$r0GBGk=AQ_Zw6BCk+5OVnc$`fsT3)A6+>< z8VZbBhJ}S}aP+G-E!rU$6`_K;NiX+#OV1_Rwp~dgon1LxCriM8dTWJJi!SNfh(#D1)jt4<*@A^+Q4TYXRmmIJi-C)DYn<7Vj?e5~zT?wc*fNmT9;R7;{9GJsB z@V_&B=%uoJkj!rK{@=ttM~2~_UcM1zh0O+4S1+?p`_3UKKRr|o1SS9a;~io#k?w$V z9yU)KZUVG~N*QTsU_lB3BR`(PXFbr%nAp-0AxF6{2xu%r-m6ovXyS}IW7)>j&%0LgxJ`WNb%pUm6evR)%9&iY!gt|a;b7z<)wK7Ze_Wpry`u(pnbTt4V1Iz%&N#}Rj3DN$EXM_E}At7F- zpwGwcdi-rBGbyFh@1InkKmJ;X*IPWC{oP>?-btB1F*LD;h7^h_v)ND{J%Vuw=l=DV z|NEO4nxFyx*K~II%GW^}$%2(A&hs1(#KhLOz#Z}Zdwg~g7wrvQbsZlCc{7Up`BRas zGJt?20r&?+1qEb4*65W+vkRa9T2dZVQb~+1n7*asb`KGqIQm5Ch6rFJ|2PV5t$*)$ z|LbHo)z@aAvU4i;6{KfKb^^tm9xDe0TiHDxo(|da3cxMM=UBP=hQvD~{p*021QWR;|J z3OAEczYkkB2W$on!aE>{s(P#CFG~!GjIywc_aisYxr^auqdql1r7BRXp>!BCLH)Ik+z?O5Hj(kvT&U7Y zMp!+TP)VD)Djl^3Nweg8K@HzmIo%rFQvaWpC`X?q43;w4mWJGwN>1s|{&6=s^2)u! z8k**T!^30d7;ApBh!%Lm*<9hxE*r$F_PmRs{8MqcWAvS0gKnF_)MK9aU{N|eJoJf= z$CXRreKz~-*)te69C)+QiMj7Zh*L#*pN*@6tMH|V2mcSbh=A|k@x%?Nj!$HU8|pIa z@lpog?1z2m#Uhx3J3B-8_C4_=_vGXRTyo^ITxEcdT7r&%N;Kj{O>H!%yaT-0q*IG z#z$w98zz=Pa;&*{eoyPZaP(aoslzqFE(AJ zQ*@=tWQSO5NI{3T3s7``ymS?)(SRuJ^B$n{ft3|#&fq?M`UJ>){(*rHOUudti57-4 zGiVKXCn^6^;{AIH3(JCd*Drd^?5*P!M3KZjK61u^o#HsTxn}W46}>F}*rVwH)!VS0 z1ZaMrJp^XLI@*5;B!!jox~xN1sHTeP-$v+&AJEDo*&DAz@-n&-I{HfV0&sfOU=W_I zQeJ=p^z0UuMa$`cRHwzf$@cImxAXB{BS{!iz49^YZ~lZ)NiISX=B0FaC}~ZAj9q*b zEJB-)TX9h_KEc|vO0pusH=gHYNyU} z#Ah!??M%C-?H1fAZbnQ~-Pf%v7h|yg%3oje3VYf$x}yQq6;fP98Wx%*kMo>Ax4E`I zV9+H-YjA_9ba;zq)((z-U6X)OWQ$s0_@1%pOo#cMjFQU&q_sxx>*R8ekk3jw)z~GdrrA!zuZgXSgZVXXs;mtn5-p8JICyl)lK4^ zbON74w&=z+S&1&1Zd7mYdEHy#uB`uDB~C@1Be=7Qd89SGav>f|w*B=T82jid8_^}i zIY|qhY-!YqH`fZX?lywdsK-IE5j+9cc59@!==6)1=*EjjlKf};nFPw$Bwlrc$nrwW z2wrl%$v-sKsPj8?7pESGT;7)1in(6n{gE$Ye`H^LTh?Q<2<3#NVuuE2q5D;J%dkJ6 zEPoYRAmw*KBBRj}UxVQp7++M`h~815bt1u`cH8_Ib^D!M0Q;vb{WeV|1Iv+$hEg!{ z-!V7A{C>cflbXq5ZO452P{`oS8-qTrUBh-O!qz!l#CrW?^2zJB-4IulN@B)WG6LT4 zvdyitx9J>@DVJ{;xs?@AV#N`S4=BpUI*YTyWDaCW05aW)~&J|~B>%jNq-;Glz zQb!aZr!ka-phvF%IqahHpNj(r7!9HxT|Yf@4W!A+huDNl=;-|QD-~f%~wv_ zBvxni?UY;0DR)d^_iyi%>T3_zG>Tj;;I-uTVkSRnZ$4Vo5qv~~7m{o3MDaTE8Q|J? z!bH?5;erH8`@})}KeTogAn3SXppvQM`MwK%h>a_7YA7h?Ca724-E@KJ>Jjnr!bF(J zOz!S3h#2kBU=wArr5AwU+SZ|BPO6j`*siSD*0gHpI{>|BHBhT-mB&wt2X zn19#382B1V_4AyN$>M}Fl>z=!O06Cngl8iIJF1B37 zi$e$(7L|PDW>%>;%M#<5P2KA}N#Q&|cDPG}WVb7iXvxgLOW@_})tr7&vbOFhi5XSK zLDXnKwY-xq(xy85uJDP4+`jY9`}Utqf6RSDPRU|PMP>0`<$%zf~xMYBPA!NJZ%8NVcQe zz)9m2ACK>4zs=nI63%jW+MDnPt7{?yZ+0P4ggPIS-Q)|Q(%Y1mbDb(|8x|6sro*(I zz8nQ)JLKr^=>_O%Trd6_7Dt1{O;uTx2WJI-3Fwl z>;^A2Je(Qu#f|b86ceLh33p4FA3`r=MTNXAH|8*N%j>mbvJ@448C*C zZ)C^s2=;pExNjSmHWxf%P-g>!9ftGLM2Kg;O%mOtJ{PhbUb~e!@{fhn>lgC%H(L{y zD=w>PPneO7Q+@7^?<|@?^}d(stEJf}1AYaXzOKK<3EKTZX7*6%Ov|8@)6Z;1Ie`P7 z_%>Q;OnN9!m5(iBxIQ}QN8zP66sjv~QRR{H)uC}-fE~FN`QJ^K)Mwo_#KfY~jY!i{ zQk#&1{Qp3(KdUED=Rz?~f-7_2X_VT@#IHL7TwB$r*Fkr8N2#x$mEJJB|w`qvSxo4P1b(F!hGnt0x3 z=@+PC*;!jj3U7zcv*1!v=sj+tI_FP*^ln4ncIlU-EwXswBH#%5|FtN?!g72MY}+8b zPMnZEuK>N$?5nj*ELCmke z){6!f0-XYgZnCcn$LY>a_@pcVWL4>fldfVkh?~w_Qf@Z}A04)B!VqTT`~)-@Pt$Xy zu3{(Hkd-zWmAe?)>+3R>3J_7V^s$l((N*B(1^IsZ)i@jI8!~HI`plfB9XifEQ^ESj zCJ0M0iQQzodiqWRJCeL=23~EpWqA0gm(!g@FIV*atqQT?X1a{&;)lCtSb$Cc5}t3( ziQm}NRilVUE^DU|=6(bCjs~O=0c3xmg&g5ij=q31TqyjGK~Vbw=c8PFi=K||^F%Xg z8&)s4##_Plj5I9SAdNUf&?lVCI~vBIDLN^G|NGG#9_Rz{a#nuc0W=1@Q23;Q(pI&a#-^nL6HC$f-S6F9K0FOJ z&bnpoi&~N%!3%3|?dPRRu{Ji)X_gxd8mi2%$U!F){-3^8651a!f0Tcp`R&Jeu8&;v z^z;(|3CSPsd1&i$#B*4uoWnmW-JWk4*u#Csn=$!>|c+dd-tRQXa6} zjER)v$66GOKd$C}*w)K87Zr)X`qb;f@}sc#9tsMIt88Ass^-Mii2*MiP}>lo?tL~d zG&S3*^Ow#)Mp-M4ilOib=XnvwW$ss7B=?;lXN zi&Bks`1FtUml>qGkm!>1SaMKfdwroKzP0Alm3RO3`(6>%PA2iNa)*}@ccZg}%a!R@ z{KvA8?6-TZpa0WkdjHo}6wv#mSGi;KCu2w8>m)=i6bdlwE6`dI3Br5Hr4n#{WqRLF z5GdFnyyk*|XnlHyB-WITh{bwL3JEvTj#SGxV)VgyWCjCzQNJtF?D&hn-z<)Te<`0S z_~#I5*nb`^^+4%yPzAEj?v4 z$Ri(@Nmw7f?YLr|m~8Qud>XlTOBz{7T0ExScf!zn9R20X2cRUOWH~~{X_0#IAv@Qs zNz4AVeeCbA4Qj|P!AZ)GLO zt&ttvVo6Z?#f|FOGa@G^0ib2L4-$@0iMcVs@VvO7TWsN|Eu{84pF@Nr_i>x*)@0j5 zNFh3N@?5Y2G!+2N5MN}s^<0u{2~6RqrlzujLDhkE&XSPn$Wu`5p()kH)#b3JJg09>B)!_f^e$5RfKDrck zSINsNWB4(MYBnfkuUt22@TgP%!arHc^+Z;+*5qYopo)Rj7sA&YokocY@f8@F7>TOi z=SSveANcelK{ z8pNo14t#wW#>Vc3hL2x@PG^!P7p(V`4uTM>tmc=PZBXex9P62W7jbQQUVU}eQW&NB z6g&45~7-gfm0@#Z(#A8lRq0hJ~`RDo9aTyrChUdiNUZNl) zgTT@N@d9)))1KlX6NLm@VqQ&w(@44O0@^^$q6O~C6L%MQ_`Y^;K77?FNBfw)m3(FO z<)-xXSBWR(Kp%4wN_+rp@4ccI02c(n`6RZswy=F_L zV@FFSJht}_xs1Qf$%0zGcweRFf7p{6FX^IfS=>>XG8bTn~Qu&EH8H z?tYkqLI>SU<3^=n(p5iO>=pNJ@yOV2s>bml-$$^y3_dGmOl^y(zj=A;CzQd=_@sxg z>GNh30gJHfYyP;&F6kF?n0r7Gb9r^uGC8Tb@a`pp3T9W+^>!YcGZ6u)0Q`BRlcapl z$GzhbWTS=S^MW}t?CqKT_?x_w#zonB4u`yo$_||_IC@VVu5Ad@wmxBo=tUD-f;49!BnUXUBbjTC{0exj+#YqF@qK}xH z!v@6EmWc^GYDDKmAM5NQF;gpQX?dgOiF6`ldD2+iyQEwhqjAp|S!>orL;WVnWBe1f zsVQxRt3^W-pV;84{OiRj1#oEa9B~gHk%sS5A(b9{D~k@~>9DVkaVE=t!6>Yhi6u9o zapkg76B39Fv|MjU^Ry~~!&X5{E5Ban39t@>42v(v33z}E^rlYGi= z6iNM!`g_}OqvnmuewtvJwY|!hhM5LZWBLnKu%(R(-Pl@(k4W~rZ^hfJ5I{wwACue3 zv^PV#0}L~;RIdN~(2Twj^LjJ2M_ce5SwuLMw}diAv%oU}~d61a+Q zZ{Nr!+M)FJ<`#Rp^8(jawDLj#2y?hRB@3dCMS7csGCXJK7buP*Lr?OhG^%-g{H<%f zGyy6C=r6aKu+v3VA+C~oAmjGd=xhD4@V$bBw%HsX2S%j8TyiJ6T#< zlncXp?CqzvnL$#yRKd$%4WHLf>URpUXzA!Apb*I6k!{;2#+#+3ufb(y0<5gaYbOr& zJ3-~__6yFImW;KII|#wP1}~~pwaJQJHVwz7JKM!fKECxfW*v#GuPgi++ z{U4*Du_rt{)0yclkC=+~fuYPd@F7UJjUeGeZ&_GSp+5Q?r~ERr#l|RQflOm|s+iwk# zCktvn$EUVfNcK5CHmiwV9!f7~`>B*{f9+6E{|O8%**Q4U74zzr+`wAiYY^93pla>< zn)H6lU+zHHP%)Ih-+__;x&sLvcvC#;L9WT&e&c|8;yKt+{IR~w6RZ6nVdfSYnVH~d zI8{hARkrveR++DRMLc8}qyAG>@u#{#6`P``T!i(m*af!)tVC5`2$Ce|o9vL091rMXd~KO$x(ZbLY0yGs`s zE^~jxTSu=L7xUq^vk_h0jl$s&GdyI=U!lZX(%5B2g=$CmMQ_oxYoCF+c^Gh@n*Md+ z0H4f4!KgVVak{@}#9>xTTRVMxn`v@xXsB61=PCH(j7pLFMX!{YO(mVHrwMvknk9eT zTRaRtn({=q6a8`6`n8KxoJ<#ycBhtz@YOHu5Q?a9zos{l<0VL~QxZX6-Q6__#ywNm z-?X+=VRS|vz!`gWz<%ssUbRN~W8T(m+jwi&MfEb*-Ho+cubXnK2{fq8)if7fN{gL+ z8*0GyLL9ix!EE{MXGJVp@~rwR3gSFroUm^UruPPd{utw?Pbk(j5o)k;xzMxOx^x{( zRc_Korto4^jNk~O|6s1*3g+d-y0WvbIvlPpNwGbie_SDQSn`?c>8P~cN;dOXp|EKMS<+~p)|H$b1Pa6*Q zh7pbatm?&e;hZ(|)lu}!6!%@6isP>lG6B9B8L12JhnD-My9@YH*fsN7$S7fJ-zz0U zix+&k?U|9k+rfrTg+&<|95nuQ=}?@^C2N&{1T^zvA=Pl6%%5u|kCdMpY*x+2C{Q`Z zO;eth9Bo;}e@M}_dgVu8x9cyp`rw`VV}D)msi@tcJI`RfYjP%noG62VTH5k8Yef)h z2NuAQzkJ!>9~|<8g@qNAzcn#D7lFH5JCi9L+-*tQ1TKYad#LKO^D0L<5#84Q>9S%& zC-^wK{MUy>p{`{4FuXy)FH2dK$d07NM}27x0X8)#SXjdi1(;uCjx!D!Up^O1QP=h@ zr3Yg$LPJB8#eG!E<(2F(+8LhaH(EH}#~<3g0`19zE>3-7ri$%@k{~px4Fsq$B^0uZvI^=tfg`ubhAE@X zRnB~m*FUu?Xl1cuZ6J*B!im5ccIJNf{0R94Ea-}pR&vnZJ|jEmnX>XN?g3@BCS8o3 z1Jm*BS<79+frLw)$F9H^N>R;{8*2TTmt14Sx}o?&*Cbu%Vibjk>`stHxBNv90#iFK za4XNg)z*H-RKY6k9Zookb3XoS>SR{Xa1x558y0To4u3Tz{A?V^$$Z|B;I@GeVb;@FY`OGh#;LtEhJ5hZSjB%K?QrRRl}*im@Wv zEYx_Tx7oBg0VPAayGknG0)2gb%LgT=baR5PSOz-A$8j|ZAa(;0eziPoHBf{ZC%dNX zh-a6F}m2Bc+xGQjr%T1_!RF~-H3mFUUg&-I>HdfHUuLwU1jSEV*yhC!Kd&po*DzhagjRUC>j1soDH{{ku%+1+G~Y%NAG_v; z6dYj@zLw%nWR)M4%pB~&NwIu0!2+lX_}>L73}zmM_W4jNH@x8|itBz<_m1HXD_ z5lz;V3iFeWF=%MpH5riy39&vBlt$C%ENFw|Yq)mA)1k212ySpklJNaV$}q4IEFdhT z@U`LSZSL_8#Y{tDwnKWUs%rmLJgmO@ZmQIlOYYmc2>sr~6G+4DvSD%r8zT15N8PQC zzj0;2&1+_woS$s-f}XSkw*wU70a;lBFSO}IU2E`WE5*QMiGVKtiCn5I*g)}&ZBr5u zyxdZvdzKj1a|L)n*{pBKX;|y9l zALHTm$Xq;lhS0C$XWC%-mFE&|gDFfjr+#B%iu^X`Gc!aGK#F@WRE-2zs=R`@Cfc`V zdSCLN_Qw)n?;;SfX+K)Ok`yXIq8D5UaN&UuFj(lt$IM>{$bzc+P0L3J+wgra|G_Fm zN+jfoFVqo|=|LYjs9LJmN6{rejVQYK;o`3B z_`}(=uDD@{0$zvS-Iu%WQ8C9ElpS&8ow2Tx_u7v&j;m;an$?7z@P9q?Nl~9f_?140 zQ;s92yCMJ&fao_FKB2vM2;!aH5PKjBAn*mPt>-;+V`GnDoDnrO0^oG|@Z{vjQWbPR z`Xi)h()#l9RmcL75>N^~e)7b1fD`ynLn0$TU5D%(IIf)0(wXtgNCSLPDu^5GmHGUH zFeJ(hbDX|o-{|CMpv7bAJT-_b4K;4Hsud%4@rs}f;ijdM^&w)VWtY=C-e_f{@0k&W zVXP0B8mjKC9@zU+Ucfuac%qXxDnG2cA??~Z;D52ZPWQvt@wXFRTBO(maE+QN5>8zc$OsJJeH=Hj`<_YW71R$Z}+j{4g&zBre`^>kZ0x@ zfJVbR(YIJK@Af#k>Xa*P7R`idza=VZ z#p+~F$eZMUJVz&fxCiT1&(^F$GrT|NcDlPHP|?tkY1g{6%+F)ZRzU%Iha`qI2I+4OEiWa#!z1si=_{ zPh>unP=GA?fu$+ZW9j%Y=;2RYDPWt>ABU=!yhmzEQ;|Ae zWM|FCD(o>+7~${RGS+vu*pOj%aJD^N>Op10uckeE3+q|A? z(TO=m5a*4N3%JSTN&bcv|EZP&3v)!Sx!E@}2xZBKMrosoGO0jA2(%fVnR#oToiZMWYC2Uq$taIMU5Zz9lP*Lw!KGD zf5@T~0>Ysr>;g{dy#pauTyGtr*Q8w^E2x(7P6U25R!Bu^?}>Y^(cO$IUT)Py*_4;$ z-Z-vp-ur+rgJ!XyT@POXqlI<95@? z%>Eb84{xCzT=zrTtL`Vyl)Tcw6OyoR@+H@wS&T^`2%Boq{N{POKd;HnHQ4IP8neJp z{$g`|y=8P12Ov^LG!fbn@!HRtZjWW|h!EYx9D)Pmk)>?$^)gE*t=GMZZG@ywW2U^- zL1(gltQDzAPfb1Hul3d+pERgIeyElf;fD{>C06sP*JgM6vcMLrax5>?hx-ZTo1?x~ z{#PdIlCaPNj`6o|)*)fWQ8KvKdF8lgxOaV^j{D{XTcbWrHTG|`;s88rKqkP}^!PX?>ATF}VwJUbW~_KY&HmUFCs^N*3nK)2dhaGj&*?9A z*h;(^7PJINy{-@sC&JPw#3OY~pX%If*usMXe;yS0NIV+ySKOaGIIyjbgx+lvH6i=H z&z%Fer?}gu{>2=RS|WAe3!;*Hd0FroA7T5%Y%BnZxC&0k@l^?UH2+#r#*STO zrzsCJ^E=+_oq&LVui4p0S|>2WgG|IM0QS{8JfXi>JUP`YA)AV%+6)xn4tjU|Scu1| z;x#uR(`gAxr@`c@qJA^V@}cOnH*yxA4F(LH^=l91B~HIQrXa4kZ$$nc6+Iwy?jM_B z*d1$zw2j@vgsUrTrAXRazCKc#o%7V*Oc0+*M-)7&Ge;+Ny*=l1N-R;Sg-EoB+=2GH zD2q{b-G0`-P$btMV(6UI-P}0#MvR`x34fc7v#is!?dx^1J^T{cd&h}Bn9vbAy zoU{NxKR@ec(JwVx2}wyn)_@YvZv#|UBQj)vi*CcCbba(kf~(VkQ<& zLqZsjcX;q}>7k+Qz54rm0hLhqgzrrHt1A(ypjJkYDFpJp@RSsH`|TAtASc#*@qw0! zIkvo}M#R=O?o5-Ev?MB_VBnqwh_kGz;bdw;t2dIlZPgAKzLyj=F;o{WrQU6m=&Ej` z=4Z#RaI5=p3mA*lSr4Z`PK~KvpM(y$xVRjhodKg*1hrC~;Q4u-!ZIO3I0vU|b-lPu zpbk|5<~_N!`L8bM#yN0~7a|ePqi0yZ%XIjNX_lXy`vx{)@HqlmGG(-TXeU^9Ul=2L zP=wjQ=?jHyCl}sjN3dDDt1v|&Oew!F@E%$!mz@PhjqM3_`d2C*A}4HRrYK1;0vews zDqijDC$UUfV3HkIz4N?t-4n<~;cSh3OM>5{zkY}ki4Ntt_h+w9%-mXYb#GLM2&o^& z0}zqgQ;Vo*W@N_rkg3EX`(NXNlBn=-I0goW4%F{bG+72?fQDK3JHw z>=~e6`5-s^-l8PoOpkKVEGjJx!Ol+ky+m63uPOrngs4$2$(r2g822(}RtTRU+)ij8 zTV1t;BUF=+kSHrp1C4`&gWjdJu~AEEk0AQ4+k+^f@M|<7lwLPLB=KW89A%2|G%g_PdiFhTY^SmTc%-eM4$8| z{!1BGhJuUvk2noLFgep24vWRas`F_P8{NdXjnHd^Skd=CSuiP67c$;5h~G6roDIbq zOBn&e8!R5)`U!T8(f>6|n#4Ze8uLTCXHEdL#!o(vQ>h#=o9{0(a9u+JA zV&xqT%Z(bPwC8wp_my9yeokCXJ?1OC0L6Cu>Av)Zl#sASI$1jqdF@De-r*m z*Em*UdKlE|b%+d-=KQv*ec`cx=PfL-_Y5|dongf;lO;~Q8U|nNIr}GH98(;v%T1+= zFOlVv?qd$+2z=*ekr69vdj6;RjB8|-rKO1b=JYx;$_c6)l&>qa^v1r@-x;01KkPX1 z>?+j8dlM1o?Uni;V{zb8QTsyw$Cvuq`u4GLn3vayK$P%1h$@1Hi#d_I+r2AVX|-}C&RZD-wlAYAbkS1ZOoq30 z&Z3_{(xqRnJhI{>z2S8ZwGZC@9gkC9mPRCf(2ADJ<{Oy)8ujPPpkLb0_c^((N$s5F zF9{yX--=wMJ8@&pS0^L5%3t_-xC9&pmXMhHLwk|ZEZcLprjqBaus1^AiKS+~<@EI- ziC){(b-O<`)5kZ*Fw3TT^%w=`5Jl4F%f8pCv!qYMEsl5np#iX@8EClp+g@5%lu?W+ z1>qf^+@>p~3&_oVEoF*VFcp`jlj_r-C2b9um>3z+01ct__V{ZRHMNe6Swz#CM$goW z3U*{ zD0Xyp0U4mCJp7^JEHw&6p-XF@{3a*gJasE)xl*{G{($~rEXRF53gDDCiktc|A_EC8 zLKswu8>P9U-(Ljeb2FC)CYl09a&oQK0<3@%4t#qdY+zF8Us3}1ExIaam7h6I!@C`c?d<&ZoUXaO|K2G&6OK=C z27OACo~JQ?FQD%x&qEMvP0=q$mLBr~zsX{@ODAP9zBD;Rc64mydAA~M`TZP9V*=Ut zi$x;k>fKGmP+~O~E6>J|J7nD6eCljj^#k<|w{q)YJJzMG4X_I5wHjpZwfZrEr=jj+ zQf-Ra-w4thuITN5j^Z#?;KA@396d>gr0yz+jpa za!+Kz%rGF8!OR>`+la1-RFn&qPG}`#OKLe0`>lz;8nG6Y8q0th`)L z3t?ZA9sme!N^d*>W1=%hUjWxMxdU{dWj~1ln3YwYXT1o-skwjg+uR1U#6zFir zfe*g$CBr4cR8J~S&hrIg##F;>@UnXCA&_s%7P`%`DTZr&ytb|%% z-OM=K*GY8`v({0(i?~52!f4ymo$;i>_z9EER+UZ+v_YQ(3|a}J+_b1cqs7UxO660As_lDqcsV?TUfRb6vIRHN-OhqqB+E&Sqw21+i^SR=Q}d)tNf*zvTM4M zfmiV(9p|4{N4n_?1}?2M8iZR~5TNjUolp%P5molei&sk{ozoH5I~9{(P;A)WAQ@*d zl)9I9{(Olg@A7=bI1<+r7I2CrAZJVwK|FmFk3uPaF4cP ztk+wAm}|S}AH6`_-hZx*a*XzBMKB?pqYZJBTDz`Qu5&k9!_e-!wWLtO2K+qYfl23) zQLYiI*sUo``iq|jf$3L#7Z_uC^_|AQQHMD*OK${f&;huRH81Ds|HcIKpWrj97zGA@ zO$WICQu@o%cM`Q~S5se52qbx5eVDn%sSOIgw@p6avb$Qe!oba6g`(lyb|b*dFIg!1 zrL4xE#m{)5Fg?G+JXWD~{t$dmC6+MLL}?zvL6qlN_lkxxjZmNkM<8{*%QLEizWAQc zV98v*e*U;!cIiZ)4IbU*=j)5mFy^HrN1=$OhJFh9fFo#Np%R?3z&`V6 zhrB{H5oKNbOhO2~yr$Ye`?C=CDuYk)-OcLfgt_(!S)bw|NzChsbsJz;^%6gKfkZ}+ z$|G?Ab>{?jxs|HG@Lu2hS_mg!eNyLaJ>sU}S}z+a^Qgmj43e;rsLE|7^wKtOJ2yzh zE4+>zKf%2PCWDxy@cBk=3JtAxjxKn7Ij-_I4B|TxRXj)0JPs8B;}V3O9nZHcwHfV+ zc2SEe?MZaWLbp;IS84NcJ4X8mUyq5?Mcq6-2mi4+SvXDu%G&es-{&d;3f798?{kJ< zC|IA~Hbvt6v)+P^2L;oK3gg~Fc%(}4Aig-J8fJd9jw=%mcDoH3ne;dK_f7R3Cyw7; zCqO?iEd^5yvW6t?TBUd$Nl8hTOfYasM&ADpPlNr!vTmB9Ng7&J5sMk9kgW)kYqj(l zAti?A?+}NHNek;9^ZQ&7u_xIu$Mvn&)Ym6YJ@fsrMZnC9?W zRFlmvVW#j5%nPT1Eah^WV=R{t@i;>12n$S{e8R4}_Q#eE%623gx~^a3tW=CG2QQ{F zuGYj;cy(bkW;zNxlBITH(n7n3*9$+y*A+H=4P-i|M1~mnNvi}SA6F;+YG-a&QC|ir zB+`%^?%J>Yu=tMx>*+G9hcHVmJ(usP_bL!qa?N;5c(CSR5gptJ4{EwG7|Yqeve~uC z+2k&;)Gd5>lPJg&n`x%DXf$SLYE&9=WXJv9M5Z+6lcz_3HIkEGGd~DJr8BS=1M=Vc%ukbLE$MLG7gHOP4|e#>y`LW4ECHYGRv|1BkJkm0wxZ0`s*MAm8z=hf%wm?HgeO#vi$h&dm4RF6H;;(tOY6 z88jMeB}e@a2#>$f>M*Sd{q1k8^g{|%&{g)M{;2q2LZ>TtMH(1V9zjiTb;HCx@31sn z;4^us$r@}1pj_0Okp!at+y}BB*1^g3uHU7(RDfyHbJ*U4T&)y4$yzLU3=A5l_Oc%;Z z%L}M{?CVt3)%&EG(-oV9ob7ew>nAssuX@sLcy_0L&*q>yKZE7h%;dXfbEE~SUNl7* zN}lcMzkcBKF+6s$EnlyysS$T^X?RDWna7p8SC{w=CaNhqa69j27 z#@a{NIZ7B@&W7@|vEI+p=XEsHRC^l-q2Y$7*xj4lG;*!?OgB+_=-ryqxzA;%?!QjC zS$do0$Zh*@@tJ~A@_?oO*RC^UR!ikm48^W9*9wNwJB!bdivvgNY8DZ2vCx6kUteQW z#y2RHUv(40S3y!Kt@2DiB zs_i|TCPf$%L$%V1Ig?D>-uV;DGi~3%(9rK-q3MZ64j5WNl9P#nSRzbpY+r!Lo(;I| zk5>Xd1kay8&nX0EQr3XP6>x#gP%6xEv9@LdgTXl!LRb1$Gru&!S4V7Nq{I<`JIxDt zS1P9B=yGzqtE+0UFJEXAl4d&qJ_rE#i4G#LEZlZ>vtsV^qx4qU`8$nxmfKpt3$$#} zU;K>%v{=hOvoS~n+;bBw_%WPcKsx&7$Xg8npLtH)!h8n|0hzQrZ#G9S105kkKnj6Q z64a4wB}88nh=u}bX~C0-XvXlkv5%T!);Owv%K{6_2)qs%Ph$&YWGKKawYfSn5V&58 zeoC0&b2b=nk0%HV3wtsm?N(M&8fDDlf7<||V`h%+ z$-@YM4}d?RS_rkR_3%GL-{`Epe9M$bI#$VWRfM}_NDKV5x{=CNOc|n=h}sqm7mv+k zin1zuZ2`g9aV&a>q+CeKHx2JHWqUKlxLp|{58x+mQY>!Vi!V+JZUen<2@1c#(Hu zMCu?&Kk|a#GnUJyjt(`gX1fZ=k3yIfcze-!OQ^=+8V{1?!R+R%AmL{hTPL5~>g$QO z*U1VucY?~d_m`IqwY<_Z@`&In8gDzhiW@-0B7faSN>TwFvcCQ;E?z8np;54)wDg^0 ztwhNB#s(l`K`}9DfZF<0%Y_jD1{OfZ8IU}al+N!Yr=gDKU5}=BIu^31+dYny1VIVX(e~ezI;K{oODlbg31I)&6;l2q zrB?9rGP^o%8!-)kkXLHYla8fO|3ZHQD2u|juPbaHix1j^*C&n-gm|Ce;eHjB>HsOg zP=K>acz#VSI|N+rIpq1F=7RKAf4p8qLyD1T6xbd&%*auX$a!(@=LW)i-p)Iry!Kq4 z1}K7)3@^1Pw#a>s=%k<#thP4UuG@LA&)MqhkpF1#8UqW@q2Lb`RHDplYSiBhD{N#l z=gUP$;9#s9sPeMsFsu)D3A>E@J22(Lh?beSiK4@W3G$bAz&q%xjjOHCa2gymZ6=Z4 zTeh|AoKN4TaKwh0nB2K*B2HI=tQg;>(dfCa zd+MZO9mmiz5%F%`Oq@Bi$Q)4D5k=QrBR+)15f8cU%P!xWWAe>$M|}Z(_5C3a*`?>+ zExpHEHIrJnj!Rbm{{F^_7SrQqhZyoSzWw()_*?}q7??BvDF$GuclRT0Rt|SA43j<* z+&9hpX}tkP^V7E0d{b?nn6gH2 zV++vWML8UyI&#I$ur}HwNqWhNPURv`Zn38~IXf{qa&>yn`6f4A;C;|?Aqm9T$jWHe zirD^W#1&yF({M67sglLRPdZi<@m~}5QX95qOcp$lZ=*)|+aYn4=}CZ+64M-azzHue z^isp^raBRLysGc}?;Vobe1)Hc28!CFz*J}=y!xR3p61B2mY**<54_l$NcS~c7Wu4w zv|@O4k0&5oGEoOOdH=d{FrKKdM_o9nW+N%=@yU}3ZnO=coctGFP1Z7QHUc+Se4-|= zs*6seS`XFD>xd#v)L&f&{*y_?jb3lCF{58k?-Mf=&GzUOY1lU#WzF~SGR>0}ZbHZz zLu@wJ@OEDPNH(c{|FflhOW-8}Kc#1bC)zs`OM#2WLtS?q z)yv>gC-ZizGwB3g(V$-mTaD@))SkP>&W1yR3I}lj<2JPK-a@QM?f~PceblCuPSBa; z)=?d(GZNbEB-k1?j90f13V#?_K50MxvZD011RK2iW4vdpjMw*!O($D`gp0IRk5utq{vhzq zw?kr@OLFg%G4U&K3i;b6y^a*tiFF|=?!l`qLDce)4sLnY9!HzIvgXK_3l<7Vj?X2B zH!{X2(K;^SpnXgP2)~p4! zH(<_Co9Uqb-zt*Y45ver56U3_*akeAFc}3!RTwc?v6KNm4B|zFNfi@=FW`W?E9&xn zd*Qd6=p91k!ln$2Ir~L5p9_G=N8*%-sru*CxQ(-EfV4JlX4__<$|>zMUSk^~L^s|LQ9&()wO^XdiI)ITlxIwn#(> zmIkJ?joa_(m21@9*QGCq6M(wz%Cgphbe8|IoFruS$_h)w8);x6>kzu1aZ&?WA-*JE zP)-$C&e&^gB(8JqP4tqYsk+8cO2WvyLF4T3yFRd2C; zggm80Je~_bu z+#{!R578mf#0h4Mz<hnx)WHFq+4e+mD6(TpYcjE57Z{<>w(ZS!0#Mq9Y z?{o!2Gc1+dPDaU;%vD&)Wr#?qx+VNwmm$Zn?5mlrSDPFd%TW(LvIkA_v~DIlJ7A^~ zg7|J1?ew#u^0>ZxmBaq72d`!)RogpR8^7?^3W+Xcv}+&4X7eoT?np?Y2+E9aTTh`0 z=A#u>gmEYY59qK>8Y(;i-}v!6fW0zPYeD=iIvNWX*Z=CunI7=e0_qnYdKwnMa2%L0 zPXNA$2p0znb8D^LLMyK#)K!28j-l--!Z7kf?c{_n%-qS5N`)~jl>k5rq`j`~&Z%o^ zK5+zqV5#p95@vD`$R%_r7f3f4Th*v^e3c?s+%<71(O)qD1!+Pw7kqFA@>dr;lwO>w zwR-EH(>yUs3r9YmwEjULolspz@I4+kw!;dbYrcg_@~}I@w7Pz$9_JPaLE~(xU7D<)-m_|*N6<3m# zrK6WMH3+z=6NO78{rk}T$CXyr_Jkw_4GrAza4j7Z6GZAWJOKf}hDO5j-?5fL(7%~h ziG@7{ikI)Q=|w+%`W7=n8V&M;rl8h4Z3Fd}DXwmR92o^0+gsm?;OCr$`O8a76eMK| zQcK*NoUtc$7=Q=oyOBY^mL`m0@*6Rt^xEndQpEf-b(f+W*Bqm9vF(H7MBPv!3mrj# z?br3dIgs0mAv8nG%X_^w-i>l_5HZtwFR!7+U|?qEv$n>xUB&Y!RMW(~5ey9dIxFYA zllhDSOAUU=g@_wi##QUx$-w>EK3}yy+3}z8(8g+V3aw7BFzhriH-F_`%djo*Yfk&4 z4Fsx@6l!>WY(kql(#RhChJyoQm-?DHwBZ=6*VIZ#L`c*hIwT3C6wKAJ0_q8;USK$D zL%!15<*{Svl~V>7SO#1Bp}5&^BXaYOe+}PG)holf+V($!)h7tb^zeyl;S<$#CA$SC zw~E1Pgx-nIU-P$hb1!mn0b^KhYI0gGcmHcvxn8>gbc*~Qc!OvoN*z6b!Smm1GUeO1 zH;THtumEWTC~HNEO5RIJ;ZK#!QFm8WaR!A-i&;{J;xHs9XjNO<17u$iIWO0fmC#DvBoUR z`J^Ht;Y+FA?s^}eO#757fHxz~BfjE?v{K(?6Jm(H+1>qlrs-1U-WW?bkVno2J9-PS zfVaF!*u*%D=>dK9sCeMuBv}JFV5Rj!y`!!D=gQ_;t-Y`hSxKMIts;E=%}HXJU#3&$ZjaSU zxEa`w!^nQSuAZ{c734=p|q z^#kr5qP43sX_q1Gdp(&h0tA-U2m`<|cN~Y@>5Xo)GgfPBD?obrMuv-NI8>M=%E($H zD7UKDnQZ8O76VX-x(bmo1Tc4yM$#~rJgo@o9ri-XJ0e#TB?Z2w>%kJ6Q84aslYC9< zI}%ABGq9!)?Y$9}lXk0TLc|al$ND};LLc$l^wDK?D5vX$xKLCyM3wWNpfYki1G+FZ7CCUn=CHPz{0R0`g)zV-jxk0ubnGAh* z&jfwJTXvt1J&JesI_T4(y-rpv-SUAGis0=)>*cEz!T|eA-{2cMNAkEPUCEPc`!B@i z{OuzzwxbqTQtP<34+Z{G>;2;&V}ce_8JlcWUkKq}yw?Yp9TyB0J&pO+YwXL|6WG`@ zxE`97EV&|q1WXfb#=S!zqBY`oB0wAL0OlY-===C&%9HBr524d>iBR#`Z~Q;ab3gpo zxjwcq+9JmGREFtk!bsbp;Kt%nH?bjT!fD!KnD&v7l13#L#qVrlceVj+(Es(jVqx_~ zfOvd>2^~+OBl7JCdCZ2)UYpa)sW(mklTrkfhNW)^g()+**!AeSlO=)p`L{qEiUAOG zVS6@wwmXf1j*cD_9v+*wp`xMj3gFygVZr>B5H$HcQLgJ-aOZL%UHjN$a$sbo^g5nX zlqns)yAU3JTMOh`cz3huCIj-=<@?|`nl=~G1{5vB{l{)e>R!cH_HXZSP4{l~>G3T~ zzNycPPq$n!pn6!m&eJOH)h@FXIeoyB%pr#vVd^wnz$w35kF?2n4_LG@Q|US5jG&(R zlr)Sog+a%WP_PQMpF*wwy)F|DNPU+rHzOWHA4n-FDUXiWB<19U8tspLo0_O=tsZgW z;-qF~wJ3ObQIH`>B!5x>o&G@qd>eqT@Qd#Wy_M*pp=*tS<&ZY}A}zf%ZT74(8XN_{ z`2cxVA)!eBdnM)#Q6?L$n5p&*FBK~%3|A=`o3bXfuLuWxX#vqx#0SK!z-{yS@!=s} z7U(LULL*D~d!Lx|z$!^}GImZvvJ*42Ki z8$rpy06sq3(AQAbre?(kJ^@8-!)?3}#YoxS!9dVj;~h(?t>3XpqgJeN4-cj)j5I$C@sw>d)L3zX_}=c_-Aeg7_ZK(T1N$?j?}9< zL(_+QW=e<46@Fyy{<1|r{tRu_3g7aeZ=BJ!V&r~N+BMo|1gsl?gB7W9W$Y;5MHhq! z)YY9UnrjL;pcv20&Sq)XS$_EV(I@+3tcr=((ld-n+%*vo_Lq8b0Y|pw{-3X3&rIWf zWap2eJh#X7)n#IfdWz9b^LlUzBjLry zp^@tT+c60fBfr#byY*k zJChuHZ>y_L=RF|=UMgj0gHc0_?8q|M7>5P4@C+(!Z z4gKBI?!#(0W9PM0Ofn&CNLQRX<}z5NQFQ`iAD8Ww*wK0H9mvKi*Di0x1SMQP4N2Eb zF=Cl^Xb?Ri8ziAGCcoo)+S;B1N;!5ftMHC(RTeEDW_!Uuo5?YYRNIZ$P7{8=Ltms< z<=Jq55EOE*)aGcxYA4;-E!KDEz|gH$(nRq++7OX9(Q+wJh}iixX@FP(|Gg3&yl+Rn z8+p0WPGSCw^3udcs@!7C3o{XI<{~Mg0d~Fo_ltIM_X+WfcTA68h{vVu|LW_M#RtZF z91l^-DV)fy)!=Qb%_Ex462LW1i3dN8T)!6;DQbNmAg2fNz&8S&$N`Qwqet2Qm&kx2>G&(X0u%z4A7lIznPLcZu~KX6>mQZvzCYnXPrD*!t2bBd`?+t3 zprxVtrINv}WzsgoxwLE^#~p!5Dfug&1nA^%lAW#hYXdC{P|4L+N19Qi_sf@{I{lGl zIuicWS7(>rkyWtsCCJtSit4=gYL^R2!SW0MrBQmKC7V?Oa@!$sPb;)|N{oGelVe4< zG3*Uxl!dI2BUU?yde{HzgE;mXP;Y)18Tq=A zWwUx9X7Q1w(ODayl0N%WfrZ`Ldhug$(7&Mp#uwNjcTC~<`K6t!tNg;l=}Ab6fyT;z zWyL-01wG@)yM?u=! zq5b_*gv7+sAMb!_$$Ez*1bx9Z6FP}3;kd8Au>+BUAk*O2S|e?ttMaqfUpe?lTMGje z^kJdYG0H0d_(OYA(4Hvab0Bss%RfUpm6vx0IRo}n>ojlzU5pDm4 zvNHd2RRa`A*$KK9+5Y`;Hr_11^vfde3$=*SFXS_@j+SX#_cJmxjg8X1SaYSMP0$u; zjC!~iDD0Aj`wQ6^gG|Ls3svdW^LB%uf?$W5zEXrslY}})+~3Xn8-B;cU1MfOfOqt6 zYvUgupFGEq+Vab^j`#x~M`H+I@Z}`FpkUFK!zyJGwappDxBDeavb0fvf&xlhUeCmx zqBUI1Tm8XOG6kt2%6!Bp89@l+yXsIUh@HP{Eo|_=ynb$$uDhUr^ZeBEqB(wpT0(C! zIT#0X=UL2qtM*801)jz|_Zvp1(z&J~dr^JNjGUb=rC z{-rkf9R?a_KZPqCde<%R{Wbf|%F1{+iIX3zP(dU=1?dkM?iAIHfzkrniVyD7Z?{}x zE55oWb$L8o+8iMl0WFAa#cT2yol$g_c=L?=UD{@&<+LS{mb{x4YiR$VAxq;CSNY}2G?QCUl;+C>tKUi9( z1_1ZKDGz$mY>Hd32dE;luCDH^L4|?CBy1(2`#AV?W#!G@g4_28yWsSXBvm}Y7;o0r z)-t|lk>GVh=)Of#A1IrL_VRi;8{gY>8HNrx7?zlYMnARj=)(sKz7t+|A^j)gH#RQL zJRf^Y_?=b~x;~PW5l(RXA&{RGwIrCn{zo?vOaOAf_Z9j_D*<%1D^KmvH4!3!LN^wR zUWv}QHvGv)jElGjS-uZbiJ3q7cSxp_sgi-=OhY$TO$DmfG`%RhSv<;!RI3@3q@s$?QIpckKvX1$uk%DGFM0HGUo_#p1k;{ zUQvG2n9=8f9c3Aare*_X(cLvjS2t0tN4g%@77cCl-(Hz_x4-oI5zeTIN*rnRhy~A2 z&1;QUA@w-8Zo7K@Yv%kzAfsXBG5G`W2z;_w%Oi@wNx%WUIeVsO$GylICFk?QL+_$R zk37L!6tYAI5p~{qs%O%z9z-okKLXUrZ;<6#f?{uknoc~ztghB%43V=ct}+iRlr499 z#*cg;R3w^}h^J0JhG_aWPx&^>J7e-I%(XMxmlk#%>cM7h!MQZH@KfG zy22U>zKDNqdxl;JW#8;nXPeZ8v2c7PlwN~7SNiMxnZNr3oP^Vx*g182o}gF^S<$!{ zg|=szQ?|`W*Maz}(Qu&tlHZ6|S11CrH5F|YjF^wBZ;N$p6fAeYtr;U;{!A3(J!)Ab zFtTlyyZ*&mVLt^n_(+Cg8)bZe7}!Y6#*Ic$vM|C|&ri)82c{pj$G$(*A^pThiJjKBK zS1Tra&G+wLP*Ix%B|vWYLe0V(_-IcdP>egwQipq#rs!ExhOGrf-#7+K|Z<&zw^5gmSVbV4ZEk=Ieel>)par$-n-v*|}g` zz>R7UaOZqNwFwNj371oZ zuj#Y8PqPuPp+b zuh?L?HPDjl5sUk_cNg_9`*#5|KtPQ;aSP5Ac%r6e)yi#0D*D}LPUaboL;%c=5;?4_ zh}Y5<19D<)p0hH8DZDrn`C;OZESBZXiB@5<2gwJGGt;}|&l9e?@pFPILbZvyy0(YE zU%o z9KiAsl;k<}vx{JnMu8kBA71q~`KOrfauKG`M4D0CjYxHzy z8g+i9#)?in+l>vHb*xSj6noEY_1k^_Y}>v;QW;#a{PX1%&l?o2Im?8HVdTN>l5f)u z)N2nSgxSx>7;nIfc?(cl+}zANdl-h?^*Mr3Mogn0-K`iBRIWujnQd1TETx3Oi}EVZ z@LP{8UR}3d?U}m2S%-PwH>Yx6i&rt;$KH~cAO3(ycA6 z?;bs3xGnZOt^4Yzfw$h7MdC|0#iOv5e)`o{AD4wq^DA$ES~W5TTrea^Yn-A%FU7LR z)JqHxIxeDM{qbdd0BCoaPZz_Vj!L#Ie4H?ixYu(Ex^ND*Z#`Yju*kd^YscO%4pzBgdUS`pU~+#i z0|f=J=F|!@bwMAY#`7-c#_#bwrG7-kG3}@1x=4>tkGury)$2aS?~pqeq^BKz*WTQs zIsX~@g;Q#+dqY9zx5oDew)!9p9}2X-wvRA^Ng)?3EAv<$0QDnWS6xooR~F)+W?g?H z``mZF%8KGK z{(gZ^!KyiBj?uR?jg*ph^e%UDs$bSm*15Ms7_R+5-PH14k*tmjvqD6#h3F_)Yw<&N zRe7w?NmUAp@)r|+h(|sJuuaQVsr3maVSC#g7I*m?94LH|1OF`II6m$uBBLHv%P8E8 zwM^eWFX~#Pmcd;SLuF3opJja@%oemQUo9~SYTbC3k~b5~x;^UmfhmPzen6Q3d`^$H zG>V3kANFnfX$1SPHP#Xldvj_U3hcJeb@dfvwz79iy=0*2d${dHEks<31TT9@zK~%7(HCA6cKD&65GB zq?7f26A(I)5L+-|Z{eW;F&y5MW)u8@KfCwAUBFO?tE+GK6)zn@`htQ+$HwVofvo4o`f%kp=`2Y-$R)gFL(x(J$r#v2xFUS z`m<$lt1hzvC5yHOxN9)~xZ?wNrlS8A^BDMSYG3|c9-H!u$PR?)6o?0Lc4xVPM#YB7 z88*j{$2XGJ0+~_?O$K}X^7^*q*LHl31}7`=M=IsK8M5tBKf&qvM$!T-h#b=fRma$4{$#LFJi>P$Qkwdzz;gKwgi1?4qI=+0l5RF;1xOa%9ZnvY51Jq+7Z(9Qd}Q8~F;$!ZKS`Qx z5j(wG9{7P16urLBV%gCZZnmD_S&--MeMk%c%tmi8U{c!m?z({|T%M+~&w z2UkHCH|K}X+U0v&rtHv0K@>`UL&l#Qz)s_JgP*qJ?jY*=as>x@d2=`HDjn1VG!s|< zY$m1^x#N;|7B#O@$dS{P2X)#4*wWI4u`e=KxG_4=9hpaQDfs zL|KTEaZJ!VQd?z5yXgnhOpS6^ENBV%xO4TfeTRQ2<{~}fb7*fzuTE(3j}dma?b^Iv zn@4VE&*Nu0r|Q<0&%fcd9zov~yMMv1Tq}>@e=c+n8|jE&G!CMF90j{qE=f0>qr%_S zKl51kzcj80tdu>0ap=m;h#vfaN}rsKt++X0T6;9jr&C&CyC)gJ#j8x&zX~fjPbf7Y~#LlvY~mHyB<-K(a56@H`#H^ z$vnEAAHn8jK=^#~)cUClGhUwOl_1Sk{8D>XZ^cy*Nvk2WrAf2iDVj^at624K8tsG6 z;4Dutn5wv>1dD(GL0w%Ph&{{B%Yz>t9{wOD^$iTxE>y{CZhp!VS1Ja^Q9OXNQgurL zakc_ox!E*}{mvxP=5VUtcU?)9_;``^6+f-z$Gz&r4G-A^&<@z2yd;3I1mdSm#A8e2ERNfV}dV3W8ZlbDqoKjtG zQWu6g<^LS*XQiF^j&roDZDqI-+;-)YQst$;vFHVDT^lgO>Qzs{DS9ELFLH?%xLfVV9*uG3RNG+yj{v!rs{@b*f zMXD=aUD}FAc=+M&FJ2I9Mv`{Zme&`5MJIK4^V2<{6^6YzId@@Us3w{+gOQPuy+G{o zt|1Ve!ehPUU9Cf)-RjQ!6n|XP-MS+5e&r(TTi7X`dj9J8uNH;$h2E|Q{2%%=Tj(_n z#q(ae77ey-6Qgh%C!Zv7$?xD#M@qXtB5DK5hl?QO3W{`(em z?4yZhq4yBXRE(m&?fxMGkH(gjhJQw zuwBr$$CfyqZ9J`Jehd+ReE5a)sLjG{sZ^zM@QBjmv8#gUbu8BWW{~v5toL=5n(ku> zZXLb-!L$bM*pinu9=O%Vkw ztUmqS2sO~hUnU$;U%ygVeRT5s&3H-NE~3|b3vg=!$Fe1*qw8h7VwLvvxX2f`N_@R2 z%$WcPR_I&e%#%FW-irQL0E9!R$EO*)fTMDaVgU!hK$R7h;J-ZRL}<$F<*NZj`#^Pp z%xnNtXgj;h)uF*)3MYO!>_m__FKoAS7@%x=aC2}QzY9fDZ=;KLoes2m8760p* z=K`L2!jai|d$)#P0+xBUUJ44B?j9cNaS_g)seHLjFUtT6v7vV$JRri;Y8?f!2g#k! zkRJU9@GNH40zNF}k>UCu0@2-?Xj{vtgWE-1Qwi3MvZd$nh z-M@S&|NOHL(180BaA0cN1~}yWKeo;~AgZ-%`$~5s4Fb|gh;(;%cXxMpcZX8aAT81< zDc#-O4BhcepNM zW&eB$N&@R{q(5QA|MztBAuz{~%kpC4c-!Ox1_maMoKfEws4OWAb#;LQq~xR&;XgeV za?38cKpi22%N-4nMk_Syw)@!G*_kk5IlFdJHUK3Sv43^CnW8&RbksH z_j>z_&0p4(w&yK7F4u$M(BW~|<0j2n>|k!Ory$)>O-Rcy9E6A zXDTP37WqBG0N^j>eWnnOC{Z$bm16*XVSuIq9Y{%2(v-&S*xQ@WwLUh+t45I zN|$)w*;WuDw?Bfr9rlc(koEw#QG-I|#1`-Wb14VD@%7*BCslQIB7ny;K0bc_#@_K_ zeP5mRA__Kkm}Dwl4iKS0K|wJvGWu(jhX5L>fq{X1@9;$UmGZr}c7(famwa4gR~%xe)H7$HuyjH26xRjTN z)t63Cn?HlH#y6mD&|{^wke6Eq0kpL+eEu8&&<+6bszURv0@4s|dCtd={A+&lVjOj{ zYNil|=#X3i9_v%rR}&uan$TMxvIDC-5maL6#xhpuGh=aQWvZ$ig;czvrbgBDsR?R6 z>wdiAe7sQIW7>Cj*Hk3lflIEU7afgZYqLjG>a6P}FJ!2x5;FJ4#U$%#@O@-rtGb5I zSgsN0VBK*4!e|SZTbIr6mikm*Q9{Pki6HTBPP1cpj`lL^649IJYuA-Z#qfwTGq2P3O6ZA(^K8YNk6r0qMvT&2$+96FyzUS58}gOQH> zKGHBUHa4_2k0wfbI4%<-G~rQ_0X1b1ZVEt3@M)^RP0i$%$&uE=J22@3Y)gHakg0d* z&o$^H68$el&$q%0I$GHd=T%95x@9BrgnGZjcxj@Ed3kjgRCP2GrszQeU=im(mATUM0UQN9}dw z_jn_~C1PxhDFHuN@aTMoZ)9R3vHLTp=`fETO0d^$N=IUrY(R1I6^vD6A9?zm=L5)K zu$WaEb-zV*v>=5=JY2ub(DjJ%yewM|!Dm;Heeu*5uxm zd9|*sp9IDbc&}|9!g>aJb>lBYvI2 z#boVq;a1`C?D>3kWzvH!PPJ$~bBOSxCF6cr!pH3P(^MF+-wHP@yoHkBOv-+NC3_rz zkID|2*A7lJFhla}!YErzB&qy1Ljg8v!u^I-vE#Rne*!2t8`2$d{MfSaVSobPFf=Gv zvXa4RXg=h3zJz-)VF~$KrfgAedM21iNK+j7iKo>%GSvTs!@$L|KOy&{-M!N%1Vlu; z+f#L*_Z(;-aCe7Ppk-%Qq>Z2_dx=y&n4G+bi?@n&N>h{&HS`^4J>@CZ;gP3MF~;Y3*7Hk&kx&DQu)5;g49Pu6BH{Ej>Y>~(~FxfW~1%PE=?L;63pj`xJa%Y=&QSgN(dB(27lgbGZS8txm zFc6DR1F<-8q#7@`lumy5*eWp2TZXq}6_xMeY)+Vvck}*Situ}Z7&u_{a5PJ_+=~AV zqj~mqS4MhpJr+Hm)(s76d)B`pE>6U=l6J~DK+|8P_&Vnb-wmL4zO37|T;B>o=v-vj zQ^}P1z5^YA{7s$|qq`Dpi}KRNNmyDq@JhcHFVI`m4Lq@oe(TB~w^MqF;q^5$Cd*j_ zBzBHY9xf#0msi1&18NaU7IbTSww7nh^cE${DL?lIp03;6*5-5eR?EThF`DFz^^ryh z9x-)&|JP$VY((K6-xlVM*-*W8>K2f)TsP_qT}7Eb2sIb%<*=Z}wQ=J*CbS~D{- zN3z=~YkOD`@(XvqRaIdCi*F}~K-h*(J~et{PvttXz^VM#VR z7g$~|3otgmoG3s&;^|(2{3NcjZ|ygIt4n_J=}biiRHG_^WXUZMV~iKc5*1Hdyvl43bW@K&M@Lcl z`5)50d=b9@3i~h=vg8tdlyr1~>FMB~KAo>^Z$|)-P4jF6VQ*7YJaev@8S0XS*1319 z)3d5 z5u4CRK*|+9O|6s0>vM?H4+!eS>ZikFv6P3VtMmZ*w-RPdxmE7F;zp?|;BcC5SA=v| zl`<>g%8T^A_AW4Zkvt~$Y?r1j6_w#=BibQ)LTOAG!i;L|CcGLR9=wSUpo&u-T|E^n z^lp$FuI-0`Uo+ok!MxfT@au3EPh1nfSx*t(td3RRb^^bs*ZeRSA79N6StGCjZ)GbYVUDgz~t{%onget;@ zgRb&nGL+y)$0(o7;R+EQ0>$+|KQlRh9O?Id`2>!ozdV>DM`qm-re3>4uV~js{!hGo zw|b)iPkyrs`S(nabnx9=8hZ(sKV_v67z$yYqxY_K63Om2L@gHU9kHz^%@H}EtP$Qb z+#Fw~#^h{Y3OMA&I`rqC4C$&r!tl9YN73*&Ud+MYl%8GzYq#~n-<&HV*WRx!65u~3qB!{_T3fd_lzd_Aq+G}YDzcZy+6T1=o^ z`3?p%W?)nRHls{~Ra?YFloCMIDDk2?=lPTxLAwFX(PLg9{pZ^Y)A9r&Gt`PRlXYCl z!5?@Z(xIa=0{3Gt`Tc6VkYR3=HHJWHPuCXsV~RGl-*51}*jy=>Fg1*XePZS%>!*E1 zo?yG+dAS1Uj786~&3ReBE)m^#!qH;yBXz^?TFET4PbR*LTUt#xp-~2vq;VSWZC5K< z=7=vu*Jk@hMcX&=MB_F>9O~>rDKCf&Wi)EpPCxvYH}(Bko+vUtr;C)0ykrq*%SX^% z=5>v_NfI!l>yMNZpduepQT=xGwc8Z&Q}_3mkUBg2B*AFZ(nrxt|4M<#%R~xIF9Y6X z#2dqv&C=>?_2ti{kqTi{sE?=HX`iFN79Y}mI*N6VZH+i1P6e``}X#n!Tj6zRg+bM3z(s%l!%{BBYN)a}T2^*0ysb zkFanw-8wuwHLE^N*1o`@(zl1~LPKlG9AQx@*}>umH-d)v{qP0)S!f?Wps9D}4pyn= z8>wWzk;-O<7 z-Hj163mt@=BMC0&>;#DamE2Bu{E>6?x;@DDogfcoR;i~Oh^caU#H`4YR;%Dqj7XxL zWuJs5iw$VC^UkqB;7GjQ=79Xg4>ob@ngGtt2v%hTXbX`5e{f-zujK{HyKfR~vBvZPXQ+5K%_}!!zrpkv?)fnrv^t2`XOQn#zADFcHizgV zX|)hi6WqDP{YDUPDdm56A>hh25a7-dlV7hc{jn-jgx~|Pf}t;IR5FvjhGFz^RS%|CQPygbnS0m4H(6nN zmijqsw7~kK%=OfxB=vaUT*j5)FF|ZI>5h=~BdLkyn~+{A5(8DE-*Nk1o%_j6;%}@I zSM*ptgk;afm?m%{-ms^+Cre zJ|XZME^tJ1&Qs2B+k_&1%Ia%iLhe5qh#zimYGv6pTeKH9!F)}#R;x8)AtYi1BNgF_ z_(EhY_*F%1wgOKibgxM~hPKDE{eu8JmQYIrpF{()+qEtBc6r=)`}X?J60@@J8u#S& zeK&YS_4ecO^0jXW0&GS)xk%9>O$QdaInX29mqLW1+0s&eBh74pW*_lCgi9x*3z&>{ zG}G+r2^8ZEZEqRUgd#Nshtv^uh%=5iXas`e%^n)u%cX@BXY=;*9*nF{1*>^Wcs)u4 z`?cjcdw(FiUB4PdB`Z_7mF?h^ZG_hjF*upbsS1XY&u;Z6s%S7OWzcL(Ar-OW%f+`I z=zaiuzl0g~RC3aW>)*HQ6@@siPFaz{xy*vu#NCV_nRNiQct9)UbNS)h&hY0`7xK$4u_Ibh%A9C9ZR?fcVi{7XoQ++kVRQ~fR-Q5)V{gvH-!lKO{p|M7Fftb^ zA|fB*4N3Sf@VsS9W*nJUNUz#&BHTZXg|GTm3*)3`>?<|j24VtFpQW&d5cb;@K?dup zR3-BUd*QJ8DyRp%Hh#daga|8)#-Y^mrx@=&4NI2QUF}0_YirK9S$+w#dHH6WhFdm0 zLn-{9jjn#2H4(ATQdUOj8wpl(`vbI!&e>2H8YwAHw~;TI15$egJH@B`Vw-G2w0meZkBx$GdXk}gFc$AKj<&?S`lAx#xyLYM31F1uMUrf zb5L*X8J~NU8W=s_bI@fpW+YkRpMCVWcI2Pw6+yfHPk>29e&c&nfN#ZPQ2SuNLiYFm zPX>smE;NVsO9FPL#FZeN10%`dh(^`ItY`aIW7QgDzF+$uKN}Hb^+k+|{?bklE@mb& z+?S=e(h1gnfm%=24ejJ~r+9W8K};llTz?NNYqU(bFZGKMq~y;2%I7RxHxn|;5zYE* zBxRoL7~k^|u^BCs@ssZ0cb^E>TS!qU61B#LS0TdNhx(4_D^qEC2?kkW17!^#5~DR* zkVZp`<OO-nTIfb%t!tr|j#NY*b zkU%UqmbBq^sJ)*Aup{wX2oOizYoV%nTMJg9rT$Lu{P|ie?C9hqWMh-pPhTJWSG&jw zqy+LM(Ik;gFEB>DlnvS`|L(s*l%Q0#i1RT)mf1fql=pUa-d=iAt1*C737cen>8gZQ zkcWU=I>8HmJ_guX^}|rqC2$^KNLm-4!W66qW}f7Y^zE%NFEgfqRAnyj**FjoxlsU1 zbmO^44P}(DN+3|!Q(o5=GgS>XJm|!{^?5R}TJdtn-TheEE&^NE+AQ&X$eISQ1(|MW z*Y;TMeolALXMZMb!{l2J7^6tlTLvATUiC#Xcvn3{CuV?HD*1008MF<2=L^`Z?(~SC zpO-X_`r{`%O4GRsT68*ov)`_zJKtX2K+Rrwgm2h)y03o7awT%QP~}hmi8@%B?&s~u z($)$GeIB$pXp6B^u@a@*uIo=mA1zoMxWrF{fLRrXbw%y)aVI)6ayMwdM;&CiJp+NE zlHTS0TQQAA>clbDoa#n-!Sv-!;;xJ=}xkxQzW`N`8)6YA!)Gm1n6Doz7FQ3 zE5ED-!ntG-o}Xs|bWN6C8SRMac#3!xGcc@nxhPL_$eD5-zZ};%cAB=}Z#=|}JlVUA0S(-ay!UNd+8Ao>M_lk7$8`NlI_c#Za0``dh1ZMnDeVwn2F(~ zUdU|No8e&CSdC#qMW@I&8OssnsYil#~xxq_74*J)j+!a_E_cER{jRlpxR79yY^8l#jR8TM zuk{`x`qA?6RZ;+b=7lKZMV_@-smd?YIVCRpV@K0}ZR^qwduVTq)^e(j=ipy?bq25c z`kU2NoKY?&w3qu?C9ZQZ-b>J`^w-Ek9glr|fQ%sgH3S(saR>MdU^mNH@1?<^L-fwK zpz|9WmiNYQBp0WzFbx4|<}AKu)cEpWwqm&~L&e%eQQ2eAgdy&1&x^8i+4jzNPlt;C z=wWi+U z{=V0cmlv&wly-!*xkd*uer)TQ^vPI4hDbu%MKtvX;fkJnY4!%Kyj3K_re@d+Y9n&8 zJ%Ql?f=!PHKB=Oa42|d>CZh88l&k*rXgNfkpxNFA!FYmj<#=^JYs$jWX8VN8VX9yK zt0{)-8AYdid!m3uEpZHn^b&`i0DX(FUUUwGRm1pVsqZU72S8NFc+wmwkP(*DzFZE9 z+l@YzR*LA5|dH8=@*eCZMD``yQZiE!I5&pbD>~WM#1n0NI7lgHKbA zUIb_dUPWNSKt5hV5g;A^sA0ZxEU!~osHmuHsNC4tu#EZGyLa*_$iL;!0J4rS?juh7 z{0XIQLFwqlojdny@tiLrIvK5Y3kru7TH&Q*pg?+zV5q`&va}rK`r0xya%j_AW&mew zzJ)1Ne~6sXs7CeJGl3*X=z)nm|1cJKoh)#Q7R5qiD40Dtl45tnwPl}s(vhLrk`nJJLhC+6<+VC2O-!hToZID%cZhtyB zDmCfv|1B*OYp_n&c=3@+VCxLNIEb+&bhuk_bNPMin_nx4PcKhkgm!@Ij;!IJtidVu zcc5QK<7US%y@bujkgzHasY2LZgk+>J8K%!p^j6UE^jG3C?rQssQ_F<_rB!_JZ~7F2 zu8C1psz*=3=?nH2N73mk(ki{4+1s@OdzhQjW*aiG=okTuoT_5E4gstd(rVt(z9=#S zgL=5P=&5UmjrWp-m4*{5u$jHG-MrA@$QH$@tu<%R%wSpSA-X;Fd}W#;`}ZDW1;S?H zH<%1hU7%`%bteQwr%K*BmNVIm;UphPKIdg!^c)y7is#-zfdzi;SI5%-dF=d+%;o1|m+96Jxo`Y11lTlKFp}oN;D5Tjt^(g80i`H?2%SlFxjf;6 zXQFDdYkH}MHtGL(SxkNXIb*N;v1Jr1Z5ooT`dPgtod&wHFe8jC7BO^}Ir#ySIazGJ z9^%4~o?`akxitJ3Uz8E`Q-$8Ka`n+$~thf!!nA=PGm_A2}H=t-x2=O(PK)HI}?slCP zlsr9VTK-1O9Dv#D0dgH`u!e+-pF@khM$>sm*p=VirK$;`C4~24uetcP)FRS zM477WLQk^V*W2Lps+>9nge0PYW@mjmf%5!b=AUPH44xy@`TfV7JG@AeI@vKco&8fn zm7S&VEK56W-e*$>IMPwg2;%MDQ8#TWgU2+|FK$e|cl#-|_N9#1Al^OPdj>nynO1zb zY0Oy=$5wVh0;%NL9?3FhBl^ePHnfq8qE7eg6g<^Q{Emq}tl67Z5&Csg8+|sV|Mcgb zmxI?!+~C;tfc{;{!P_6tg9eN*$?J=2?f=Alia^Xag2G(;SLbXzz${#NwCW}RWO}R1 zMm;YB3R~K2F~_{+Hkjd0QxZuPJQ8+$!qN)pBgkjw&X^lukgAD<$+pMmI1#g>ce zQPJP;dD7mLxd^0$ao+ZTCN7Sv^f`gXN0Y9s6HnJh@T*9f$48oefuophwKjT5q~F~Z zOR{0fO_FvF!A#NUo$;h{M5gIh1FK`aQY zuPpq;n7sTlM<221cgOV3P*VeTimLj4xxNlY9ai+LD;@M1_@>6y9m~{HHzmfs8$CaG z^ScfCGemS&z~JcKfu);OVUM(0cgo>}M(=oFd+r@+RKdFa;AgSLdW|ONug~2lX*|MS z>3pyTt_Sr0c81w=(axN+-L;{T&Lu>C_|=>WuLXXT-)M@g&F{)ccfEfnCTdQ|Fs2>B z`7qx>IwyWWaRu5(NCiw8$F#8=K|7SSCEK6Eu*WOvC>NE1-11*VdRz;F zwz0?i-Uer=Tv|R!F#?VGBKuPK<*yS7ARi=8UJH$7C6O=n zdq|tDGCQ?S$sqq;6yOPhRXdMMo1_07(`7?`U9W@0gMB}-%D`8qhWrsN&nLBWN+8UZ zz@7FDoHYrHPw_7BUm%(6W<{e!VX%NDzci{v|L2*yi5q;Ghz~hbF397G&&7*JYl!39 zKr#CF;ZD6B7QTbYu1eOXyBof5wkQGM9unbCKsUl~>7hQs*r*WqaWGXDIo9%tg`?V67XB|sXlxV(x9iC)D3*~tbKjd zZ*)?(+^b`Jt`gpZ2kAAn<5M&lPgYx9aFn@OQ#XaXcPt25xw%s1I?a-#_ zLN!YwTbRXo#jwt#?5RvF@4l`(M9@Tk5*rc9SX&J|Pi}9jHS}#35fxV-3Da3^dw-ZZ zmHy8j_IhD66Q56+q>@A;ok>?485#L%|7R^v7{N3m$q2YUNKa2szhYYrfL@k~$I}zT zs;a8E6uiUKOu*Gn5uJ`@9t1?Y6CVgQftcvSaLFBG<6pd$y?4n+YGF7;1b&5b(Pdoh zVouFJ$$m%7hZRhk8Y*Yt=c!1Rig)?j?i%*yTI*T(!Y8PJS=Xk`@xsHqex6LGx_fKe zQjIG=QN8sqsrLBC0qWnK<6FE1jlY{NyzLx*ip0JRL}9T)@Ze#C#C4>YYH$e%S7iX; zv-yA>XH1O3wzs9CCmS1^*y6iIC%&A{cVs(A#V+UmzS%jaL{|_2P_cr5WBNOv8cWide5zW^X)A&Z(tbeu|?z$?LS*{oa`Sj z8RP##!@TaV|866FEr1>Z?IA{F-5pB{NZZ1Yl;c~!#wU>*sm`kG&5;dN3 zzPHeS|NdP7u*1Oz^B|#NREc2sbQW+qXE(2qQ-6Ov#Ax35BNyQyN(rdx<|!7*u(_V# z2Xu058aR+Ics7z88X%P=v51L@#a#=kq7i-nJv^MO=^B&#Q1XQm^?GaZ_OThD%DEu& zym(SFY+LKQWA0ofH^X=n-p~40UpH^NmGHPkR?Pn~82D%1`Sn_UQBFqzLXgyu&D}-l zVPtuHq#Z8`vv6W*U>wuL#N^d~ppL$g8N=3E82ln)$N8bSW$Gev!=B^X^z)$1p|P{YL)GPHa19V#oH0& zY3Nb+;~kc`hHwvHlR2Q8>j^sCYg;zp>g2xsj{Iu^{nxV-BvUe(#rM*qdx`!7(n_}+IG93hyFoUG8C4S z&N51(erKSoIskEr3qMEcxAg0eyB`cgCIi4G10VnO!+{qTQu3&g39EyzJ>Tdg44~x3 zw0bwXkR_{t_Eoo*y94;Nt0ROZFQ0aRulQH&@ZSRjm06-}Y89xi_HB_hVc~!QAx5ot zyxUEyw3s}k;ll8TTgmVz!}UJp)fEztU=5qQ`WC-MyU; zD+>=_SjY#h3CO^RykJ4T&${}V4NtgUSN&j7$X;lY-PfG4gHO0WfG$qk&5P-#XUlfY z;2T{W^%uTQ%*_LaA3p7pg?lsqJqQ21-=}G{l5AXq?PpKv$D6blP`cQuZQ9(+h`^&0 z)0d}!q~hbbwvTZ8+X8w2)4Z9h>C5z3*b?H7F0gKr6o?+baUIX5dlDSFgXovOv}+MV zy4qXz;FqRt@B%JYBG*~|u$guhMc4WgVP9gH&lo=WJUL8+-MuaL3tIoYM8rAxlJkihiwVw zpn>=Qc#JO_Z|$4j(OZWX{B7IFBIJ$BIhvNU3;x9Ltr9r`iGa`G3rc%n_w(RiHjICD zntAK^*7Lh{%LbPfuiCv=#yW=~3S^i?>#kf4R}|2^TNC11uM~LP3BKLQPYc&ALZhO< zw|@!bsiF=8m~2}K4--7rac#TIWlx#O(v8hAVd|v&CN%ANe#W zWXN!K&w#!reN)r$^{y@klc6U{`dO0CQ$#vCbPb@kHxQ8Sd4kZUw|9+zuN!tIr>h@O z--kljgHl!H1c>aN^Yb!uh3Hb!$8!49Z&e7j^~YC;c92f&PI$oXVCC&j*d;i0cArUK z`5bC@SU`z{7{CFVKh_a=YP&ABC7O0s2hv+_Fx*Z;n(rcOo+I>*ibl&vDJ8w(MNfYVL8Nu zAB@6<;EyA1B3~{t9Br0u>RXGwRxdalN8LvpvujoyN2hP@vRtL~7JiZ;;IRng)e-2= zI!jMF564AK$6Bg>kXUa)F$- zx;kNCg)6}O1V7o1_9llKlF*XJSCW5i2wY$|2!#B8TU`d zJzmoNU}6fIRh?J2(vp&T-k5RErw}4#;$}DHp-7w-P*Gv&>?E<@=;jrZ9qric8yAz2 z5mZvjVEDa_6BaIxa&UX6jlQ$ocp*e-IrUqp7#$sbbRaR93zrcQCJ3Zi^{?Cl$eWMV>y0MYxmyjPDq5_w4+f zUS!70%`Q*5d3eS0eY~}OzH|#)(LA9zF)i&ww6fyNX7!e(shU~M+0;4Ak!yD+Vs;18 zY?aAZRJOFm{X5rifZ(RZYHojqA`yH;O$ zZADh=9-%}|{VZY7-=|157aByW4|fdDdxoNQt) z__VV^=*4NB^O+yUo!e+{w+@#nL&_f-y2@-uBuLD0Kv|U4>UwR~Cl~{QjtDlEY2w4b zhLQj^0R;uc?ZbnlV*YnV78Vh})c18h@FAKfwbTY7JZr9dc4BF+$o2XJN71fK{)RA- z*>ED<`NS9&@j3x|3T^lO`17>a0Q4gQ9Xc;xrOMSes^L+=W*`S zJz#`O1XyZ5{!dHQcren2mFm?n99ZNj$>O%R8SCmGWhh zTRmTX8Et{MQ%x?!oY@LEVOu4}81Dfp+o5M>6nhS7#z#xp%TfW@$B*1#XY*%#2z#WM zaSG!PP823cHN$vwx=4GsEj%)W5BW!j2O-mT@dx(7v&LPx+Y3We(*giX!ubUzPw2bq z)VHOWLEJ0nZeox}srAdK;9R{iqzMO(M6yJQpEK`IPbL+w4T$X-cwN(;Z{+Yk+|UTw z^|+kRw0b@<7#XKo(axzG-zJUN+RpbvBN}Kqugz&7t_Qnh^^y<85b(wPpZ+=F1;mU~ zlaz)N;}X$I!cNf?FoUzYL7J{>TX+aZyL78jeAGY3hxSR;B#lYH*?i~Tl20gonPTRL zHctXRqmni!y?INL-YaWprobgRAL(U}Du>56d7RUU5+68H_L%R%ooc^BYYRIgO7DGL z$OVP*o5_nIa|(v??=8f&QfX4Z&(~-UOKzsnKMIMhrpzz4x^BX@nMG^D#R+SxgO6mX zz9~-)ap+$Fy{Qj=(u-h&u(_gZ@9;TUS8w1L6&>Z_?bviHR8o6uahS({xMH`;gEy%u zVO$ygj{MRZk=tlv{*J(oV7RWn=yUP#PhVt0fy~PFCKeTHMQ7y55UK_BSV>p~`$n4Q zYFYMe|LiByyB=J+i%6KYk1RO&ySI9MvWa7L0UQX}X*hziMPA?&G|9ECXV$Xt_H()c z6oyH^m7ET3Msy}of0z=tKuZp83gXmUt3GTBu5d{c{61LJi(ABXyQX@9kCq`&1l))9 z2XV3H#Ei*QMq%l6c;@PR(CNItcFI|U)Rn2&*6)}e^X7~j^Wc}@j$q_GSbAFq1wPP~ z=?0^(Z@WA4{cEL;i*VQ;z%-YdD%WI1!2JwEz~O`f5Ucv&w!JbAr~0A5p`83`97UZ# zEAIqDocL!e%1@skGRGSoC3BWmR@ypT8g_=$Hv{_v8LZcZ^yTE}Hm%dX?(op3wGbvX zW-HMZ)pdgSp?(fOY#i!xGalx}GTi0Ko*q}0GHB4_jw{qozzP6LWyY$m;!(BcimWtN znG8YT4Jz?E2yuJIPs2Tl+ctJ9cjyg+nYUz zR6nP*8h8^hU4wT>d@srMQAMa?f-tDuI8ZE!LLo7SuW33W+eCeQ;R&fisQ%gVn>>a; z^`37ans?3ndjte%nKKKIk2h@@RLK@SW~5RviJixDjL2O*V`<>u`xyTAoB>}GKWOaS zQ$Qz}X1^NwawVig=(;T?k)b|VNsT;OZ}KM(f@YNeE^a;bm5^V3B<8`HrQ8-|#`%0; z>SK+__u|*3EzBQWIdp!Ga(eBN+daj_eC5}J08oMhE&Wg*sFhr+pKr9rm}0>b@%YX| zUFUXK{%vXHw&$n`vnTt+3?`J=a4=*2`T5t+hHwRu_!K?AG7$}Y>|yV4z4lS*z9v+VF>LR#Rbg0 z*Z;FZ{_i|imb0*+K3QrEEGwhUFDlwx?+O)g7YInxr{m@Z@9#GUHf25y4Gx=CB*47) z!`3;%b(U2Q7dyMUHRtPwyWnI?r0Xv+jB9`CW>gr3olBkL}fpJ<3>6Z1-BBB33|qcmFYL7KMrwFoCPiO z7Pbo^TjZjE9!6q(Q0TMOJsI9?1vC@k6m>E3ph%O|vtY(WYeexBZM7O<-vLqAv>RVd zHS>A!jpdZ+EMeW)XjF&#D&H7*r&z7Y1%Zq7YKp0v!jf4_DwXk3{&yKouZc-04w%r@ zCU612T#nWjF1wwfR6ASSAbG-?>X%ywmf;Y^RsBd+=wk9gtV2oXpkLsU_hL-bZcG!Ba*e+*ll%O=j&HFvdp*4@L(E8e(`UZqbcQ!8xiUeH#P*Qh%L5a3-gRm4d~?6r$9bLnwcn zcLM_Y-6P`QTnrHyUZvx$)LB;7E`y#EatWbcyMJ=EaqFTleBoV$vxyHUrdcC`A#&uT zqmP5=#}c0&wAqJ2<`X_ubKZ039peYtt{j@t5#6vYv#QGTPc-vqIMIZjZu0~!ylRxc zB|(}|Tq8R~H^MYM_FvsK%nY}L9H-KcBh4p#bi59bOe!>kJq~!#dw8z%zlT4VvU0iT zU{%^*4XwXVN{LN6Maj5zW?^|I)!~=MOR2c(V46jJ{*1ENh8;_lmD&UPvB6P;>ht(x zsfvc2JyQ682l$^WINWMK=i@>K5A!$b5p+LtKaF+uio;Cpez~`tnF{guC$yNY2p5T# zVsNoSo?Fxul$1nA#A_o>VrNSu<>b_a8Hp{k4yM3yK3y}`&d09fd%A(jF`q1iX?z#a z#H{X}NM5X3nH9IZIYDr z-U#3Z(>XcMNvd#6{OC#0vUeNcgf_$OR3hV>IpX!!*Hn$^drM*8Y{h*FQ^FI)+gF%@ z^oB{VXmsFm(I7>k$PdjKfildS_h<2_PWDP?c5HWUz;wtH39A%n1zY5?X2g6(WOF2M z?K%02k{p}|%jwe3H;Qh}wYB*IB8uiMY?nXZm#L^gCPrt>GYyHU zm|R~`|7xN!k`bM$dnF<{xu5{sHPcn>Zrfm+9lal+gW%n}X(to+?BukiK76>)#a$$Y zKfvVHF6X@xIyxc0XJQUP&~q)`XVNnxzek3-EuU+cP2*+x-mSt~T@jiMm|GYD;3tzn z=QF;;7sOuLWrTX314qllVXo-WHrxP}Lg#M%Q;9beMn58!c4Eo}bs+Z}}7&Sjy@_nWvi$m_Or&W>n4ZoK?!;>I;MS;!d%Q(N5A@t{41&8M8QA*b6*>qhlj!H zcpjU^Tve~|cZ7yAc_!Y`D&#Egf`NRaOQ(Ea=!CosA|KMYeVB5=kv3n6?F3dWZLX>Z z5%W)?L7VL_FsjCCt*Sh##z0v8k2$48v|f$s7XJu#lSlOaLAj2BARV7(X!Fax`;Jdm z0WUQ*5+maooBaln{#VnZUH_++BY;>+Y_zi56{)!!pM?@VbZKN{YV!VWUpps*M%=}h z)KGB!>L57Xg6XL=U3cpI?o)1VE`Ti#Cg$S8AI;{)njz!h&`_i28Q!IuVIm_FrldIm z<^zxKOS+qbf5@eTSV7UD6)gHSE`huBpL4KSf2(D%2-mRPmSNBi#5u1hzHGB@DP$9; zdZ!%R^Ym1C?7Nu2v1JWZ#0<%z`8Su=6_NRxqV`8NZFX7$-?QT?8C{+}*t2N{gdIc} z*wR5%^aekH6Y^*_EHHeU5IE1ARO8vSyga&Nen;T*0b+u6ZwW82TOy!+iF^L>u5-<~ z`gGUc>Cp?j=}d-~k+s^rngR+Q^nhD|XZw!cvpS2XDcX&QCs70b*HbkscwFUZMFF>_ z2yT`(SD0{~`a_^^caG;5s}NL;>jVyRwd>xcU(xD#U)-D?+wHcmJbe87BaunMUKT@S z3=y1<-_LxEt}S)E79V}uc0U?k<7wo?-K)CdsS#Y_sf$9@J?hYnooB&y?g)}~2cck+ zaa>C%$gHg>UTgH>TjNCv8>a^N>1tJ*T{w5|r*)dIK+)plOgIXIG!d|^f;GhYx;6*T zCV`-AF%gkSI&{^rB<90JYcyLdqVLKkSvZUq$+Rj$S1++b@o=4_yg+dqkxg#{jin>X|K_>MmCq&=}<;14@A^MJC5FBRaShT zZ1zoT-+_V{_7!I1!>!{e?b+`8LJ%yoZfujY-uqbowUppf!l9XmJZ2b-5qnK17v-AF z?Xvv7-E9%xpelIj@)T}|nhW^3XHbXYOW*sw4%}+7aDRD%mZ%m#@5sJtmgZlcSCH%d z;I$gpqPrPI+)3wis_LKEhEyl*`AQP`x0O0PK-aXniSfi=ud~CaHy7Ymk>h7&cccmB zMLs!-zMhy27f)w4?GBaP>vX)RC_u2;SYO;VG0q;N4HAB}#Nsuz42mcwBv&N=W5&Fm zd5$tN&Y!P7d?H3mC4|`E9};}@eo0{P=6(!e0G)3y!oW3AKwPf2Jz<-Uu5|Q7)(4sM zfKqjl;EZLnxJ1p&iWyp>qWK)U3A#fd-tXK~<#V;tBsr>9XrcDr9bO&Ip53haZvF~{ z?rZ@px`~_HNfLdnq%ux%pDx{HGIMvZYQ5T`m`q33fKrjw6FvN4jv5xBRb?8m#~k9I zpuBH+=ZaHcoh`fCOz~)cS)04&qrkk!q3j&<%ybzu#!Teez1c7|RYB!zT37eN+0}h;xqY+2Ls7N(|q` z_32Hz>M5oIacoaxwr_{q%^R%<{mFj$+wBN7+4j0LnbtEq&r=?;{@H82x*O>_FP*R9 zqPyUycN;Zsy@gI?R^2iPMJ{5QD7RIFsc35I0w^sG1Kq!zKUQk}T5#o)RICfHf9^g4 z1$G}B8qn8VogtviG}~Xe7~~`*5O^A|he=>mTryZtr)+HpOn-md&?)CMa~Ag$$zWZ; zOR^ne#%T=ewZle25!y~7_>eq3chU;gKjE@*X8&Q=2Q^vd;kioxf#G6?(CXQTeWRd` ziJm?*yND>O>dZBr2J(>Rx1rtH?)uzXo0^yG`Aap3zq&L?#d@WHOZBnGn$7hi_IiAH zr_*_@HJb|;wzxT0LwiORkDONjFSgS!;4#*#z##?v#*IDZxGf^p>QbA=oOAYC1+H!t ze1+oe%{686Sq@@MCYpt6*;dc(F8QJ?M_m<82}Y9@J1k4|tv!Hnid6WLu%)?J<+8*U zl+oT%*m-uo#`Z|%RLBr2teYdTAM0(Oan|wMA3V6v<{jJ60;Mt(%ZLK7`!Jvpn&uDW z%l(M4nQ%6RRvEiLOFF^zUt5%qxOgzdDyc12G%mA+SYD74 zR7~2l zj$5$9Mvew;6R=!C%jzH+R?85Y=QOyh6-+k7Vq?5SKG-U}O%0QKX_+MMOOf2P<=bk% zy-E38VaKJl2NN(m-~SDQkg&mT_h`EC!Rr(n+Wv~X*0hhDfK`?*MdCc7v6gMs^lrV& zY@NA?N!UErJ2^R^W7~oQiPHH~aR!_kh>`F#)dGWjVii7d*G35Ep=&#pOmr!a5C1eP zifV;oPNR(~UTmk;aX|AUH};J62kF;@-v6$n`P6Ib8?f@uNtaz{F-^U!y!w?Y> z+0V6LiGt3OmWs!bLnYDlz4EcIQH-U025{dJSDdF$;0+N_F{2e-RHs)ks%et z4$P3;nwZ5XwE#rjtH4GX{0dtgh*@2*bI3uH?=I9d$jP6-J=K1y2=9zJz;iugh2S=+ zj9&P)l7JN@a+uP~Hw3B0HB=N?lwy&c62W!N&0S5u+m8u}V5yZq;5UfNd~tyw%=;7& zra<`1F|9hkVTq(mt-XuzpgF*Xh_~9h-cF$FBcI$VB-nzv=vt+=C z2zLj*emc`%Ou8ztnG0!f&AIxfyFBfmOB76=4aREig=oO}p7&TJGBeUq6iyzqMc^t$ zt_Xr>6D*@+RBGofsdd6&PbDc4aU8A{>XFKNz{1}_aj5gle)S+Qm~?BqU8p*l)1Z}` znShGEMTbH&K&4JmBFw24=!3bdC6FK>R0=`$w3jK%%)9Jc!QZ)Z3v!~(r3)uBrU=}` zC!+l_@h;?C?6xu^MEK!iXU^wK3SG-Vx)Z97<4>&+6=P{y0^De~>+|ykT;jvF1^sR| zVn;7$Wy`SgxPoV6hyTadTgJ7uHGQC^xVsb!(&Fx}EiT0hE$;5_?p}%(DPG*&HMnbW zDDD=51a5ksa~`?B_ug;tAv=5TthHw5FEcS(9}ji92kLr;O!jjiV9M^z>1tktY@MeH zIA9^_iT3xpMVJ0){41viId1Ff{*V!e~+j~t%9lX~AUpb;A zH!D9}cy~*gda>c7{yAj+v#3?!iFl5Ya37z4zN}NsSUN^ z3)C4>WM&B(9en%?l%tk`4?{m@P`GvyX@BuE-x7X;fIuL& z|0y&LCY*kCiDG~zj5pbCB`{G$**KX7j8?4Kp#@J0(RU01^|0vA@W#)+yeG5Xl$EG%$ekV2B!8!6>(lt_@;;F!N8|I>8kYMeafD zKg@!`QR*}K7QRSW?6nl{s(Di$J3yb00dm;r_X8inTzQKxX_jUS@;ane ziJdMG-KrtxGIvPvq}5HpUJD*aYv?8Y=;|MP@j8_@jMlcc6l|Dk_V))foyH;9Fn}^d zpSK5+hfAP{J%Y?Q)0M8?5WW(Vp)*%l@}|C8|)@U2g~Q%scII9Iuz0YM!|17cNzn zoX~ie9ZMJexCGqmLiMgRz_#ra<6~8g({J5`6Mxxo;e*OPq(D5eAtH zv2px$2-NY&B?rdV&5ccR;z4du^9JA8KRJHSvJg<5w*PWFCeHe(Oifg?_-#o0KHKd- ztM1QV2~DGACrm?0+0@W7%;ewP8g>zXdO1ODZ7ntdL8PF2HgwJ&Oe}Fa1p`A|EU<6# zocL?ftiyi@yk4%HNyHW*Ne@hae73)o@59&d2k$AA<)xBn6hqvier0w_^%CRz}v%GSTj-%kI>>4 zp3YVHNtNw+$y0C4%6b)lCv1gEU#9Yjzml9;4;Vl&QF-vpf_b(Pd7aE1SdH@>OvS>Y zL{y6N<(xN{lOQe!rcJ_VLG491JbqIDTM=Ht-Il<@iB{mNl6oJ$Zr|^;q{jo4-OfVo zC`0}0qoc5A@bD|60K;?hGAJ(16}x`HKdb)^*IzI9alg;Cg0GU-Q2?ae7-Z$s_%uP? zZm~{;enuueX<1yTT5>968k%@S3)f@46i4;?x`AzKv}02Vo;|hZX{UoPKZP_i zE{@LTjVf6-r0dl%;i7SM+YLB4z0T3>y&-+kvdH-`sD*2O$yLBdYJVdfW#my%^D?f3 zVYwfFiG2ZqeqV^qPxiC(`;~6fc^tH+g+QSZz_FR<&ilZ`lKg4oeGV5jManGv;3*)t zp)K;?B%f1gWT(S-o9HhyCUGICOKdioQ$2xYyI#c3OCn>M%2y6u@QwQ?eWqz1W?W1f zzdi!}B#G9WvWZC26C4}R}#!gs3Yzz**=GlYW*q>%X7~GiJvm8%6nz?jmjP+gl zJx_wQrQOb$SzD6=v@~fHOD;FXvg44`T8X8@xsz$G{rR=wrq4(Ih zyXo(|$DlKbC#=9$wdiShq#BXuh!C8diy%@=n<)%!OjB-AuT zPeFxr&Z2)E^TW}1*|G7xr=!5?>pL8iCuo8w6}aSfCi0stWUYED6oFumTDiCGd+`>x z3V(Ii@2^ev{drlG5%?S)oL5>QHBF;NeXqQOTu)eD5gNM`EntKB_D%_dE*SC5PH-pL>FM#J*lT$)(z$Z*r zVc4Da!K*D88~A@dJwMme`6 zKbklrLku0AYb;6(+QBb_*FMhe^cU2<1QQt<+3PejGZT{bHG|ulN?16nB8QS|`4I|2 zW08@KFRZ-cwwmjX#HEdDh=KBaDW$$5&nL^A@1+P*Dp;yehE`wXh~NF4lBl}E^?G~1 z+NKEZqm|#9kzk;)58MWLe+DS~9GRf>!*BAUoX}Q%*CU+!?(vFK^!zpKTPg>A7$`H` z&J88{FX=On>PD|ZH%5f3b5J9HlhG?qn?C5=a8`Yq6#SPu<)7SVo!F^G2PuV@mzOYT z+;fu;b8f#%h%F0old;H?jNE1tc%P7w!BF1=yV7!VgZ7rTxW*G%MqVCxy0TU7_f}g9 z!J1Z^?q%b}u3BK&RF6gZY3Q=?zk^RwMc-_j1V1o%KR+)oWcLyZB?k^8Ds~h4au!fJiFjN{Mnf~}ESIdjxxYNY^2J>>8 zHwM86njKj&y;;B$a17Mq9*3p<_O)3Jx_~OGjVFg&#|D(`AO>;&R!>%8Zn@FJ*kC>4WgLg&rrwS&A zT{*hiy1Lwo3V3E_#e)M2 z$U7eRtJFJ3lS@LpCFS+Bu_bT5rs;}{Za;~26#59oB^vtjKRwysAjSVa-v4}uUMizzrHpaN$34HlKTod?&6x}=Ea()m|9!>( zx_~M>7oFq3qR{`xxBE%$J+RgJN@q~n3qm=i0nJ&0T0Kq!&=#fz&#|;&^}_`!k^3X2 zi*V66dm$5Q}6}67Y{dLSV3dO&wf&aRNf8W-( zrkHw#g27^WwcobIFdtn+=|=>A&QIbtI-7OZW-+5F9*GsZ*&6;dy<$0XCk{1p7BW;< zE>%J?K>9pz6ZpR?`oG>drAETqX3@TyMS)P#Ld^+_w=zy7Z`lOT7vpdX)@oQ__RkIXNjaiSw^VU}BbK`R3f7nd%rhZ7CyXbIL zWO|R9t9D3{_l4n*k{sd=6QnuOx5ka?;5{G&cg`0vBy-s-E@NtBV1|sV>!tJh|Gs}L z2?pBi+iY6vNrg!qjtE(30A3a8zOLtEFU@9&`U{JmKEr!lL-^ zQ>{7ca@O{EbD*+EN>E1Y7l{-|gny2tnHH)*16OWgKBW-l=4TnE+Pd1%d$033oS<{X z4C2k<*nJB+)8(qsqe~*^PNwIZSH`2QLo%c9$#8Wo7V+u=tu4eXl14{{aE^%6k5NxA zZ@1q(-5$?NsapuGTNbdEt9_AZ{blofl#SM%qty+>zr9z3@etN4^0*4Pf=;G+<1bn@ zy128pa69!3Yi+2fL3O4gG3P~yfRTdr2*bXdh_uo9T2|GbOa(zt7=k+4#42f1um1k; zUv{^k=GcW)w2ssq6w@mvT$1ojhBcnmG3>N&=h!R1Q2o=H31qX=7BMBJIuS*$spO!B z7RuGH_AI3f7jUThuxR<-(8cY&`BXQ<+vhW4MY?@lJx&HOQ8i32SsC=bIH4b>2~pQ} zVa*LQbq9lMeVzVDIIG^q8#8a~^+Kc4i54$m+%Bl&kK6}uEB0mLpP+ulOZw;J;JuIQalz2wBz>21 zjh>IdJ~B+X?|NXM+W6jN$x7!O*u^k2_1epa#6uXm-bS~--NBqkP?+~6eV+{V)R2u0 z?91qk^0J{&#Bs&JO)984D*Sgcx9D>eC$VGs64=Q_-_?Te9{)nEn9NBnt&q)$qFWJ@ zJL-*VGC;k(N|{;CiITKzrKf!yWZJM=V;RL+`xzOP>jYE%^B3LM029n+qv{?SAt7 zNnJTwzi3Aobyr1*{TU4*y?KsLJ1l*UPl$LF1Q;iNFs)zX;_h(9zKORlhwD~JhoPy8 z*30q~R~WT3KaT$0>{m^LI^{_?*>-a!bC@Co$@g^3;G;Z~ksx}i`{clgT4|dGoQpXn&PV=3yh{2fC@E;f8|S*stmqu7u|PT77U7!XFJ{9P=%FZhZ2i*oRJ5vND35h zrrvUtqGO?UUD3)uEz7$ut-q17@2O7IHLz31<);MJ17zRe9qZ-2f(m~&*FSeft!i52 zuAE@9cNB9I&uO46b-9xY7iXo=yp_9C`m5Z26gCv9`cu^dJg?rASeFUmd9qSUiZ;!s zZJD45@dbRS{C?}Ef34VIXYgfTU<#DXNOPjm)j%r4g>Z6&DLuol#5V@bD``0HRZr6syl(aa_^5)7CwA_8_kdwPZ z`ZrTkb7Cmgbv%!knNQpAT#gs;j*hDDF5Ce6`7xU)gM)(+k&%f-BTBGFv`7+HoZREM zq**wgy2Om;tx8%4x5y7Xya7*ouavU+B9l^$D2{KiY3fsg@>UrYChV@GgsIfk~`NMc&8EMr=2`iksHR%~l#TXpOhY{M9muk?AU zQVm~4`_*0C@)dgF81H)$t+SD*D&>T1j1!pX@1c-WlD9~a!pqW3Fn~RZG^%%W!?vL*H3jqs&r^w^zvKimT z%FJ$Ki22)291iqE7KKLC_iOkQ!zg#THm6%VwZnZkcS*?fdBA5#1NKD{>R{YB`pNm_ zvXf7;xhE~Q11mg-Gok|c0a1bOQcc06TK6Q(aK;ZG1VA$oHX#=|rqBbn;EUY1Su)KuxMm4Aua5M9Lj@+Iza#}6-Sao~lI07ei_`8AKZV>s zH-jWd!Um1-6CZAC5B8%b5%!J+e)JRLrd0Npi!88>eazIf0SFHTRIrvC?3@8x|U=KkjK{b+oN7bK%Q*3^v#lF$kYrTi26E3!NX_eS7faD5 zM9&TKlsz5+!7C`u{PKa2%pwf53Pi&mcjKkD(P4Vg>Ktx%o!1Df zN|(j2tGDLJ##ZZbLBiKBMcZgPzU;HSXvU1&?N(iA)OQ;_smCd@@c03U*65^k==L<# zIf9P2o!}OKKXgJCM`@nwcxT)aYxtF^3LCRn3vtSUFfK3u_b=Mb%pnbdfV*Z+~c(RMn zTnM(KyW1Q{XWF2xDIVp<`VmT=*q4fe_W7{;O>wZxD5jSC5XtCjXts-e1c5>p;#Ly6 z{!XfBd+6;}Ul9GwiBAlh$1*L^pG%A8tgKwzFCseV+aZN3r}P$v{v{;)E7MhfmEEGR zyWsUv%#!bvU!4mmf=t(NWt(JO%iWY!}+Y z3a{I%1LxPE!5OS$O339acw(gF+piG~zt^xt1z_&_X4&VtAnS}H#&ca{& zuTt1`#q;h>UJNCzb&2imuouR|*Y8x-*y;wDiujQ57^JU|+BBzsHODMEL+#dWY^7m- z=v89CJ%|hH2<73BfUTj`Vc3bO$8H=(MGQ{%QgHbmij09U0w5C5n4vtluTa zI>H=SeBQ6Z@K`}N$kr$8Lwl-e_=5cA(RI3f7SQGyJ&FffR$y8mPA&X6 z z00u6!$rs*a@;Af~nAR`zxH;;*mKG9=a|FK9XcEz1b(fGSHPWZsEKCXpScqm^U~W#n z7(WYOlCD3nOEvHY>tWx@A16+F-JJ6Sgr(01R4zBjuC&{Tg+0kcPW<2E6HNS6@g=u!Q4#zl$~Ojpb%#n=f3P&_@O6~ zVa#yyO!sza>H6CGBIzPM1);EfB>A-Nb8gOKl=`Z5)S8crwmYo8oh$J1be!?zv6BiP znskiS|4?fZ`GS!hmqqfYDtLI%GBk3}-lj%x0+kQ`?wRq$2F#iM^7kO9oUqZ$0c<)7 zsWGU#5?4m?c#%sZlh1vo`miBSSFjnfKY0=V8ch&7HLX}(=M#tYm~Im+qllHZI2l6e z3%BS@hvLMoSKq+@RW}on*tn7 z!6pskPkJj@duud3&grN&1$i@^p_aaHT-Fcv^}^Ui&$`VpYx*RlQb?~%)(=;(l&*cM zC(Z5NG}iHC`12v_pI!8)syzqqh1r8yWEO}3PgmSRMbC&83OCN#ak_NHehxmV9Yw2s z0Qs)I%v`%PN_76ukN9@>{e<2U6pNNo;&nPp8d?9;$R$Ky1Tth|<)wS;@F>ef2wi!V zh?=1_BI>TPosjex#KUkC&lTK#yxMlbWlml-y0W8cq`z%BgxW8vNPrNxxO07fd|mzi zeJN9PSNP)Y4z!H7`+d5UX_^ov-UBHxID9koRjP%Uc*JmfcK}(p!ZmQodZ|u#SNVO7 z_f|2f`o#N_P8zr;?RxS8JfX7)zea@a+0i9$4Ti7pb-uug?$SuWVvW@CFMQoK8xXx? z?0jLy@=U=ajwzNsneTqP0SKk8e97LA{|wWE*&{i`d4{m*UihY@6EidpE^H9KxMmUZ z1Gc<@6YF9B&U0NGr&X!3deb&jW%*O%2fr>osSvJr0?1t}Y!7t z(=Q0yH9YQNlE&*WJ%BREb@@Bos10AwsScP7etsEK_$jh5jD>bGeV<~liQRm=j>@eq z`9?hfct}fpR(wV5@;wPs4ghj}rYwQvS@Ao<>w#33y~zXUBi9P2uK(*<$NlE zR7(u7d+$N)6OII?zSO0}QIdmYB$bSUr&jE(YHZW6{#ka*qu9~61RqCVyYyCrcDVtV z9E|Ef463arGwQkU9ZSh@M9sJBy^$S@JuioJ6N{L49;>N3aVXI>OpG0-2eUw;hJ>Ms z^W7Hl!C;`_>8~B6SVclVL>!3`HUG4$;=|$KttJotuk*q!-$cGwrSpGj8Iy?LbN!J# zaCZ+cl(>gQ;nH>EJ08{pfJE$u1CTeY1wKL8-S>_$ThJb=syWz0#_5#H-OA*Y;XFpQz6Xe6-rnz`BMJD6Gg0FY zp-4g1*6I|Ewisd_4JS6907N`80;yJ`DT15>e^%W!U3&gN?Oxb9=orIjECDs5_F08Y78!5OTx03L)8E+P2ct6JWeyda8J4!@oJjVMB2fQ&R`@T*~sdmg@t%#hM!slm0w(9&XCj=hg&-=2>Ym(EHYA=#DvO&Hz zcwZ=;c`Lv9P^Ks0 z#_uoO+Z-z`EhP(27UU+O3N4;?=ZeN}AE-F;)%PKuEw;wF!T=>@m@$+0{)I#WVz#wh+xplwSP8+i%Z^fe8 z4N`wgT^^?3brbzD?4!S+z<_5#cD0P`M!J_)ym*gwzm`F=gADhz>q=>u8Jv(}@1Gi5 zIf`yfy6#5X&w?$F-}U`@Y=38=#^F+QE>G5i52Odm!B9ST_(PEAnca5vO`BO_~Lx6%Je9_%x6rdx1-4+UN%2GV0Mc9h9&m++G^2l6;t zIE$vCws}(ywJub zQx80={o2oZEYnFXgjDdc+#@vl>wnMAUILzZgFLI-3cQrkTI3G(EPz&HCtqLAvBQ)& zYm7!aSG~(61*;!$X)gsE*ywATSz=3fYQvhEh*?gaD^KZ^!6!+-UYr3wLSg$aOvAs7 z#;5=%d~fHC`$PcBF_!ty_H^&M7Dv0tzjs7EC~(qm@m(GhUf@1xj~dLW(~VPFb0RtW zug3Vw9s63`nUxRKVJ4rOhD%!H#lfx?JVc4}*)hoZ`k>&4cL$fTc|VDbtpng0wbh2o zS0whK-V0Hp_(@Ijp4%C>Ur6l{o4{$LCtrSoiKWmV+b(oT>D`V!v|zg`-UYJlK1{IX zxE5a{i?KOhc<#YkW&<{1h`#w#)c6a8Fi|-Q0GCLVdRG+%j|v<#rj*#PZG?z233+$f zK!;C1wZNXu*c<$V4i)gZFlXf&Uy&=EJmmU42L4f^<@yXIupF$myem?29pv3m=zTnQ zCm4~60b|lA9K^!F3Lx!5d2EBF>dIay0RdZee6p(IQPt5QJk}aFD9GHlt1T5>37L9^ zIC|I*y>}tLWDjd*2L80?{Q>-T-|JJU$4L9P?ydJR11*E`8{r&+J~_QGl!k(rZw`2W zc}V`6Y~}f<+GdxeW$K~L$PnFG7gdqbc}v^L3qdsrb=bb3yA8rx%tttgO2#Ws-5anC z^8zzzd}l>$?)bvamWC)e3qx$lTAqhWdJxsJeok&`aK5AY>6@)5D(%hg?A}DRHBvuf z&ijCm;<9d1?5{V=ieh43OTvFMp~(Lx_yfGp1@%MGM@Ed^pG}3b_^W$B{ZQ(H3zQhj zp8K!RCE1f0pfE=%`r`+?wDk`57_fQPY}Dkwi&Sg`mYX#*+c zEsu2yrf`X|Ve2t=Sr!!iHboR(G-cTJ;SA#ZoFrAEii!boxPfJpP3~69$&ZF*Lfp-)>e41LlcC3 zUn^plHaDFBi9zo<3mq7q(FusN(}K*WwIAn|z)BwbfgM~7bzhHYBTtm6{^Xt}bpDs= z%4t$EOQ4$kiCILu39X?ZPsr-7d#Pf>=+$H+OGP+=U=xB*13Ax#O46V(yJbByT8IF* z;Tl9+;l3XANOrbpEj)#uvGFgT70-F=zIMD&&(|}D&2->AT=yQ_cg-7f=RF1mk~R1g zDQ@SLy+yz%Inn(ogBAh4>zAKVPc}}jQ(n_vF&cLI|FU`|E!`H)HS!ss#rrbMNzc<)h$!i$XOAD$u7qd8AUNP@^-jL1h0Ls-sve z^op^%mpdE=49acXPEDtt2@e|o$g5Q?9^f>8ko0h~=)~~aC27}B8^jeQI8*tOv5+E1 zL`Ln_kr9`5+?rpbUQq6Fhf})L0j)ij%g{cZC(qtKgJ764wxE`8r=c$~Jztsa4vIk= zJ&acw8}K}3ZjrW(y4L;2doVGsr&P&5f4*IO`bxikJK`5S#~muv@AfdB-c`d1O^c;X=>XG3-#tA#xII-dPS3V0*EGP4W3nVd6w+F=DVj z4Uf9|EvNPvu8BK4ZEl=2Ol~9i4+Q$973Qq;G-X?FvR?c7maPGhUrP?p9@MzKHSbxu zWz*4>8R;j)r)SyWdX&}+W!LbXM?k~$pi6poNj|ji(er|FMz;|U&F+FYSH)XXXGaJ* zWFi-tGpz2S$y#u3lb_?pAM>M^4<}IoI-zRdpZmwJ{eR1r}gy7ibJa;26JUFuZ2w-eFL|7AV3;YlofN35ty@lj z_ndLw^1Zx!5hsi0fp6?dm6lV6{Ye>%lXrx?4GY+N7Ay**AEWidfP@)IaU}9sah-&E z;S%;n6ic$!;6Z&em6mlv={NXjRt(SF8pHJZPb8>m%b>vYGddTWqS(0=m?iDfrDwx~ zV}pR0izF=}OPakl|HyMq`+<}Sp*G)vX#e4thH1DI$iU&u(9kx&s-i*B89;2@^rO%w zh33C-ab0CgbzC?p@e{QBFYW7={)zCzmxX{_kAWQFo8MeWDNuGk$Vvwa3=< zUf5ooRb%8KjoI(`I4Fs=trp^@kb$I2!Vuu1^nF=EQHdE^m|m|pNKli*6WkN!@&`Um zVgm&m=B)zHlv4QpP5$HdJFH6eJm_<4X4KJLW}AmkqV);T1DQ<~pF#a091Vsh1);wM zi)(xa7Y~-Nt(gR#WQOWDemL95;2dR!Sx?^EkdvgqA>YY2yX$0rBGy?%NgfpgkP*@& zX39!-#$4T1TcjDa96Lsu`>|qLYwp`bFMg=uwLf@XJ;e>5*J2&p8vB_~Euzvez~{9)d1NDn5-qACzYjyW86HY)FuT2(i_ zs*npp`|Jlyo+#Sm8-(xp9&gL2JSj11L3(*K>!&ZwokFA$TXxrmKPvOT&j{Ew59JF7 zgg+L#j=b^OA1%mCcfbtvPT47rZ;f=7V(ss=eu8jM|FZn5g^XIGJ3WZw2-sXFFLWC) zY@4|(fr6MfY!#8I@sR3cRP!1PYwyK$hel!7DbFW{TbQkZWTLokNZCcppLQgCSg^F7 z1}o@(0jAZ5piV96grGJ3DoKj(g|kLzDN5|-8V^0E#)w2$3VB^DgJ(kf0ir^K)gX`W zupQWRXCtrq|8zIG{_x=4<5~djOsv#f@;DMPx;Ni;r3ZQ5lEk5_k=6-&3`OIx7zDeZ z;rFpZhj}%?d!2dsw=>@)L?j67L4AnF)r}o@6mL^}$ulrN*WLMkO4DMZP4}k!PWzs4|aOgKY*y+XF;36;eS>@P1$;k|40xaYLVX6ht$sk@2Z+ z7zFhE2TAu&Cq!k$iStkJgVkkCpnd!@>6t{^*PN<^$*6 z)ZQ^Ux)0uwP+M%F?^kbDb(R~_8iRK9HobRS3)zY@UjBi@>;BsWD>7Mo9qhClx20fc zSW{J6mwfA;oZiGNxmgzV?NzyxZbYeVpbyUSKjH~YA#q^|jIlRk6 zJ_5hO)(QtGL)N+??-Z!FTCZM7fQ2($MaP(~aoNVUrUtOCiUXG#J=&+9^ZM>WH@+9~ z2>H60V*W&79{B**Qq}6qzh+SxlPegxju^KV~N<2YRm9 z2>${xZ_>9@rMFNIdU)hXOY%@+ig%OO=!j>Jfi_BFFESV_?qoE}1>QB-zI4{dj@;EE zcDGSbvSY3Hx}34is2ySt;(PhrOf8hanz%O^P8ZN${9wfpfA#9+M)tk9y8J@8(uk`< zdOgz0GkiJe7qO}c1Mrp6^F7iH&$Pr~66(@Z1)>?6YhO&frr~u9l1cTsG!PrIl=bnD z%f34Y9XE6+HTYr}LHQ{UY38L5mt5W}SGGiu?dMMXvEkFt@A;O7{(1s$0*;?RY>XH% z($83<|AfT^ql39Y;$dueEE1f6wBzCgD){m9RZoOe){VguHBE=hZDz`Zmx(L~=-fBx z5adb6vsJ}hA-V(dN}U!)h3i(IO;`MLbaeEA(IupY(ForwtVQLgz+!j1&4uNBr27r_ zT&A0IPLGStz>oU_6)%*}>!Q8g8^9GAv^Et35+Bck8!oH4A5ed5wI*-lwxgEaSuF8G ziiOZK;?jh6q*Q$c#qG8Szmz2PwYhsB%?Mp> zmtvCMeDO`e4Q@ivHYchXni94OA<_xv?MS1zCwYQX*yB-mbEh20BIGd^7JaSpBwpW~ z2=zMO1gbAcaTdq-qv`UaZ9W+yQf}&Ml-jfPa=1*F?{MAJaf?Y=P=GFgp9zD{-#!0^ zgI$UzuBsJk+{iTRsbOEqF%;*cOiuppps!=RAJy1^YgU%YXkg9JvrNzm?UN){tzKmC zYDZ~?&i(pr5VfbEZw;Hi;O^F2mNiBAm}P!p6<17bi6N4rmDj-!^#Rb{a^}iwSkFlG zauS=#;l1^K*PTS%pV5}w)A{h$wDCE$^d)fxYQ3tD*pPOl+@yR_E@%sIhWqR4zO&g4 zI+AuI4HnHh9PU@}jR$*JX?KGf;4jt1PX&Jz(o=NZ(wg}LLgZB!wwFf5FRswKIeFHb zTQc;juCy{A?-66%F|jt1NJI52BjO(yt17;YH*)<}0b7UiifoWm!odydiNtk<{E!kW z{?Vz0--}QbcJhv$AT(^Q$)U$8r^SKo8#PO!|LoAz+%!yVNV*OA|7+7T`G^2XF=@s6RuJzON@)V#oK zM5DW5?_M<`7Z-Ka)uPM*pu02{%cA&fkDb<47Aon{kmJkd-36aUqeULj(WnuV`g^B? z4TIEaK?vez_sFt?ZXO<&My{NnUh)tddG)Z{w9$8P(?FafPRE;TNMh-S;{%R zKoFfQ#$X`)#L{iuO?Dd8Gd~maxdHDvH9B`Fy)OwS6pb|uO2(rQpY;-tHE zeEF9}n7R_Uv&%l08r$^akSug;Lm@W{yGf5$dr9bM7n6Hg4lDWcV;=v5rR1 zKJcvLtuOvC6=X;4gcezuaX$9~2cAaL^dk8|=+@|rZXFTAZP;}_5(T#t{rNlQ?ACXR zAniIH;;v$^Fv4p+i7aWAh#jERq|6vgC4(}8Q=#~{u(Tc}v_&3Q`Bi+#YBjS?%7cL& z;Rh3o0ljNmfnRw9MhG~D?;uv9fF^XuM?Lq6O8R$bL)yu9;M&W@Zt>>B!|_Q{&s<8N|5#w-fnlG& zR?Xy+`8prPobi(HZSeplte!FEwH%1x5n|zL*a5Y z_BiTvYu{zW^+a!*!KIPq7PnrmA1!ViT6K1XixQAaY-$_^T~oadWaQaldU@@?h(gw{ z8i`+Iqc&1h#l@6HrIBcXnxn?)l5+*9=P1eY&g8c4n=1kkl#`BBuICwFulC2m`|v%< z(0M!jDdLjcw&K{NJ05F#33+dhB4@3Hf5m=i&j&t2k)y#4p?{>h>nyUeyJ-ob>Yl`S zE6ON$ujwBmlJ>r?H{~bfR`qLRngvUYe#4RC{J{x+H=mXL$ z!BfP1^hpA7r3l$e18gcbjIqn98G=wpOowLSn|HVFY*b5BE~hlVSsq6&BS%(~Y(__kUa7_j~zFt8)Sux4dKQi*d5SMrNSP_$hY{S`*+~+#S&ox@zQY3MAQ(&`WNCK{{(L1NgFSNr zmWYt+mc_CA5W(AC#Y-WCoSH%ht;_oAXJ?+|_B!0B13C`sNyGX^l!-U{iq3k4h!!US zGHD>B7eOX?W;$>Lj7RXAJZWdj;tque+2rHS@#mnCS_X9Iu}of4MQb3X!>&ini`K~Y z`dg$XV@AnE`H2%XAT&WWg~cuO zN$&ftuICuoT&IIM_wItiM+cV;vvQDwxajrk#e&!0uG$%jycYJRwyV}sOGxE;#%yR! zJbBqZU5_;n`CpzlvE+dF#E=uO2~9&|UpR;i*IZ$IBc=3T#Z)pJs8L0T)Q@LwBwSr=RGa$;z&T zBf{@4(%jLe=cGz_W`D^b{fzhZ!8H1*Pj6yM1v10}`JG2zZj`ONM`o`HME?-tJnJ!r z>mnTSwMt0LPP>0e5yd1QWAyY70pCxTsqMv4>{fht^)=ieam`7+^NYmf)Q-N683o_u z2~j1Ed823~{7yZRxcyTqAfKb~ei%I1EA)y*>U-aoVWUSjr{??hmF8zCtDqWLsfnz) z*~D}17ZJ~VqXJOCTzcUGV0hhK>~A}I9?1R~ePTw_`Z(FP>DY>}k zJlRY4-Y6m}YQ*1vvx4L*&kDOm7$=6}oodr>v;M{)Cfp_G{MGft$p;{UF{q>*r~?)sXx22LqeWsj?S3P1NU*a}|)FbcX(ys(o-o zj8&O@!L0ySDF38bp>Zg?pnC9amz4dMbOW}+DA+uyp0LT$=G2LabTarx_~Q203uUJJ z30n;?fJ2C1d;XRWWr6nZ6HV0-nnY8@MxvDqcK25T9z9n8(0*iL59jDOBjc@c1V#7l z52uKG-{Q#xKY^QaD|Op?*Vc5209+PWVdx}bp4WR@$5mZ}1+qpnKQYMqD?z%gF2ic^ z&Q3UL1uiaD;g+bhC_7ILFA?Ny_|Hq?dWe5~B^R$*l|3lHsjeO#+(eGkkx;_~a^L6y zZN!5&>)G>m;L^V8?N@;&oSYXI)uBeyg$ZQe$J-B!G~Hd^pSB~ueW1&^=x8R*fU&i; zeGiutlm=VJrL3(;9`M7~CGu;$M?eA~zJr{e~mth}_idHM?DMWN>^I};n(!YyidLb9O z5r18C^%AuFRncJoZDk#`pxLx0rs3}X`UT_5ke|u{2Gc{FyO~Vj*oexirji?*&l{Ak z@eSi?P{=&0;(5PhTP|$bFd70Lr<6QT7H*Av|bZV$aNsN+>R2z`hZko;Uyqs@(r)Fyr!9;o00d%?hxGo2|Wh zIhima@T?HEhyL8ZRUzZEQ-hAO@m?`xdZb>7UXT&5oJw?gPwkWOFfGJDO&=laYk8B| zSAlW#dBC-H1tgK=;zWt zY7E!|aUq939>e{O4C_gg<~#Mg^AIP)et^fv>Wy!l35@9cfrIchJr{-la`HPa)?A`$ zmbd=E8Tw4Q_>?h!ouMzGvEyYL=ic#Y3nDemcMCCrO9pnm)1i+&Yd9RC!>?Yp&{ zyF&`fVM2%ewZAQ8{Jb>j{2h;lW^nUDJ(ttp@b9Xqs3eT;_BtHR(Qn;OWC=pm)IGbS zsWq0fG^?Gy+CRT1P|!3Zp`wne#qXRt&<|UJSI$vlV$eeu%Lwfxl$Ces*9&?r=6)Rb zsp=f|$lP0#Q9VDtJFEOmfp+)YhR44DjOgjLOfHm3+>9T+-)wNQg_$`>D`@{5UzA)-l5i{vXQT0w|7c z`@>BL0fM^|EVvWgoe(UzyL)hVcM{y)-QC^Yg1fuxyv{lIoO|!N|5x>1R}D2?HH_?D zd+pszzMoCq`_90MDapdr5BSh0&$K7ko8?Mx6vwouqg6C^KB-i`UAP=ocPn8dHDBMm zNy^SW3jq?PxtWUk9;oAhHM7Se180LY@i2<6+Kic_UdjIJBJ8bIM>W)bDb?pF%3Xz0em9?i2rLRVW7u z5vLpMvpRCSDTf(C`~X69S`SJ1v8e2F$roH{abQZKuMyc^2WQ56NUA@N7C?f5NT*1d z>*_QHqM<#ZtfTrh!dlZ=Sgm{VlcE2dR?;6f%bK;WbJ$+rvSRy^4>hJ+cCH^q3yvjF zDu$QkQ4}ly{=15@N9UdOYxBm*X~=~jq;AXI2SUMoo%qT79?ha}nL`IHlzjSrPF1`Y zc=@|*U%SKn1yYN$<`C6dhBdWFF=9qDV}`b>P1rx+C0%t)34vRvK%I3qJ~?*_GbGy` zC~O;5(^pRng;>dfZ5ChMy{xlT?A9|62AfOA3&=t|X@adXY!>>*?k{FI+Pa%;-h7F> z%153FJc)W9p2g82)l|~W`YuLZ$n_e6=t|6WbtCWD-V=ybMCQbBN&-Fg8_2>C87h#W zEbH(`u_QRH1uUV_no4mVP1oCtGxeV#ExVwAFB?^u5pwv&%{)QfwD_4e%nHn9N-m%4 zwbhLX0Hj}o6VDk63MDZpzeSCvIiKw`sXjaOlK##f+)X_FuI6Z=z!J|-hpT1gxuWRY zwKe8@it+<@1lKxT_0!CQt|5p2hC812facByS%qoYy*{`#o7a z$SmC1W=cZiCPapl9`|*&{NgK-jI9)4Mi2Y4~9754IAd?c_ogAD)Due0enl0h5^ zaPuN_6Aw)e=R`w6KypWsgUF{H%<5(gOct(_Uc0gtus5q4gnzK=fO@=8c8RSneifx(rQw zfE{`k8I{k4I)y9QOUAV8c*;ZM9P0xAJ#ijkmn%ulFhb1v?rmq>KR zd=TW-XP^bZW0vyTq^A$1jNp5_vN|IuumWoJVgz@EYpy%S^JAE3cOMnvXVD<~hKNBfCL3>xlo9OPb45vYAPj@O}j*mmTOckQ` z{|fTNh2OX5Z$&y{SkC2sN>%h)use^ER)*_%LJ`G?djHJ2yt_DTR^L4!skZQVN8WF~ z5uS4s2Y_JQm!YMRBJ#H?8kH|()NVQ-Y1AvOQ9dG~eE{98vaPqmzaD!C-LAq?rJ9PASzke|wwT+``2O(H;Z;_?)oXN>Ln7=52tWg0Or!GTQdpzW?PMSMkdc@n3 z?3eU1mgIA7C3-8hxpe5xZngY3%BpR6Q51wNP!j4+i6W|PpEZ=UB&>IrqJon9<3e{x z6n>Iyer%gR?6@7wTkN`X-))6~8oG1WN-_I-uv2yi-*87!e##XlMZ;ui^~qgy zR-_-PyP~(2nbRQ=s&zk7RKWQ|Dnj??+blg+Osc+FBMXyEYtZZY;sXOm+b&L~pi-A# z1VnhMQT5geX1IU!Pm8^ti*swF`YZG$sZ3&V0~>1jg*&*%@jh$^E>#xFF)W2J*I=-L z*Xb{8kg`NpXbX)cLWgiZdmN6}W+lEcOU;$WRjg9mW(~UK4}|qj84c`@)HnXE)tAg= z9F!Y3ML#E!os;m)Y`K} zk~pUlT`l~3@4DurZWUD`Pf}QtpNhE(S1~Acx}}1Pts{?+7oP~pgP&SPd=BAs>E0?R zyBrj(`f{WOUX^+KtZ5Fv?P$E&tUXk+j zbde_teguEJZ3nIJ+1S{$!M+S7J|{Do5Y;>!FIMXsfs|VEb8a3O0V+AtpKeGv)o1tW z#3?xq_uH251xtCCrCgAO4l+uy(RbCS+Y`Teps^mhTp@U6xmJ1ML&NiyL`jKDv6guR z42!N}vj9)J*nEWub9Jjv847w?0tBZoCipWOhFQ#A^eMSpvj;hK7rf5nW@|yvE0Te# zBftUJo|@MBsu!yQ18Z{v|JmegX^!@DO*`qts(Gu}H@w&pBO z>E3<{_M?^3YOb!B9K<`4lz$Ib(O9=?P~ZFBxLXZq4p{fjeHMze@rwpOl zA|Tk8Xb1nn9>PRb-*=(EbiKc-UWJl~^I_=K%Ej4r78oTw9JrE;m6!t&!u%;*x1FVWgc}sj zt5&{^I7%5>f@$H`wh|A*Y+Zc6B}%^gP;4SL*kE%>i5ZQ}%(8KmtRqsa^T5NVzzHAy z?l*0?w{m;vec$2Qf&uMH>UaP8FF_O8%n+`nWK1XkclfYGJ?I?Ujmu&trKc~RmdRGm zwMVUYh!kY9lDpsUwqT?yhJ!1oF86fYlOn94opFmvCFkZ~GcNuFr{lEt)n2vnC5y*u zXz!j;g6ngVMYBuMQi8Z@z%O^w!ijOi$@v(rbY_2Dk5loxMS1plnENnv7fA}^bkw^f z*%=-sZUhpG6&AhV=ozP&c0_7-jTFkvi~+w=OtpTL3)Id7Zku zV4wMHf$|5rNxewUCN#T2>2D^@z&VM`J#)HTTVBkmOYfI?qT2ZlS&D5=(UmIHC$*#z z>7ArEw0_0 z%hEf>Bfp-5J?C;v6ex!&CtK6(@SQ>Hd?RDFp&Q`iE0)J>RBQcW2KJY$YL{li=ecSd zQz8K|I5-!R7?6Hu-t1V0n(yHmk^yFSnOwB$wx`k%iB;J3NU28C)>WR0&QP6+ zIsVt^LoP0Ftg9TWAQ4b!{;KapONQpRA$#!=sCSBE{o3O8YsraD-<{Y!mZ>4Qw;6U& zN^q7FMjiF8a;viJ?E2vmL4LRDulY$+@V{pG;sgAL5zC-gD#SOMkkXK z0#IAfIhbQG;Jz+P7e!no+>J6xJlUY}9O-+_n7MAqg##!iFMJJphvNnxNJ6$%q$>}V z&>hXwgqumxgpmLf7>|x7EoW^{h^+CG(GSOtDF+eGKpdHb7r~#IXuZBw7woBVvy>Bn z#C@gUgt@#YUv6`Q<@BV}>;q9d<7NqrZB2OAD+T|CwU}Oh;%aur)gn`gCyvO*l7uq=#=6b-0yU*PdyPhbz=bnUc zTG2Vk1G@!2kU*CGl8^+MFn@0IilG>BU~TPpxRv}W=Tekjoqd?Qzo`FTYt$|lfu zPC3UAa*Z3I#e(iGrSSgW&@Bu(e-9SVZiaCSs1S*fQsVeuD_H91PazMDbSFl(^Pu+x z5msi3&;qov>sqo4O`@yM?LK#6*5wqrb}#eXUCf%_#&IojCof5*gStw)kDFBi(pV4U z#S;eA#nb5W8817h7J@tIoqBoeX~asUGVdtP(KwHQdD0YCEVV`cua4KD4LWHnx3%dcXKD)FP4Li$QAkqe^myWS2*SewrxPFu&QbCb_>XgoSA4#PuD4bAo&2mVrT{TTxgGuO`&U;LXa~<1y~?`U zDctms>wC}phiEu9bmZ_Jo3#;T+^0jM=a1)5!XghZCPQ#7^sv^@(Gx($dtiLjdS zpNfOVjQ2eH@L5rrhn^@<{@#&P=j0qF`lZB3g(IPuYjVS8j=cB-kJw%(>ct&c7#4KT zJw%U3Lpp(8EGzcUuusQw*A^CFzN%eu^9QxyWA^2T~v5ML!zTQT-X$+cjevL8IT|CsU&?KjAckagzRe6B(gB8CI)%`%*=I zS5lJW6cV3W%RwQNry?sLi@rxxEf#%AWY{G_QEjP|;<0wxy?h764-CpLGz}y!2@Fm} zFVZ3eiz0rmh_iKAgp#Ek_7iG9I5|z;G!GS)%om4zNzxKgKZ8adnsrQ z8X&7rP2-4phj`L;rbAx={IGXGOHX!(2f#(mG65wj{|be?eRm1e9g>702^7Vk(<*cP zg5bD(V!M=+@qS@UaK!Q@>2}iQMX|^606XBB?QaaIMQGaK$+-wL(>qs zt>+CNz>uRGS_T;cB&AE$fyYkUZgn=yAt2*UH1b*s`|w0z3&J5XIE~K}nx$zjX|l)x zuwTB6ckPz3lqe3;(#OeXQ79QSk(d2VDywWih|prN4NlAFLR#Yg0qCNBn)dnP0rY*0 zWzo_{k%r19J=KOZYKpCKPRYw`(z$G4+^yvlhGf~S{Xhn4*E}OE>T^v5zRXVOvcLR+{m&imE7yTS?6{)AsAx&v&{x zM3X2rw?4g_?P5HvwLxCZc4{A~q4GFgo)=<3laG^X|!17a+bB;Pty@_~#R6+#y6gwb?h~);pO8ak1$kG2# zD%|IHgVJZvJB%tc`UVEX)YQmiQqR7BR@{bfZ!-x2HMhR%Y2FD5;F%HWYs@-8W9hKf z8obffriu!qrhyTE+O@hd=VzJ^9}s-M^=C=_w@8M36W<;i)#F@5&S(t|NG_J_F`X)(!>VD4vgz8l|acD zKd`4h$&hht(1t6}!QrqVYNm6$lD7P2gXA~?%DcG?vawj$*qcBox$9f(giE`Jg7eCM zGm8KC5ZT7Uz6)$+N4`{%QUWvWa8(hwZ~4|ZfC>Q&V1}95M&RzBarP6LF(5Q~9FCQN z5-TV`l%T&S7$vj3JQC0h>z<#oJI{cS=vHdQqNLjRV?M4kP6!vFUm{4pl6 zd=7cIi3fvGWZa^0TyTF}c{?XfJ;3 zd+Zw+7~=ctLg^YSSRTjoEbu(p>Z+ELKdfVJ?$y&Hf2)d7s;aU+6#Grz$VgC44MtTp zX<~9x;7br@_Wv6y5*XP4;6Vfks1z*Kn8+RfsujoFQ+ZLduk7O_4d}WKFj(@Jc>NRO z=OM5N84ZcXkzPMproovh$FHkPqy{?evSDUoT4*wbkw#s|gZ#+t;%Bi`_u*_qnuuKL z1&}m{mgWu$3qxJK%frOM*|UoxM@TANO7yrQ`iXpx5#R|`lnrDLp~{OQuYR-KfEerl z+TCAX?LP-cUTd*jlV4OEM|zVeLro4NQp-=UIshUIIs03C8{zh)#7t4HZ%`0Mfy}!G z*SlcE3DBl6vbhD#`FiJP^=1cza!nKH#Rp>iwf^D~*qMnb-5cf~$Tx482}RA#OAr%Y zuMgz*_xA~ii2>u8x5ScKL`5h!iB9jZWv+TQUD>)GBK(8lRlK)F`>WoHtVOfYM!|_D zBuVy>iYzcAChbWP{-dZwESfYZ zG!!ME$Zzfm?%*KU{R)pjFPlP!@chYwVNUZ4(%z4s(Y3t^51%i*TiNwF%pW`7!lu;9 zq=^3SShWbRnk>SpHrabCEdmVH0TjLS!&$1HK+OP^`AH|NC)6a4rh?2uijm02Jtz+Q zD(}k5x5y}RKhkIe%PfB{71>gF8iZHPb#>??qv3$i3L!A*0LUEnVRu&+PXz7*4!~{| zz~gTHWjuGR;TI?hvvqgMEeyaX59e9^)YF1j^3 zqf$!-)XLw*(aNe%bR8CkgoPcZ`e>h-D<`)AfYy{}7+8cKUy7lip^=A*Q1tZl>c(|* z3ahevUUD##y2czx&^e?<&d?=w9wTT?XXnr%S{<=7go`&YPmbRkeLN6?)`3b~Ap5hM zTVAK?kp*+R4wW`M*JpmD^2p^lsZG*EInuvxYJ`$MfMLy9S5_2QV*j>-zm3c}^n&kU zJKym~Y9e7v+t8TqmW|Hp-&#)FDG%x{E)ak^;O_-=YjJV0i;b??ol_lZVy*tH1o0dw zOL(vY^aG{R+bCmtdp>2z5TgJ}zuf_FqTlz%P%?Qud95Prf25?4wve&2Czi_9RcK!3 z>~(Sc8%sW@k`F+@x5UoTe)qw+*ksX<2Kp6{eF+03eg#7mx4KPk%U^SWUAjy2=Q~#a zY+sxd>>{DuYM7p3Sia&smKwilGPF+5(XLFJ*JXwBk(X`zYP`J&lU6&#`%2N^>N7cj ztNBHzNOsr5T^!QxYy#a70^l(!9@=uja=?H*(}~5&WwJC7>Ocn(4skab!^PD&moxiI zY@WMZAJOeNdse5j1j%YD8U1x=tg*g8_u+GnZ#A+hn8*MNd-0IbX*^~dD}?10X=W)Q zqVqDEoX3aw-4-6M22VvQ4U-V@-df%~J(UN0uySpH1ZcQuQOyH_34q3T5d9Yi9HEDNzB| zFg@W{R!H+0f$4`nWZi?j(zn8Jn2j*e8mnTd%}Y3|zRU~6twHwZuNRL%!n13hdi~ih zOoLYpbM85rGFFjr<*+-bb-)S~Ed1|X+24jmxJ?77$Z`WJvQv`@p*TdRJN*N;5%-X$-7F=9R`9CdO2b?|lz;vxb$ zY?A+nH|hPehUQuB4kZ{7oPzoO`JJDRZ4+MLLiB3@FcJ2B1h9OCM)Z{+LlMM4qG~L-*XNaft7rC900i@`? zFaaehJqES!id;lvcwK`W+4PB}yS25n%8J8y$$1L`oOX1iG(4Z$=mN1w%kPog!v(Fs zH$mQdoWFB`W70WGj=Y+)Ojy@{`!216n+grd+x6n5C^`sZZD7C4A&83fuHHBCTkv3z z=t3gRy`>p}jZLPMd`%-P$RR0U!(z0@KHO+ny&BflcXYjluaJuwY#!dCql#D1zuxxG zAi42<#0zq}xIs$U$+rfN1&mubxC|N+9;xsTJ!$Mz*0L$o0m24uVm|hEfZ8}ZsJ>*v{tT3 zRZ^@TuVO?5U1LW)*CDqxCadS9xL;nt=eS)WK~UV{b3$Z_diGAObT;;T$)!+9E;MGb zsf#f{HJ@|FQAQ}SvYIEE^v}uqSKvDYZ8gP7&VNze^#-Nf$Ytwuf zgHvGN3rV^ z1dcR5T>pWZ@Aw^0q|Wc(G^y#K4;0&9D#~

);72oSe7bF1Ke(kUuy2?XX8odr#v* z2@wYGxi=)YxWf(^!MKz5>QaB)L+!nQLg9XdNZZr;x&SyLISgf-%4Uk!lKL=kKaF3( z1|UuOra)TXkOj|wPrkpNePNav9)MM?y~&Wv{|MYo{=mM1qL4o8`t=JN&=Ls>5AQ8i ztDmSc5C<9+37DDDNJ&YZ?#~JB?Cq`3G+&k9$XbVmhx>1R(_~^IFH1+wiD0z zO<__TvrDa*I6}F$uzd5-`X+_T8kvl)mv8QXSi+b_*vdBF?ZS#W!$K!gM^+|cPEcna z@k=Y7SL@eG>Ao>uZACJIdswq8p*LMq_BwsPUQ9z0<$VuWVA8{_y~G?a!S1V^TVdZR zUnl#Q_fyP9V{(pnp9fqt*gbxFw(KM5?!fNe9qZbDe?^}u4B?~vAO_MFGE45XT&5mD ze)@*`WquHjstwy89?l-oeMM{817sF7&Egd-pHDuA(%vOd2WOZx*|0la--++2rK-Eo z^>JXu2kQ8N6BUa-pfG?xAmkG{B_1ybD^@)`-PiFEu#FA z`s@?fX)d4Psn-WBkk^N~u4ZvQh^1ajOw!*pug*7fg1Z~lJhEtGE?jXXQDd=?Q;l7> z3QTKx9#<8*-qDy7_zqZP3oXMNT=|wO zEgAumHC>L3!_CZ&Nlo?Ck2t{Phjvesvp1VD`I(F{Pa#XL&VuWLdKW3N7o@*5PLxoD z$0!($VBfNfEQ)vDr9eFCC)M>9R1VYAjlYPA)%KPk+0si)nt171nBg#qL~07IlcP~2 zFl&UNb-Q*qrJ*j2o6P$Q&tu&ibSUS#0x_@u+}Z!JlF9$BQTP(k;JXm@rbnHZ1pL-E zGc$9c*^y2vohLkBIvu)vzFZ4q=p7iCA0zZ}`6Cl~Q#$GwaU9ht^7vQ}g^c z+ILrMOw&~c)HmKJQL7$C8ng6|Sd!axFUg&sk9?H?^$6ysu}~jB26b+-Dl|>= znQPm#KGS3HC@p$S)(fu9U7TxB(hT>*gucdr9pGI-PVG(Lh0x_KbP^E5wx!VmwMh`x zPwp)Yo&ln1$FJ`h@gphRsWb3A!!3@$sINAbD&7t+?`n6C#&EgP+iSf!t(s*vnZ$6A zP2_V#J*KJofrK5zy&;QbloMVdsmX>}Vt3p;+64~zPM_JoZHqRWD)VQ(N?HaRtaP?4`+g&Z0oR9~On@6ed*lqG9(l@tyj{lW7v98@@qD z#tM1E%#D^Mg)@YQ@0a05AF^gh8@Fk=-?Flo_FL*ORoX+lQ}8++4it3xqd6h zP3$3R&id7Oj=fgyRU|;gsdg-#2;!~$bjcuK3-*vs9Kl;qpa^5f`WRmE?_trG8w- z!iJh-T#=5+gq2WX&7QMnL%riiG0bL@_Z|o?A+X_1`|E6l*ZemkD>`O9ntHUlJ8=iP zOE_&EL)k`1aUEx|F~+a~N1i1M8WLavFRVJR5Q>g3b|bt_u$do@Sz4?eC1}m;Jh>sm z4whsWj4H>^LJj`%h5u=$LK)uJfRHtGRHC%er3@#)J`}?@^!HmKi10Qkq9M&rMk{oiuLuwKYo=)op|YpC>5nVO(1qKdpb~!-yjcShH?ToR$J0(kXPg?gyKo7Z=K2R4ASOQY>xAG zDj7}Pm`HHsJMT9IahVPJZ8~aww6pRul!BL4d21J#>C0@@kFi#mX8TZ}R&M5W|Fbk+ zYEsATVVqYBT(nBb;kEK}9AFu|E9jUr`S0y^kl0)gA+}{1n%9ZXhXi$0+nu$-lBnMw zO5=u{mX2hU53H7E6jHS8vz*b6u*x5b<(X&)IJ}5vTcH$sMVXqgvb-Ysuu0lpC-3>X zi$?0+$eSnz*9s|#>p6UOMi7NB_q7u6QBJYOYm4{jd?07B>^fcPnffUnEDC)#AlDDg zjjbAVr?4n({cu4_&2b3>c35$M7}n zTkW=bMbb%r_7WFEVK}UHXY<8X`B3ZE|06Eeg$1C--x*D|wb3(Kl8Lk?v9O}{IjclR z4$%wdnb$ef&MPnxVxrH?g zOZA!_BM(4ozXOyi(96xHir9;aczvE4*3;S0RLre>!&blqyXDKmZ=!?mQPvMl9hbHgn zh`%e5>}$n@1k&BRV0JV_E6Z|C2A#)?*!B?Ykhsd&RaDS>eRK_mLC_YL*;4nLNbFiq zHQco0|CRg!j}zLQERsz~D-L)yvG18Y@n`be43}f|4{{m;;Ih+;Fq|OjUN9h^;BJSL z`LupYKmAqUe3E$Gz4g-RJF;tpmavdpoP39V58>uob;E^x%7|x+q+&O(jF0<(s*a>&Q$yIP3mddd^4)oY7$ z_B$x7UwsuvckfvwH6j(>@$~yW!o_k7hj3uxz(~6@R)EwExEJUPa@oc!)+35ZGUb*K zMGSz}ssCB~5M|*Eatxr~VcaocsWLMI0s!HT*z^3d5=r!9!_&yUGii&9e0iwfhxc;( z@`;JLVakVf0NZ z$jztGpPiqW@N$rp6k3h&FUwTcY>r6Ck{d5Tzg{gQ(Vr~`q$})k_K8StNv;oP(S2T= z<2<+W?ER~bOUyG@qjAQ6V5Wv_W0*u$-YQ@DBvmcn6c7K}lzy`=jkA6vE0+gHg9k^R z2GNlY2pYWUSd#Pj%Evw2^nOf^i^0oG-^yoqWeu$^lGoZR()KV7wd3fL<^GZU*XGH2 z-NWq#TCrKLXR!$?Zc0oRDZ z17p?Y@rCOvyl_An3CH!@0>6skmt0g5^8HhdY^pTd3(ur#HriAu?0a6IFY5!EGG#PaHc<_rYEA}mc zryUMLE@MlOAd%}NGt022u0x@hF-UK#tCun0i1|5!@7Z6^N#sq zY-}G@Tb&;&!Na0Mif0m`Btw^Z}t#4q28Vq$-4U@#bt&X z;^k+im%jZIpq!)vz9#-W_yM87)CUNT@^<@t7oenK-Dqp*8$+`&BO6g< zSL&G4_o=3_L-L*Q(k_(feAAbjBXhbd1}=K(@TjZP<^UwZTqdpNFt!$MCcnL6?%jdB zJHQxk_p(c2+~vgCuJHqdK@7eTTwoYHGNCgR)5n1Ma+%F~MW zV4hq$SC4IFLewD@l?FCNXegA+Pv{xb;K{RbFWc6>t{0O=lRC^J2=|B&d5ZLMb|+&l zer5=|9cPy}rj$2Ao`@k(w^tK6-9&CnS)3(iQ?1DVV5`aqlJu9H6cb9fW=J+$S4mpPcgfMU{WCXB#*g!KPFr z8_vDxOj~^72*1Z1OMfLAvC^K!kUZ(<%Ue?{Fk01x3adHnzDzYNP$5=~nM(8Eup!LU(BvM-d*VO%1)1S<9-Qpj~6( zS+ndQpK;G8P9de`&yIWNZ*O7>dMo1I{C1b78RlrAW(5;7sb+jJj$^T}qSmx~mmOxQ zYl)$9pX3-{vu~-|8ke{PXRYn_EE1*9wW;C5QSTiZ-4TmU9esMaVD(t5-_7Qd5CV1djofCCfUbmw(=Tawj z%P;LD_eb7L(i2b`YiDn!nPTs(5y}V(2R$b`^Wa>rkHCuq05AOuUL#P-*NhitV6$9j zdQ-BO2jlW28h46g8`t-fx~nqGnZ1QCIvzxZquFPN%36Q-{zoN`9WD_{zuj<3Lf@cFDLrRM7PH`spQQG1jWb* zf($0<5n08tC*aonpX*DZl*D1ex|BZo&*|vjDS3&}q=_OG7#RdhVv^VQHH%KF0@S+1 zU4Rzrd(Bn>RoxW&RKzRTTK&f_VIGtcW~L^@hpRL*6B8Zb(~$mmR}VV#AQ2jF_fP#I z*&^ZCPS`FmK;kDTG7{sL%g0x~g1hHQP_-kOwu1Z%en-2x(vA;U6-CxS77=YmCPk95 zWub+lYSL@9`Vi9^%P6(v+DO$bwRrVTZOzowkh>T|udD#Sp!_!(@Ws2Es+YYK&UInF zx07$$)Az89#u7gp0S$1rXN~vCpMMNUgot`LNB*SOtsbVH45Kysy)Oo8G`$DzU ztMSv|>gr0z)HGy!TOSn_m57HF$>LWHzmya_pw>9iRi@DDLIa=b78M^GVHijAEh;{= zp?afAQrF!@Ak5s#P!=}?+HPV;f6zgnvV3V|L}HHDZXfS{FFo|~W)>}CS$g(6I-$<^ zR%)r1-gsekkoXwCrlogE)la&u8D5-=tvTm~q*C8l3LRKKr&9klA*kgYF5DOQ=4N?t8Y|8hrK|!e5sQ`P_5s>pnqbjnAWknuoAZ z(o=?~^F=NqU1iJ}cd^t^Q5^oZ^$D5hnOS17n!DxY#^P3Pwc0PceZ3naURP_yT_hHx z65ST`1b3S{95A;c?OF2Ns*{T0?XJ}t+_;9#JwP_LyoeZZ7Zd#fvO)RQ_1*pB_fN=GaFn!^e7|zrD_@`3 z@6U@~9o9G4oox5kg2d#8t~f}6EBPNs(~dxPBrz?w6m6)N(@_krQw|Q{&XjXab+u1% zF2kdpIZS*U`gf~ESW6m-$-z}*%Uc@yj(MC7NQaI>XOxtOE5{lu^uRWa(siBK0HjyT z2G1{$HPnrMs~RWkvqf(l?Pj{*88A6!aJXGL^tLs|zMIAc@H=woeXA$kU*v~D5GA%V zw+I_^Q2B0S<6|O=8n!h~bUEN*XKO{ax8Z3Xe}eY*3SN&LuW``ZkM#gcYS0VdygMwK_?k{Lxg8bDc=@1k;*&lRw;RKtJ|6oY9Yj4Nek31 z08OD)B?ELcWK+77H1SbUUcN_)11{MDuU)*Zp3w%q96ua6zSpa3{mPqi_>kqXu@%WW z=&Zq*#5LNyy|6}V`jayHhm57fy-2pv_(z+MxNh=eIOw)vD%V&a?Si}V@-ehuMxjZq z_D9k?T(#i+ryEP1%vV*J-EOPs&gW&hs;PxWKM`de4vbrY6Gx(`YiRrclsoeS z{7%XsKdSp^<=KgLZsa=Y>v$!J&9WF1vb1c&RLhy2cfjx#BntiaA)k0Uwt|@cgW%mO zHy4+_=GE?~^~0qBkRsEBD1-qdget15yE}a$H#Rqk-c6*tp7Q$zqzS95Q&v^kY;5a? zE-ZX9XjU9@FtOoe_}c30i)LeMZ#*dwy1y@!C?z&1bTmg}y&(XGi&rWmE1PAWOjVE6 z6AsDkdMot(dqtA1D{?;>PmyR#XBll@JR%i%t_ zZLPV%h-h74E2DH!F=h*|T?0l5qAxLym6SFpye<`}X)55UYTJ^bZW%|xHemmJQ^FH% zYG}pOa}Smzb*DS1*H$sNhm7=JhYU&C$3b3pI`}=5F#@2xo1v+CLM4xQmX_KX+UKk3#S>iNQ2u+VCJ?dm;t%5}?2sY>47v{Pqdq^Yvz zI;6Hq+THM}dhH3mVoOD(nTG`T+Z0gb3RBx7nr8dpylYbRs;~a@$@b)gd`Xmb%y@|D z>}NJ^BPfZ@#`9&1+wA@B@&{aJM-CqIAcT(vr0wxadLof#ejP>u>(PbcNCl+B40ru0 zclljQlt|uZV_jqc{ey0>=443h(1ue*kiuQoF-0DC&wU(;NTto{i1WR87E#XG0F+XBRcxJV3=6h_A+7W@v}YHk|Q+V3Z@~i z)Y$9zJuF!yBu2H(&A~J@BV?DA^QwQMOw3fhw_{&C$7X}x^Fbg#lF&BI<6p9DwRW2y zw`ujSr9mD`4=Bu|NLpeiy6NGsF`fkLE#>Iy>VvmN(y2-*%nM#Nl2Q$!zMGfU+KhN2 z%gAYf>P(*3nb=+o;zpxfl8;J=u zHz6r0BO?PbE^e3p^Jjh`p)mD1V~L&Dsi`U*qj@kA5|WBalZekow1YLizRa|m5_}>e z@DdVXvG#Eb?Yu2gzE6@aj~s2*?0w3TvIdt|H;#EsEI`)t=M}KK8+Lw~hr5%;fyRfV zVUz~>IAT}{w>0hEDuyYhac>-~qT_McdnGsH{8}=TN%4S(WG(3m>qggBh={en( z!B@!ge18Y3e^VS0S4K#bl|)WCwU+r6F1far`SS8|dnT%41@!ak?LvhE%^c-)fR-a6 zdD2S(jx1uN=dD#|0RDBq-ASFuGaKzct~j`6~ zppXy&K!uu`nmQ^ah1z!k#?F6WbgZ{g4kIcxk$8S@ceiV5N_G_y(eZ-%YY3otV+u`7 zjH2J4E{L+f-6RlA3fxMfUhGK`a?)TK4%t|`K+Ec8WekrZ!3kK36iMWhX^O~|k}x9c z8mNNL^^2y(bb|Wt%zrM0-pFKnW)}LBRLLT54}dC>$aY4dO-xLx%5wH?tJJ6bzvz?p z67zD(#eE)<3=|~8-!{n2PBef)-QFQOHE%GFR!&bt^hI|ljj`DLCZAEmOD0}N{Fz;o z9sd2m_;~+BrsMi@utnoDK5va>@F-&ihCYDVx)&Y5v{NMq5YDM(Rsfo^8T-P6SIB+hS6iMt3?-!L#zz(i@tnBpzm{Znr%R2@&DFDL|FMev>)XhnF_uA*%CsI61L`Ehmxx%JLj9D1^k9Fr?r}A2Ow>MJd?Gbx(6<1Hdx-Uq@EJ=-L|o+qZ8`Lk@9( z-u_Rdq(y}|MzApj|F1t$-;iaDf2hy~x9az-0FEIu-ZxbBZGo-LTD@Hxd8WH3V|Xy0 z@)3ipAl)519Og*VT?fv9w1gIO8bzKx$kHU+Vs=`nuIE;ngqKCmbwOIQA$%Cmg#e2s z*nBu;wl5m)#kI*{JG@jD3oYnZ0W&LD%n#AUT3amU%IoE2Bu#jdogMhuG2>&?PUeq% z%#oIP%@{33*Kn)d5#tcq)k%&^#gXpTC-fs~)#&0MZ{;)Ipg z)`+rb>Vb8Vtz2VFp!EKXuCdcSVRG(i_#$q0t(WE(2FQV0qMPk-h1y6>C)ts-a_xa*U*cAbO_Qy zk=`L8kWij@o!5Q8?{ly9+w;F=@IgSlt))2j90t- zMmGnR4^qaux;zF?_u>S3PdJzf6y&122!zGIKJ=Tt)_2f;H8woHsS!f|cxrn#XqHbN zl>XL1qzsF9FE4cHci(LHEr0P~x76|Hug8?!Yb*Wg6P*EW{1x>SRi(=#rS!Of0&Zpi+WGP4O*puH_%QN`;#R$zSDQw_&U}z<#r|70WO@f zof0&+BwfEhyYZe!IRoJ;LUZjr0J`yA<7Es@yLiEi(E63H(7wa$R=B2yl^Epa-ucma zh}rp`e=+~dL~(J2)Ig)CL^ps8N~Fcl`sr3c2To_XZt+0{mxbB(RO;n{Gdq7}-u~_{ zrGIVi%y$L}s*t)z+hnu>23&Epz{eGO4gcH?@|g_~2_MgvC659`++U$D4mp}Ae0s3f z{pZz;Fa^)`T9C8*A5h;OA0F!OOazptt?%@^KR|ql!&b&|S7&SLNa)oW&T}zV_Wl@n z=z^LLpBP`J+$!jg`D}c&6PiOB_nyrS7#HD4x{Weh7)s``9@5vT&Qtl-zAR(ft+Saz zs{1Lg`8nw) zuAoIVjXpAH$=3m2(t3FTtQ zBm+`K$eJdoqVQUbclq4D7i=wme*rPuYl?DK))v)?AP?0n6gWCzXe&O;wx_eIueG^9 zo&IEJGg=__m&wAsX&Sqm3D8m^KZ64mJGj1_n59WtvObv@3JZQiXyzX=%EU= z7Xe(7Pt9l=T|(D*tTi&zWOrU@gc4k&nitffhsRz9_DlS=#BeGo3r49I@;ms4th*xwtfA@ITO#3xyZ~_6o`?vx#8KbYw*5{JQ95UvGEkevcBcPfjQDaT7{+Q z50;)A%6JR`;x4?jwtf@b+3*&Mn>yERMbDy{Vm|ZP385enp&oCUpv?3P^%F}8`x11b zRDmI1yt`Ua=A(`XWsc|nnHO`x(^#C1iK8P)rc!teo#3!fU?6mKd~8fsBO!40JHq`2 ztcRV6y9UN+u@m&b!xu9yF zWeL^S=6&2m`1ZtbLxR4pP@9ND;0@TKbT7r4*To(r#6*`P$=N?vYFa%j*)I(+`gZR$ zG?n4ovz*Dd+#qc>lS{!MK7U3U5;@}U9%yZUP0Hq3fWkKTYd{g-cQz3mX^kTK%!5ra zQ;d*w2FZ_+&C`XKrHY?BkDb^_=_2k}+x*S>BqURG1qGLupFl6i#j_@!lVButW9&jN z6n;yt=2ckbOgEd%^X2WcQp0~!99_(v(ASZTSh+ntK<}ZkHlbg4y3SUJQ?9(VZ+y5UGGxaB8#RtHNl7Hww_&q=gbRUQ-K8;n^+{+|mMFd-@qtHVQ*qai3xh9QZiwO8*X^qMn(M$f z?QQG3pL$)i<#GZFs1pvwqoN#R0^dnYp zH!lr-0rQ>w9?!v>7ZyMWVuh_3f2ehMZ)~GukPA9}5*3gO6Ef46j4oT_=^?6XK z&j?^7y*-+Bt9A_GncQNL7DY3zQ=%!=UT-p#1B03Zs|R;>aVI}T^OTjp)>s)?27G=$ zA=N9sJ3_b87d`~2vEHKxs>bhTTQob>s#RsGRr%gLWrxL;e8T&hln~o2@(^X8h7YF< z^U*BHCr%W)`#}f=iZ!lq=iKGjoE%zfdoEKIvaQcxulFzyI030CIQ$;TUU1Vw4H(C~ z|NO|v`FdP!N$_K88E*X0Mw2P!*9$Gmkgd2-$MGIw!SK~Pa(teq8B0c;bs)KB=nrbV(l<-s1jb$NimHI&&VxdlzuuQ$)X^d-$ z5+Je|m7Va5GwwD5`T#2ctWbXPUjGae!-b@oy7?x@he-|{N;-v8VGi}UA-eUoePzcvKu%(3zv-P3B{hg|$NZWYnt0g-x0#L>1U_>hJ3kk~~BwPdE086Ly zi)L#%8G<%1K*qC#QL1RWca9rInRf5Ro!n4s8-mPh=j(}$RP2XBmJ_j9??fWDWEf>W zi)p@s74BwxCB!ZIO=#MXnar%Ly^JmSM=>F znU=UtS`oY5h9;(_8E{yn-2Yu-b3azJgS4|ln9$`+FaxKceLISew>r7aA03*15mbq~ z0(l_hQ36x4m#oe`|BK}OI4PT+<}18x0d~nW?j?Q zKHF|Vi?;=?tjmv|?t`^w6S}RoXBeD~5KqF~+o$f9n|z<#E}2Z+X~yLxrj@TI1yCkk zEGL-dAYc;gS+O$eVLhJ@6AEPQyT55`Kd(06fda1~0mKwH;%mj8SJH3?7}a?VQ+8>m zl;XgdL*AOF;|5S}4|4reAlmbp)LGSY>rs0}a39r}DM03T#4X0pzuwvG%I?!5L!5*l z1L^`g6*n47(lZX>>L(rKSdm&4cBN#MTq4aPDInI~BVLRKI#s+z(N@v_D4E}GAy5x% z>((>)AyX2u(uT+FZ+%(M*Fd^rQ18cD*)GCa2yVp5OMpaK3C46O1}oJ02Aod$TI9+< z!*nXf?A&BWz>8!3of zT{Q;EAY(E!8JHbg za2*cB`gD6OMER^`Q9R)-*W(NRf076fsMN^ms?>dB=A7%*>q?DRW~nkq6FF}mm7{`g zq?@SJy%htWogb;=Vjljmw1!y`ZFLkPZ0tsQCN-qaNahoLd{gwb%aV3#%MB zx?czI7>9XvQNQnL&{D$71+@at`5AYto$c+HPP^=WoHo-YXoxCN*BtqX{gxv>pz8Ah z8jB?{$+|!%x%r?pdLd+38X)W>SXuAlYZw&u82Y(tD1#q7b#~chX~L+kpp*UaMUp0cO_= zx5nOGx88hBOaJOeIoj1#seK>waGKI{#}&?`=v*PXJiBt3_anWbEFo)HY_e^QbLZG=~15v7ed8lu0{om7xRS|5UF3c zp}K5U-H#PBc>j!8c<0B_&U5Ps^?EI+5gp_ehFUTp&DTZbgSYjoomw5>@FmnZYo;$l&o!f)k53g*)SiICw!f?+p#?8nRtzqn#*; zxnbIqGg6&-m1tiWmI-({-X~H3DZrk*qRF(2&{oHx*JcXG4V(pDd;@n4&|pJkUB89u z9_VUa>}npH92~^1)VPEfA|BR#hz@V@wVi8)F@5X z2Vy6sHk={>(<8p98a_RIha$O}Kl{I_wQOcJ4bnYa#b=JrOH(^_3Hs zvfw%bRB_PFSD~#Bx9WAbPI^lffKa7rurM@Byz~wB;1|@P$#pqLxRpedIZ?4xa^Mu%p{WX9*mS{AgT_g1y{4fbaR22wn-?BZq)gX(xy9v-rwOb1uZ17vV z?ZxlW_2(CK>+QnFHrV^GK|7gH6vjjy7BndA}%bse3Q_g;aLD-?qUK46KY z!NsSHhDhZ|4)tX-Yn4jGH3johk^@K4Foab_pVDE`Wb`1_dr4nfJ^#7AUw;?mageuZ zDHHWL>{H0IqVaPq$zX+j~h$v~ewxhGynS%3mf03epoWw`zn0 z)f?Y+iU&VYQ-lG-4-Sj^X_WS^L(-sImjsUgar0qB^yR$S95-KtF7h)X@t^qx(L#;~~G5EPZUF*jh6p=ShAN_Df-K zcO;?}Or*Xr_kfWZ)OuvS0m~hcm$^Ke)e*B3lZ~bhB9Bw-tzDixyYWD@P%R_-^Ro+% zO*e!sVuB@a&(jDHr+oTxD79?VTKgYZ-JhKmA?=l zAKVnzUq#-c-^#ZMhD4ys9<`#CXQ)a)FAH8RJS{&s_)g_TK(`fz#+dE81}vs|GR8`T zCDLU?MFqAhk?rIsJ1Y;e4)<4Oa2zZ5=(~y*9O;TWf8uog@NFvI-4q`RvQ|N<6*#)k zh$2I(x`|mExs^1>94ua(7NcopuHr9^k&`03akDyv3iCVbE?6C4E!+i8VK*BXE_#$| z>3t4oROG-o!h;BaO|A_G`!vnBs16o?bbYX_Fbu3)dJL1ep5zry>lo7Z|QMT72+W;lxk6vi4g2h}9n7C$PtPkYq~0QYOx zDhoUT+)=*9m^B7e-i0KI6!<$W2&hBPz20!`-!Up^pC#T_p}YggZBRn~_9rVpZNko0 z*x5|8TmDD^VSL+r1Mq+B2P#FTL#%~E~6sJUBJ<*qn8 ze?d<->skvaxn@-vb8lYeW5}DSZP+G)L+7v&N|RsyliC3f+`!X!BrXVgojGM>ra1ZS zFt93$q{~)U$!4VQp$@}ybp6~3ov2~S?zh1sM1tU5NEIaVG`HM4rY^~3qejSF)3>)C zZ>}--HgmY49HE{FYgtd(S+rgC*)~HnX-*09}Sd8-@#nFwV*kqZbc*+cf@RZwgAL>3}c00>{gI;AD(J3;yX zrtf0Xv3c>x){h$Ts!ePYbDP6Mmn^B+7yFPa4)9 za-4!iQ*DI6%(F{xm8vQ8-1GaMt3a^Qf*GC^ub$!;nZ}h--M7nwn_$;n3#M0>?TY%I z^xt@Y6q+p5+oXuC;SlYtKTt3WD6y-7_EH@J-|a;{m)4@bfkfOIhBmj~DMb5O;x}d{ z-I+!A0s?}?*H`8(xlU-G6V84YWjvvb|9mMM`@7x>Gc!=ii4zWl}U#!kQV&D9jwH;HWSFClt z`aG{vjST$GQbQ`r#1t`#FVm&WZr<#m#E@EdX7OI)vXw zh@Bc4`I9b!g-S{Ny#xuADkCEU)=Dz8b-PDS52uvBYohaqqC~%I{zkgFl0X5Xgmf2j z!|wzJD|@ltzy9f-vfsoVl#WIhba}sx?b38(3Pt86q6kU!AV^MPoPucoN_)2i(V@%g z=tyv&a9O>H7i!%2E}=ft;rdb_>Wc%RS2Jv{PKBUr{pZH%dN>_9b5 zHs>1S>4pDRlS8Pus}S z5VH*q^_n-&NksOKQm!xLNB7E(B@^2Ov@fd8?dlpK+UtBf8;^p?^BvVM7fC`!g55Mb zWvLS?~H%qd?V!VIzgcdfqB7F>cL7#q5t>Oz)%L%-fB-I?_kdj6ae%Ev%9@u zJiFD~tW%M&$zk_PUjG@MfI7}e)iLZ>U-~y89Pxn8NpH%uA^%B^F7qg_REndWUW#GSE(NGeZ$VhES?thu{1yk1PbeE=fqnQyr)!{ zO0d}Yu&5H6bF{>D-MsP2bc!ep#{N-eR1)K2aLtyLTRaut^fXQBWZ#r{XN>uk&P^OY zQ>mP*%c;txCJu3`5KSI{SR*gKj@C8kGoeM2D^9rbp4(oUOec=c*=E^%4MyI0Zl$Al zEvJ%u!-P4QS&d6}5BIK&6AlzoRTLGxNtA zeIo_{$4`s=01fF1jSxUkCn0PYlm>tN5_Rn_YHD*u0s0!Qx=-dR>9a}*(Qq-K(HC$TM znS5X0DGm0n^)lT}HbrRJxgQtua{&qLRu)T0sawgZv{sp2By8x{Fnv$#=i6~Woca+z zKV%?-Zks+EEO;N+xH7<1R<}O43veD`=<{FIp5{u&y*d2MDr=TrSc-}QQ$~xn2w-i-dsiP>J-0#N|V0UHa>J;jCxn#nD zF`JBN-ZIm3d@*@kd}8>_%}nrawz0~pm==yoRz4c6aphpDSv5KB0HJ5Hld8#Z?>MSX zQIBun@5|$6AlgX+$YaTT+vT|O3bWUOx0#;Ax;}}advpfroj;>RG%({Fr!)y#N9}sS z%cN0VUcE(Auek6wQr0}^eF(rS`EXrWa?p8rCFAZbS*{sEup@PD4`s$#fNuu>7GV3H zn^VT$#%Sc-rT@tje@>P*6^J_KYNazpe%sfSOYD;rQaq0nNd%jv9?ZPC}YJJXG4hy`*-V-wiV znu=XO?RtCbH<9WRRsZTmuy3V^%3rnHiyKz~HM6=u3F$c>91BTU`q!0n`Yn9kAN({A zIqrBhLfAj-tIEa4tKFHYr)1AI7g_SW^JC@s$03;-HLV$kNwsU2r?rkXMz1(I=0FmO zOe5c1!;n!T4^+WQdeArAb6C;6p#~5Sr9P{NkZ}v{_HZ{5{jRzRT6mmLrfFD?gH=aw zV2&Z7^oXG;IzA|<1b&RIxR?Lb#Z6H#MHTFWto z4&v0d{7R`}zin1WV8l6si{nzfg=|EN=HPh5i+6j41Dxr1?GP{dgo|m?F<$B_UnHS5#nt%V6hMI>-wp<+jmD1a^A2*N;cWq z`(7R2OmgqBqY@A5JMX3CWXI0(N}+G})Hnakwa-H_${umJhM*SXn-^89Yk#5L9Zg5q zG;{jV#epo%EZ0%m)mzPHX8IdplT}qc@3d9fNhZVluSE{hvbm1LxyxtO5k228rl;qH zJb5Hmo<@rCOJTydyNldkO{M)+HgTpAz%PDH)+>#pSOo>9&`6@RaLp?5$8gU%AXI6@ zbfaFtd5+Y;wYR4;B@&;Nt3U0FinLWq_hc_s9t0FgY`0}HUlDzxJ#*CF8Y_FHJD(ei z%d&s5U@zi8T6kwA)G8!UwPCl*3QC7f)N{o)aRD@!G5%(S#zTTpJgsq}_Q*SJ*8q9_ z+eB4#*+}K@#PK#dm1*e8XAG1|@NsbzaX;s=T;sISd0{QqgU`OkR=@Lq0Gt^Bm7@dw zo^26(g|PykmVvPO?eI!8X;iwa!>u1g8yT4@yVR!w7tZ^&ZqeN2aNo02_|f2P1KrEg zyfi^PnD%ec8t--H6wDRn1DU>@>=wRO($wfsyTI`UI@tXMG}cc}4V2&Wao1zE22fGIFjt ziclE*VZMS@%Oft1gAQiIq9JDltzNra`#bAXxHW4(cP7Rt0@_HwFMdNaHt(w<_LfL1 zFEX9O{Xmz?E>sJ^<1c-6Hr2cyU6P`C<^k)hL6{>zTnx>7;c$ZxveuYIhi z+r`hO4NazpNyjqrvt<-OLSC%^31&d38OCq*53hVGX;|<+S^d5%w_Xb}7$t5t;nVd| z>}r|B($$GNb)EGy5hNWe3`Hl%z<^%j9EtQ`5cQODkG3Ox>bD@msM zP|KM{0JkcxZ0+NF@vQ!TsKR>kZ0^S%kb69Q{!$Cy&+mr$eg305Ub6`NH&Z>;$_L!f zi5^)hoiL)rvb3G(FSki+98&xbgw%S>^<~;_$!+3JbW|`EC@i4q`;FAz~(U(5D z;y2hW-4C4;b!L&@=KMI31kYxL_(nwkzHkxQkSZpU_Iu^dAs5qt>v#H+@sd=7rxEFw z4)m3+G_y~cua`G>N)u~qq+0x3MNvHwv1mDbT3R<{?FdY?2Ni0g!^)`hNea*!p9vvT zIrQd>wY&n|&BsZLH)6ca|FqJT!p#sS=E+Taa?4fjzLuSDKHMeUlV*$bxl-k<+FE)q zouAU(Q^Wt3g^up7jaF*iZf1dYZdlQaodB-w<974x^D*il=EQ9amOVb(SKNZ2G0sEG zuutmPakhfK$5m@?eB-rT#`oajh2EOD(ej!L6e6J$e9m>$r9B>x#9 z_z})V+Xi8;s9Q(e$m=!_$dV#wJFO-~YwYK|ukclF>dCbw{c{wHetKhcLDn8?mund3 z9ezh@pqkq24 zPX)($8H|khKCcCyqL88Cm-1u76L%dYV>A5?zo{f{mR>M6r&8A9ab)d)H-)%`-GdK1 zT40v539uQ>rO!X&>h;7!`K5#h6H{e{3&oMb1#b#b(i|QwUnws(A+Jn$$pd^fUA4!1 zQC)JLUvq1YZ$5dCtm@cTPFRh+%i4L+VEsZeywX{g?v4w&<@D|F$SZkJCONTuytu@7 z8m5lvR61(z>|wT0BN$+3R_u))r{~QmyaZ;V%c3wH$KTbg$~gW}W)p$u6ay z`<$?f8y1Wu+BsIanhjuSwb}FklXRJ{L{gxAw6wGu z_S^h*CDI$-2jr5xkT8<$DgH>cwVl)4O#MjJ>Q6$vH%;pBQ$O~npQy%}BsuclaLz@! z`(Cqz99=&OZS_y(Zv0(m`{_6O2iRWDMK$LQc0FH^Uh9KkQQvJi)SLy@wvHK{9>#Vbz?L4cu^gDfu4^iI_LyKq6 zklvJhvdvv@I3JW{b<`fhMyQPEq5w=PoU+o=8tO?5VWvwTxpnrr)>oA!nTx-XV>o#D z!VAp&E=d64kGzDX@}jySU?UCfr0tn9QThZ%i|fxs(={AM zXxC`^Zfz6YjmTaUqMPgrNrXtu~Qv1s36rp+eq)=rIP z8CoylRPL$<)N{_~CBD=b+0;I#U2d0l-UyNap~8lux3I`4Y3^J5?`Kh$?7t4y<~50v z8h4@urW@CP#+ypg2-O%$_DFv&V2DdnhFkOfVL$+0I?kScoel9wL3iuaSMiLViBjKe zXd%Gfxvm``pMXLJww{fK$eo4vpLTM|8}uO{Rv8A>g&W2tQIm4lP%WiJMM+wFBh#1v znD!*FaO*_-k2NZI>Tl3o+rA4Zbb6=mBz1A_=9U*8U`M!#@!3LPI>(@ZKO#*P!N z=682WHnU9zT4y>58bV1rJi(SN_5~B2OSE;fjXS}ei^QD2C_pk}N^08isgXX9K$lmWn3F2(a?b&Aq zf)DEf_2gL{rQWe?M<0Z$G*)K(9<#PzJfRmAsNQC<)$3~9euorMi5=+$nf25&o)tEq zgDZomF}YigTMfG;gh*x~%@(d{E_T>IXIEyJlWl5oUGN8`f>NJl7<%D=pJoKSQkW6m zxmxxc26asPO--NNXts8B^p=QRFf|{ad50~)^VjvaVrrMlg>J8{ZRe*q9HIp){Zc8n z)wi+{XER^SHgzu2L{%9Hr;VbV$4hQDfhKbfU8m*Fj`ogl}c^SRzAo$CjP*e0+}`mQnw zO()KYO+qcGdxP_-^I0ec8vzt8Ky4?qZ@3G;T066n_o_nycuF}S(^JXY|Mc8@O20+N zJzl6?HtPndfDLQm5X3!$Gmbg?sX){Xp_vQAMZi88z>L+>t3}me)SeiTU6Is934q6I zO6{P0LY2KkAafEdYvFn*>YDrCOKYUXb-^XEmbCQdX28 z95c<_To$`vU*K`*cqM?;yxZLzB9vwlVd;8q{a*{v=r_ zk5_~z%F8!mrtcjGTGqpb%d$cR-=F-PDS$n)tja$KX*#(f@CzwViT0X_|8Q+&6hkBa zq#9YHeVX}?r|+3zyI|iVn-_57BhfZnp4xfuH&=l#4Y=(4&8o^PM81zI8UpBmrt^@`_Axo8&2PEQlTCM~w;G=Y0C|GCeW z)PY7`Dw4G&hLX{AhoO&Ow6wmYU)Ji6!O?RXA!it)s37y6^GO--1U&M+e1M>JZ6QbJdfR0mz-KRv|LhhFyMR!fRt}Tu^(2Z zxsKw$9yIuzSh}Z^1kN1Bw5)25(y3@Z)wgUhi+Hhdx@Z8-dx^|$T{>$j|(rdrM zqB(U(2v97n04)~L5Ou>&V}UF+!v=U~%^!w2sKOy<+r7Y<`t}Jw#yPH&U=OwDl!^uh zR|GMKtY%kl$(Je$ITF8RlNOnFJCfs_k+2>x=v#d8TYyBJp0;z(JY8+R6e=|0DCWDt zY6gXr@CNUh@j5Sy?tqaLEKyI$U1}bQC1m1p?uH$n1wcJT`(Dj&gMDe?mGeb~3Ys;f z{Z|l!gfsMJ;WTPBG<>;?=sp+xNNw!o+MJYe*MRq3UZ=s*!rY82P8ZYKswfXvYAL7Q@d$=FcSgz=`je${ThxVNMI zY*1R*w&rgvrrggU>#z88KTCB^;HJU7prQblWO9RcK#V*yEK$e^{*Qc?U4rnO3EcOs z#O=>#a_zQOhG)x5cIT~-*Yb;0uN}Cnd_7=C3mTPU59xT?nrKb5k7)U_{R>C6CDhrA z+65KlXdi%$FgN7G0fibKm4(vl?U8L~MhQ+$hjvma62(|)kHV-*U^sBlqStK7$VXDL zZ7zl?-I?gd+f)aB+>uQ40@DxW-mc6s95j?L3L> z=HoPM*xKV7;(YEG1$JFh%^8RaHAHi7Rp=6QZmnIKTu14scf^#kel?=vfQSBak087x z;!8d%Z)MOlOphFHC@JxF*jvtkN?X8b68{EOejO5))!J#^D0Ye%#vIoS8y<`1;z6!N zHZhkEH!;lzsEuc^yUNnnNVk?+l;Vv)x0k&_TwYpvu|Ftx)a-a8`B4@+FoTQUj?tT3 za_CuuHkv`RGER#Hyy=@t-1#jN&`}EAkjF%93z+sr&)OQv{E++|Hd(2OgjF&H=J`Lb z1OfvZTrp~xpPHHMZ8uo5{9xA7cLP|2!)^<>ZMwD0yCjtZ4l`M|a)mqCgCZwU@A z`o*L>Qhavl`iNG^J})-4Y>uhz9W|!Yk#r{$y^kN7X%xV3sGJ@TZX)dB5NJ$Kfwv2i z+~8wLICIZjgQTFz=`h}<9%)rK)NMG@Za-#{RExKMBXl<9YS{LH(ML{EE7klDd!f&- zPqvu7Pn)baX=}rd>zvG7**pSR&JxbAyY_T9?_=za6;2=u`NeHdeY<3+}oG^jj7EEk^>K2Xq#ClwtF4LhEmd zXqm?=-j(}U>^0zG%IuCw=V@}BTDSxV!r6&6N`LxTtd4)usdEL4CC8$TLfaFAPrK7Q z*C9d$w{{uo#8M`{Ot)7K5)#Es)t$bMM-4Phe?07ov?^0*KC z(uJ+>Uhi;}^wQ*qMEFM}iiDmZR%>rolKlNY4)AbdZfd*>*jLxeO0+eAD-miV-{Ha* z*k5WDI0F|7NX!?sN|p?3C6bOn1t2A#LFSwTNuZ#b4@UR}kLwc7%?H^oJ;5w@uTKuA zbsD%1hOMk@md77#=!NqmrUB&n0Q*l@W3B_guF9Nprr6rD{k31;hzEDwrj^MBbo}t+ zISfS(w*(Y$<_6?K*ca7xjltro>4D}KP3h#N8Ek1vx3jm7u32x%p^d|hCKyMtYET4; zocVk99vFACr*Wss+QMj8fn;abpt5G5!`=-hAktU)${-%%LcvaYP(>wnP(?luCWcoH zR1)sdRk?)dJKd~TP<-hhAMH=Wl?R={C93+I5^NM|Sl*EQhP6|M-1A3V$v&XD%~IWY zyG{o6c+E=l-~yIuZ-1?Lb*sHlcqs6Ay!2S}GkRUyd?OqNuNbiF2trv+*e`K7GDc{j z*IL_hveF{Nc}CbWZg`V#|cRX?_KEIQ=|cB)a_( z%--xEcO*xrBZ+*RA&-xE9oySK4wsfK080ttMiVBywXKz9r)z=Jlcy0H-4Z@AW;{{&m z6trgz-G3* zUpba(XX#oxRZGT(ZZs5N)Ilk<@pKF(m^s=;Yh26aoQG<-HQv|j`(mGw*p^hjq(Hod z!Ii;QdjGa{CFze zuo?9m#2wQ40hpChaOQu@(Jt9X{x5d{JM=_IPo#{R*4sB}I@u+<6!a2QeUsPwHR(LA zlB$|qFF1F^hVfQ-JVVYys7!t@oam-o^4JCl+Ov%Y#dM@;QjG%oR6rb0rH^~ABd1TN z+O`8L)Qka%>3wK-I=9lGx>Kc`P9cqftYXiGsm{$UscCi@jq7`@wUQ#s z*BJdTURvxJ3=7UfbW9Z|r+%zN0jHwI!m9;cm%l>Vp}E(7)$U)lwSm}fQ-43SmAwiz zTPo}mOH||Sd^B0M0@!p*N47^8+>DS{OYD<0IaTXE9xkSYcjWe#**qQLsYU4gdu%GU(^MOL8t4=!+9)q^gLxX70YIKwzENv|2c%zOZ8Fjs>z z!s|{TII(XFM5#i4x&F6`n&559oqdmRh%6v^1j}H1U#3;TW7eTJQs=ri4LnfKbT@%$MdWa9FJVtVCDs{5=i+QSmk((eQdYc%Ag6^h`0aUIa0n zmg&j^kdW;?L;rh$*Zdz1KWSin%s?dHgM#~W9gyxtb@n!gNs2spAaR}{@T2%OjnNgm z-mfANpgBXLWaJDx<;yPXi>AR;-_Z+v7 zo+vum?Tk6}r8^mIf6`eO)y)d;T`l)#V+ImHI>yew|L2K_DD^}mY*NzGKNL-yYz)M> zW%>SeX5K(<8*P zqMrcec-{ho3w8NYXeBT?Dw(j*&K|NKxG8>;u_&XgZ=aOKf=a5mdbi`|nK{%s)o~@1 zJ3_f7{ixgu#b4~F@t<>wt<2I#5cZBy$OqwCJs+6$qD3%L{+dZnt?>p@ddL7FPszR} z(!Kv~xfPN_sFmE{Gex1!yB*_o`nzbnS2@Y8XCvw^{J2v;Xd5#^^v51U250yjtlJi^ zQ@4rjo*{wYl zXGcQHQQeAbrt-q6bLYMLfo%T*MO1}vZ*TYhF_M;kFjobN!*aW@q%5tm4<9~Q1R5J> zk5Wiicb<&H*RU0!{in=q@nq>C*e5(ynK*cINf4cQu#i#4TJn~LrXhmW>7MV!jHD;C z&}DH3NSlJ&8ngVcOkiw6FYRaf`lxw6L^K4!41S*swg|aPJMGQT9PgofacRCcRXg}D z9U~D0gU}ODaoj*%pY&F{Sv+4DPt$|`|GViVL%An@K0r&v$F8|Sqkb>>1sjC@DC5yX zzlP;kLsFw9hB|kXzVxc$d#GkFfkN?BVm6P6yZW7b_P(NYxRMNyk_q)s=Q-?<96XE) z&`uF$?2Ja?y*3$mQmxMMn*E)W<^3M)GVl!W^*eJg2HrE|`CF*gRYXE#vCRHaCmUoi zMbxmeo|l`LSFUNjcT;~e1|Pfj1poP4ggW!R<^QYy ze|^E?a`Nx8J)JVd4YRQ~`ua4m)r}2YEGSDzNC=CI!s1$VZ5`a}Y#Q|b{P|Oig`?P;n`8Zh|D5UMEEX~u zJ~N{Ml=-iQ^nZ5l=h8)e&xJW?tSH8En)7uE)oa!Mv`!Z(_bx5bi)50}2|8kzz1RM! zkj%`O;^J32IyytOGdwgM7juRzi{LS>9~!CA(Tdm$-u+z{o`H`KNOZ$GEu~r4{;?~| z)XlA}!(R@=DC>WD{@=j^GGgBV0s;aR^_dAQljsF6uj*fFjmLk13IB6~|FdsWv9#Qv z56Q3{oX1-Ff9om!?>1MTRY*w3km(6Cim&y*)R+Gm+W*=AKa{;?R8?!(H7p?^9kS_E zLSWO~NQjgO(%s!DB_JVJO`&Alaih?Guwuz6#3M+ z$YVc!n&Dz+2gpmd^z~u;z+W_9pWPTVMn~fyBAPHVG5KX>ak1jdZvre=eSKa*K@{Bf z#y*>yu*%A;FZK25FtL6BBXJsvlsq%Y!;k5;&8J}>bD0#|p9}X!>2W&l#$CU#)N*um z>^XX^AkQJ=a`WrSHxuB1n#F@7if4C&@Mm9)eWU&Ro&5dNwCGiAQ2rzfHJC2^W`G-a#gB;x4pQI+`~8bv4`JW)JIH_xQVZnKW|WFrZ+`r-79tgk2M1vvK0IO*MFEry zX04V5G9d&;t;Yb*lNfJdI+N*tPh!^fU}*z`A1Z;D7sSn`i^!=trwl1S2+M|v4F0)k zJhNftA-*%3--0{n`f}cj=lx}BSs53z9s_y7=l$@;eVyt&E33D1jn-+(FB*;6&=(SUV2*tae(_Nv$-xjeJ>Q~iro>+e?{kh`v0 zY5rY#9!}~X=B7xmml_M45Hz2gBHtDu&lb_o)q%Y*8@k)Kac-`nPXO3#P9Ev8*iDx2 zA)}QcaoT)OmH%oIR@XI;WF>AF7mdTg>=*CLH_Kfqd>+s8iaB7S>f8k(YBhvG~Yht@2E@m5hoz;K?#pX7Qm*>owTM<4(D z8v)2P0wdcC>kAHd}R9YJ^AoBC`Z;p<`QPR9_P&+4OR?{lvFRQE+)6`6U;0UWD<~#`CA=wHYN0lj- zM(q&TV1AQY_~&=7#Q+%U9@yb*S?muF?Yzwn6pi<_Lo;)c%a6;wB9$ZoicPO93l?SS zNIMR-XGw#CIbH*$>ZVdLbU#Wh>{K+(=CH>L=(T^0V}=qH7^rOQI~JQ7K-uk3_NWI1 zen;gSy>>=rNje ztAlajuku0Vy(pxqxj5yj^tQI6so%J@^B;nQfZP(6gO74Axm(mhK9IVwm7cwzc!VeX z3_oIs{B`>>O#l`te1Jsi5lk&-OX&!)9tJb!O4_X-wYc8aBQ;4ZHqlXK$cHfje~Pho zytZTjGB#7GbA|2j^k2aW2F5T7bvJ!fB)Tgz-jXW=xduuw!{}3rwYNA=j)UI3MPAL` z36Dr6S>ziloW^t^O07IVOFWM4P zhq($DSuH;- z=FFogoB*$zzjx5;14Y=Es*Vpg570uXkB~}K09xn=c8RLDfCwd3A-r1a3p!->0$Z*W2O_f0XF6(QC#%=des=~s;SJKka z@-JH*C(x3y=DW=Fcy$Ui!4DJhK(nFuKQ3%6BZ(u?BJpUar2p{fNJtUOjFqWMFb%9# zSY>POb31Du7njg7ISE@^Pl$_0&}*+~3!R`^`2kEtpa~Rwfdd7^5i5Lm|QA`WsEiArcXjLV(spFOLCUa z02MQXTswWZIpcy<9RY$AYMFGjGZOp2wyJX19YOKHL8#bpLeK5APj@1d%=<|O;+K|N z{Aj#jy2nwi(ms60b|g|xT^;$$_+B_(t!!s}xy1~Qp<$0%Pmi!$JwG}PV8Gn3Pg@o| z??amIt|j+ncY9X`gzl%A0~13Q*|!`lGOv6Wb|=;?!El=dm=nFVn8Fk^-pTaC{{@87|TpcDEdQ z=D!r?gVEg=(xOFHvOR5Px8q9kzG9ekukYXz^6^eAxYFabW}dmo?JZAeZ({8lpB+^8 zg{_E?0_nN0Avwd@qtHY}rEz5rWRGf?@>rk4nKWa7ODkZzES(&ZRD$A{1=@GHw5*QL zAvfQFBMhdMQ;JdwCk|rK5yv1T%ufmRU6QiLP`z?ai>V;6^H`01Bv0mQ-fP3-vsvxQe4QKC%Q(7CzVWw_KqRz8s6`qQc7>%oRj0xvo1u zld?3iJ;xyV$40W3KJVYN;RZviT&Wb7my4uHV8yYU1YX+ZgeS!yvlwu3@I9tsk{eoE zfAsu$cmJ#Ct<&~i<8KurV#4`SLE7h+-I2`2kjrFgTh|i)7pDxY6~!Woue}Kk1lX4| zkqc!dB_kc4i>5@beFlq=v(OMw4#}I)8j@9vz1GDyZ&Rud1># zsek|pphr$kO)cUkMQ(0kv9|O2_3O_!L#!s*yA;xuYOyIn^}EPffx3A14Bm%9BUl*3 z#NZuHr+vcZa#9)3lN|a^T3R|HIXM)dRK2Uvi;A?z$P#i>09x)bw)J_s5e85fwvi^+@s3GQAoN?gACH zy_%plci(>JrUbun(N9#f02=f>=Y1dl@qrK8W<_t$4q#7B_sb>=nY9|JB_YP&dc4yL zbc@efyiGY1Jhl)Z0kfe+o=v%fkcehyMk;-!TCnaelh0Zdxm45oBJ8TMljR$vbq$RSL zyiwx3!&={DhCe^W3)6eP*Z#GgaMX6l!xxlK7p-E5KQJ*DLdy|>m0!_A_dFXF`Udbp zmc+fNFPUUu&ws+6*bsI({tJ1+|F{Kuy0sCrH#|3npD;q4)rr5?Fq2WEJkTRZfv`kb zTS*Sd_MDE+oIV$(Blj6h~7xyFoHGi= zTAQXQE_TGHoob4ohBcHb_SgNa%;u(<;8I)wQ;sGui<#LkqVfDvCWu5nD}#wbvD zO?E<>scT#-f&!FEq6IJFz4|5dm0+zf3%{^1G~0@E>KAk$9P%oM*4CO!vwY}MB9rOF zud7VvP~+2X^k>BY-eVnr;8^@RENlY)95~advMKzRHwR5e6I!0pA$I^HvJW6B4i(ag z&8)B|EEa+v)o$6V(*1Wq!RP!mb*qb zklp^-n+ce(Ci-LXR?%nEAqu?>zFljozFn_)o9sKH-KqE7t;S!ee_fi+zvlOP4p(&1 zdts!f@4x}*BYdOn5FN_uSQ(AjQ@+qJpt##u933Y)>Wz5y%pfo05=oRhQ}apNU5LQ= zP4j>0kFTj&$w|2V5#4bab2yHtgbaX>)Th*p z**Q5rKI|g#)Lv+GpKNgD@b>oBSCs--{F&nfI5?EXRq#(qNK(FyrUc37q_6S5c!3IH zpzL02Z?`v?S)qRM0$AenQX<`2H z7KvMP4{3Scly3%`VKgsNwbu=CJYmc!B9I!>S3g8{bCK|LlGd;}Ch=GsY}~hj=s0#*3UM1OVdRC?>wxT7z9Vxm6)6~f*Ub0W(8V_$!IB8 zl3=d$pHN&}IOFtc0wNoR*wAQ6a@!-#jb$A5NYF=r=`XD>^`W06aJI}0 zBApwWaF*%5BTp|gj?B{B10I7N-_im z;sTd72^plie96i8LB~BWGD2rbh#qU0xn>ga2e81+kb@tcq-gmfRIp-TKyL6myCL>` zgi!b6rV11n0@bihQd^~x}>QTSqB)3)y2f!p5%>$V#9LP*$KwmR7rei5I(s#n@?e>|BH@NFZ?7^7cUK`e+{$pNO-n?h1!1<~X_LPQ z1%ndbeVx6J(cz2w(=9{TAP5Z!*c02aHK5Q!$1Emz0XicJ4YkBV?bNjzCLh!LaN2d@ z#TG()3u4${a-e36&E(m_{bJi*x;jGW?wk+yMa$;e8te=UkM%R5ro7`?o#MACNw&GN z?nk^hg=lZ9P{eyZV20=Akfft$FfoRk(sFa(Xr%k~O;4-N$J1p4_0&5jm4zefbs5}% zN*u~pS4Jove01D}zweocdk%34iBHHPAfZj&a(4m(0)2gbQZN`5KLieNM7FE0NJvP} zsHoaTMld@%I|6E~@nX}#6oAmqup4q1RH__BCATa{mdpK3qJ6TL9htpW#-iEJeFm zVieTH|1a0PoIHK7v{ZOBVOa5pf}XqRy=CzC(*6WCK&moeA|@&dK|0d#wYy1aNbRlq zs(}%8N6?xy0{LPSH6O;(($cZ=CxYkgHpnO_9ll7Q)qc2=k`m@dQP|s9;wm7t`o>G# zQS*~tzU2p(ttXrHsz<{YCflZDlJ)%eIP(ZCRPwRpZ~6<=pBv->fBhr!V7Y-z<`vQv zoZZ6IInY27qC-@PgSDW*&x(BY&;YKFD7GM6_sCn1 z&KL(ZAj$UMWzTNj$;ihnH3&`H7KH=^+_@9hG}$a7TvjRikkoh%37b2A2dT0l&i&n? zHTlyWbHCxngalZ&MSM;oKQS+7pLBE+pW^-|0F?c=?N>d3(z1e_7&$Whc2((i5qOSU zah`%{Yt2`=)E=+#_S#eVWUlP6QbB24un$cQ16L_^^a7Uu#`5vJs|zn&CA-o@46}da zJxtuuwwm(s-IM%?8v;a-!ya3Wa*J?$yh}*e#X=FSfb@x?Dcmj*M1T0(>ND|Zz=P@@ zmqvT`>%1!vd!XANE(j+g38k0R($N<9BmNuXVtUdPo){h6-uG;E`*^kVO>HPXL+Gp) z%7Yi!^oxMGgR!DzQ~CU{ZN^AX)++(rMVKwdMNKCc$@X@t8?ugj+3Fg%owr+0io!H( z@+yeOCr*l<`}E955=DG}0;}alk8x{W^U#!DQ{k_6y%=>bF@ViA!`(84TYW}O2}bz@ z8l)imK|Fu)zU}Tk;2%;#7;;=+I=u&lifok?#t>By?7--bMv=L@pNk80$RB8)%|c&I zt4BF1vTXwo1R?mndi&=S4mW9!=E~V>s;kqj{M&2;RbwQe$14mBL0PYMV_aTd3jSzC zm~(agzV|cjbleSih#!HB(OB2gOIV{(-DqtR?y6>rk%`Txqy*94g^Q7yJ!UI^6_&Na z97;omy&f*KwPq2fhZ`#{!DOgX&5Cg0tW4cX$0F$CNsi7plfZSy&{upm==7@Pf;M@f z#l$JyDRtxh-;K9--94YM_DYoEh8a7&%u1Z@b;g$3aP8)zE2eU8x8JM`o#y1#fAE( zQe$)&j8?;Lbi~^?aDFCZ`L)`2q<+_`X{7H#>#~WVvFi80MNNn=6I3(TZPBp~ zQRdxjxRc-8@wGDdFEZ<55`)^dFFesb>i;@G-x3jeI5;?By>9>A?4gF_j&5yj*@C?xWo5Px&0a3V zSO%?_lh#{amq|16Bw|m*G#<~-9IydyCH=|o zBzwkFZuNKqgPs_0mB{SUl936;G+^VXE6QYcD5%QJCX$Zh#pCw62XaSd3@-O+HT6!A z0%p0pW@)FSq%7tHNC%o*TZId)q=Lt|5}X6r~CN%nGI+-6oI#ZR+={C`fL)w zKkMr0t?{z5Dy+l9!S(P8!QLQ|-={RS+1z$Za3N+19dCpYwSNCV|Ek7bQ-g8$# zB!JIdJ+zO+Lt9)$H6OGUC!fZ7vT=YgcU1;xSVUO@GrBdCVo_K-?Tzgy@ag{uV^LW? z;w*8+5_Y;(P?YIwyPpJW`B)zGC|mF!5t$UL&tk5Lo7aFrHJhFq0d<+Thum&cSxpN_e`6+}?9L=Z}d z$MOR!YmBc;$Vzo2a?E!arSPK(s0<*6G2D?f-djFSK44&Z$O#db z(3z3ARyq@x2Z}&RK6SYiO5q>qa76`{G#g%jGd`XRJ{oBRdMlLx2`V09Pw_d|8s z{94Ax6+1rzrnkAH<1s2KDp0l&R8)*nC73f;Ex_U8;xgUt#LLJO(f9>R{qsendrI2B zM*dv(*@k_IFiAu%n+};iZI@nxn&rmAn{ydio5lu}3 z(9qDM*leso?-S510eYVU)gLK-vgQL$m)U>|nBnoW_~O|zJ-Du8PsR3Ue|VEUDt?L+ zo-AjY2@D2yz)$Bqr%Q>iTy@g6IE_neB!C%M zPL1+!XeFd+SOGDCxHRjDZzeBmad+=+kYv_!O?(RmUshMe7L>*YGT&c4-ho~jQ-E|V z-g%~+*lFpkS&IYEd1#iVH!Oc{K}(8Cja!|6TGg!`3r(#bpyncgj(Codn!e$B>-03H z(O_qKZZ58)BmGdp7urfI0dKIz^vevUj*cM2SFd0DhlD&YEj=D;sG|j|2lzKMuq`jY z1=PD>Sy<$=LZw7N<N<&RMJ98Z!G49U$`xCx^;Lb(5reD49+DoNrxs-9Gt#A;z@ z;)VEp^X}A?3vD&%BKBm>ai*G8*A#pFF!MvnQx`a zV!iX}6v+es@nSLNG?`flHb_?$cqk!oG+~BwBH0pf zx59Bfph0$zG~}r+t5w=Y8rfbigUQMA9zE{_Y|0jDQwzWGOdo7_^@l|SjCCzf6*V=A zpUP7bFD;z1Ue_+~*J&*3FJOp*!j@Ae#SRnx^pmEG+nn=q8DcFxJx_p|hv>n4!_wj+ z>5Aw>U<$a2-ZOH*+{$M2IPM}aFfj0*4!ta{r~rhk>iVjxs>JIY_pAZv!$YkR0TEFM zh`iCUuweXo#L^_})QpMdhFUA&>7K|(L`P>;elQjOA9z9|WTxJR|8vHL7Lw0H(YX7K z56V6V(7L>s^NJB=n!KNZY6sMnAe0V1HF)iF z6OjOorNmHPTKqviXMZy-sv#o>t)4egn*yK@hPzl`4S7*50ETsuaUZI934b{cLGKLn zd_)Ac5^Q#H;QM1Shb=m1W(a^*12elw`z1aBLGPjs(^G70QZ}}y?Ck8e8a6ge1Ic_y z6ciM|9s=4DT5y*+IXOVRXlW!%(s(5E6Y{Kp=N&JgF{eN04d%lzR5b%2FB!g{P-$pr zm{Ux%3w>@v44WK{00ea}d0j3h9$v_a4G6&Pg`X@gX8dY^N2V-1^7+<3qucC$ks4`0 z+3KO@?{j3@2zBDvh-+`;#HsQX>iY5504{gJ@9Z!`1rC&Om7xPJb*s}t+cu#pwUUtRzXG;6ix>ne8fQce0r zYvoWb70e(N&HvQP6 zSO%qan}ff#GoaJD4f>DOkvlsBY!gtUHVwp2s72l901E;1g%77WBt&Az1NX#Opqx#n zb$DTXg0Yx{@#6F)h*r>PY4i-{CWL6{AoQG(Mn-t`Yp09dv#}D(&|*cyVfYy4;y*pO zr6lq$)yvKfQ8uK*hgXsA*HYT{CYWIBvDus`;q8_YY)2k#VOJkvOz7Scj~gN7>>BI? z>fz2sPD3R^%q*x<18y-55v@7zak$GdX()4Lim9MdRKb5N2gY1uuwlchhOKqVC%|Or z>$47Qmj7=azf1;~&Eiqws6rNV+u=#A&nwJcM+l>3If!oU3Cz#Y!=ug*G88#Ff&^?j zq#Lsbmo84vY)9?g*MARoq7zC9XNc|FrlcttPmmrOkpH?i*>z_+NIJ8n--JiPNg6Sz z-$H1S@mFCadku@Ls>IaQp8$OVZ9~IA%QMcIIPu#EmqIC=k?;tsTB8*WdA zeB*hAzrY^;zZL081t>6luT-dMfTJKB)kg~k#|YiX$=LvI&w5*d6@b7Mn~vd#h*K>W zHMQCt=|TgdxdwM6o`kXTa&k-nN^Mnrm5MUE*FrSh6Nq3Fb3Itz?>|5IEC|RXN&{u3 z=Lx8;sFncx@~i%@)G#GlO@Y{4rwn6=zg5Rgi7_z7kWlniJ!*+VXYUW}Joahx3HQ4r z9xUGP*JkC~|KQJ(!e$wW8w3?9VutvS@n?&k>@xht?%ZMOm+F}g|8O#f9gLTF^|=i% zoD^alx|dPXA5Ow=m;INXKJ!GMaQQvle&;l^?M4AiVn7M6R>HABBmDX>&LO zKG}7jYtr#ZJOT^?%p`7nT#tcdjtplLM4oe&>B*6&RSQs?5C8lb8Xg`V&vSWm6M=<= zC6Uh+z=`7w8K2s$0aXRS5p`rsfB9X_)#`pGq?!{BIrbai?xpuPEiT0RL{V!zey@H1 z1k}=+!tBUhq>Hk!sSx^a7R?J8s-`87VZ+34MA+TRuC7z}x}l5AZFz7IpAV6PH#uN6 zf5JU9sb4VPf;0Vkrl)In;orP`2%)n#5P~nt<-pH~-e%mlPG<#`B>j~#{AR)=q!UklOM4lnXTq@WRSAp&CkzsdfZme%G%m8%cStrueYyq{=?<+Sb`x=G{39;s%f)| zcIBhQK~qqgBgW+EDRjQ)E21-xwb##(<3FYqDhe7R@WEX9$hkIkdZP43hm_u9qQ39zT)6{>cLV`7t8!v1 z@Qg33yM(Cp4mQOFT8EhyKNLe5LVim1qc5Z6S&7MRpaYZ=@%Bz5M$eb1y!-CNKg6Pn z1a!M{;+nuxDT?YE*`)MvU6lo`{$D8cYhSNxI$QT(;coB2=4G2|%8-ZNG9r=eD*~X< z5JK^NE5iQH`t4A79vo)_K!$?QdjD>9YfZB2SfD3?`B5`3EHE?S1FE zs~A^gNX?5>*%t_9dUl-mBz#KQ^5v~Sm4vcb48;5yWBJUQ&O>Tb;0?Oalgi1-hX0(?8?iqUNt8gmVRBu;BzXkK>O_(^0P= z8*H-^!~xUilz>1qys)q^y6v+^YO?I2MNmoF25&!9r!Js7GocQLI_c*6W3hJD6(8t( zslqHmCZ8djMf&TR@po!1uh};dpt(*8VbwilXsm)!N^V&E*kvRu$}l7KF+b547(N?0 zVBkcrVSgX* z+qBN<`;LLG^_sM;6l^@E9wa~GLweBrRW3>OtOCZS#Bq})6DEh?5e< zMp*NZ;j%Dk)95z_=#_k zC~wnQmPUR+p%UfmjE};OThQrbNGTT35A}UR+?`V;Wurto-&ZvLF@}Rf|0UhmN0G*e z>|$kd7++$8W!0l@VdqIyRQLN1?!0kT))L0Z8P)0dw(0NCCb4D1JwL?2LCn(ShC|b= zqK>bLXKyNFde?hA%08c&3}>&Su9p&J-I(s^g=NPW8c$W$n2W2LvnST8wzgK{m43Ee z8XiRKr(@PTsq)vp{-Z*-*ygsJ!X#+2+$;6p0w!jEb=J&JtX-1 ze$(&iDo&3?w@i;{PZk~Crk1*La38EYov{s*^_4=Px=cv_=bu`|;abmr==MlYeBXmD zDWI0m?6YHWC^nvwD(rpL9nFD>fQSJI5C%%*gB${Zs_-ZcAPnXqLX=*gtA;)U6xpRs zYVF;(8b79c>&9zMqYC9SjBf3Gm*^G$q+GNszAGQa=4Rn{V;l^$X4qycDK0>jK9xp1 zn+z&z`rkjjwAIf~_(tobGg^&0l#JAD$D93Cl-(zTr>won4)GuBXyrH$8j&#jC z3l(}rbLmp#LH(ZgAi~+abp`jP*$0frxs6o<_5bwI#^=qB#=+|BfI$E4xQMe`gZh(oEwgDc;uT} zSs15zADanoM-h=K48W&yvW{XL%FD|GGwi?l|A$*Sim{GDqWV2Ct~DU2u5nJKDYtfT6z^Skv@SOBMYZ5* z>+FQ%*K}%b&F4zAn8|QAcTq)^mK;ADrubMlCfO%~flF(iW<>Y#V&O>C$l0nk#EYe;34G`=DzP5CI|sG?7=!cN?m5VBDFfcL513w7 z_8MFd?iwm|WR#zFzT4#AoxuvoRqd(-X1TZspl!rl;=%KJq*@RJEqg`=L6O63T3P4- z<*+OHoRuULp@5$8);3Sxb+>xx!5aePi!fG^-FaUP9@>;p+Yf|9oy)0dl8m>m}&M+hfUis+f$7j0j+!3IMGn^1G|TB?Uc1l8No?QJQUT+f{^GhaJk^gV`GS_1N|3n5hTVZrBnnCdBjt-zyht z#px7u2QeAEPq7hSrAl&yBYr`cesTcibZH3#{6BAUdtUvXZAv#Ac8^u>*6xoNhS8TE4SM08~`hIwSE``AltaSeo zx&&>h$i3yb;*&&oUwsXXK1+2<;S%PE_kh-?Fpj?loNH?m$l_XZ&*qAg7~$E^O%>_m zcpQh|^Rzm?Nj#U0o@{t}pZQ2e^W~yGKU@P(9NC5f>A2EHc5E(dfMoCV6q;Y!zQHw* zP<`;nYV<5QG~L{yr%%$Ibne=>oK5EQob9eSF0a2ZW^PGN%%V)xAgP7YK38+q$t~mR zoSlL)H*OJ6BDV@(2Crf?8?8T|*wv1rbnbb;bq z0Go}lwl?YP?5wthg$6sYSS-M74> z;)ec!zqr&I9cyfO?B=eqxHk4guj^dyxGai0L|^mfT(!D(T6^`C)vTwdR$M|hIqeRn zAMzF=09BbC>xa?U?O&RoMorR492(9>ymqb8-PX&{G5Z`=x&Hjn-Z-?*jXR^L3N)>T zztYkI(Rmm3X`Kskb7@%7^2b*T+DvusFn}yd`(Ol0tnxc1S&h;C&UZp^L{)I7e_-`TGiOW4y+XYw07$5M zO>VkQA~3Ohhmr(V^qX-+d~cth_>K%;g^_U4EWk4%0+k?Jk1|}A#+1UWp997|3cJ~O4mwyCl9Vj+w;|}!`E55cA zvc*1)%}BmN5U?*+z+!s`@8CxmAc&v1$OlNTILDFgT`J->zNaN9@uwX@bq_&5!dpT6e@9`(8cC*VAOzfSLW=MV*>-^~jgGJy6C7Mw6( zVIK=Uwh_m=sAwps`$G4_G(S83>wIZLNrQ>G8*P7#r!>2YiIqv#`e!vTnI*!L7v8%( zv3v8q4Yw(F`!MOtp^q;i^#}1Mi6@C0yn}WJqF|P$6W3p+W?D6)BORM1_!?7TgGlUU z5^;3b+eMsd@k(EMwaRYuJMx+O?!|?uk|vs&rtWsn!^M{MzB}DuYUwG6Z#LZ>P}O-Q zJLsjU6;#xCEgC=J-P&q9rKGN&)+d)r=qenFCAwQyG1lF8P9Eg>qXIXibNwX97a?7C z7Y!9PW`Y6-FMw&8=23x$tFv=;J#mDE7B5CB&55Vz5~7MorF(?C)^1TzQLLTiWHFT4 zL}5pvMxDMIc8C~73jZ4=C8{DhI$`5M^L1YAAD1)i@D&mTU%%CshRI%LJbQK;>0o*c_S0<=megq z3-?Dj7}xnE-wF1-72n0WqxGGYMI&Y*wR$Me`x&b4cTN&4nw_A?+W}sgfO?oBUKYGG zRje1Nd+h`H_|5ZZOo%oJwrpfO{+^592Sqj^oV<{wxd0ne8x4(RCOS-Njw|7KA|#`x z&;s27yTpS5rC43tD!Tky2+eJd^g42DU)6jwrxupfG`YF+EtA_U`Hx1 z`LsbmFV)9(Z}7zgcwl(i4BiO#EYu5pCB$2&V1kLE@ff)$R&@Kao#fHl+FI!Y#OPmF zg*c?PgKUx(_dfQRZ+T_Kpwk`W*3!xf4H(oju299s!D$7G#KgqJ%mEswL|nEaaHTu; z++1M@^A|@)ErCyIhjL^|fDz;FRHulJru=*Yz0_eo` zTdi2#tNS3Y*%6I0Ag*+VwG~@0Hpg1&txfUoaP=0mv^~2&>Xz1UHPybq(sv7`(z=Ev z2pwzA9m**u#IM{!`^>#W}i40Kb)Xgeli z@PK#&s;csmK4WD!UJ_d(_qPV#q_i=cjb6WN+ZqQQ-btr*tKL0IhHSs6b0JT6{1AV` z;!jXV>)C=Q=b;N~RAD6P{W0eLyKQ>7AEnVS&vuXa>bcnL#VmP0`c>Xw z=q}3;at{=+ThPD9u zM-v~4v;w|hdZ6YG_)9e+-n!?y<18oPnU4S3f4~R14f~S#bHLm{V!xbe!QTFeHu%Cg zbbob=g^sRxpqy87ru=v9Zxx+wdvzh%x)@=)>A3H{E17YUDISdw*icCykwm z<1L=ad47ibo-Ga}J4)Cz{wu8dGM_x44{(QIXy;QqHelk8&Zdto7DDt%2j(Wj^ZqU% z4AnO$3wKJi!dSsSNgpX?QZA0ugS8NkxtW`v9KCXkDqLymn4_eJ4H>30v@J7J2bWPW zUZ4>q%-2uNsTq9DLS^N|%f~0DrNtoWUw$L*c6U`ZsjwPa{Sl$M4z@Y#yh*uh_hCr) zUssZ%vNA3(@A5#IQ6*a36yUivUO<44kI$&zjUEq}MbIA5FX-95<5+Mj>zicg44MW^ z@k6J|^Ua&^zC#isqL2lT8x$En@zml{RJbInKH{`ohQ27F`{hqi_AiW#j7G;RHA*dK zK6-f|?+c*8U1;h2&}#O-kQTe2Wc+x(8FE=IA{EaB|Ks|qwUQlX;r7IRw+IvFpgCg@ zO(-SJNk`S21KE|oLsH8q3G;Lze(q`l#8@p$zF*6QI`80mxYfHrx?@`Nu)(r3U@vZv zYoM_7+!u}W9I08kshoXJg)`4N&r>+hBn`URoR(`n?yN^lM~MyUeF&f_(lL}>as4G# zZ;kaufngy?mJe($^0wQNyVK`tnx!bfJau3}>@zNec8s2vQ) zQ}poVD|vFIO{L#OYtC(}V`5%^=jOUX3w=c3!J%2>fa_hKm}>EaKfg$DzokI=XlY|| z`qrw22#`$rj_|JX1*&_HCw~(%-Z+txFV6-;$EvkK200Av-4$VshBSw)$mjqrG7$yt ztkEJ0?s|BrmS?Y^P66H!cZ+}{AtlPGzf4M?Rg9(3CvF@KaqZ4kYEG4&h{k~GatTP_FJr@%PXeH=zsTiwCJz82j3bL2Q3m4Su^5y1Z`sEy8FUSFqI zS1Vg+@B_Q*(a#Q{oFvin>Lv#=Tt0x^Vf$QX%F|O+UfFeYl?!)xEO@qGvgBC1H###J zm(k+IwM(3h`5tCI*Ejns)V9+vx{KdrJF4#IyoK=&ivn@|RWjPN)hY=jo2GrwZ|MVn z%~t<@dPe7;KYK>X#ie2)=lWy31%hAk5R<15$ZUKn&eRDQ!i%VLva$ng5UeLj7PA3G zg@JZc->d+%oMpNWQi>qctN837H1+6OUcCbvF9`QNuGB6`da#1?6>Ztbfwa+1zU6-` zl=w5|v#R#yyS!f=?Er3;2m{Xn!afXxb%o%dN6Z{yh|SE|IbFZK7DT{g{qN+`;!d8o~^_|v^_wLG0Tb;YO$iCIE*Od zD@(RsPcwS;iv{eEj<3pP>_kR)-`@mHcQPW!@e-9;;(1YP5or%oxb9S4vdIz&H>E_~ zcf=Cdy;&ItIW=5zd0Z~h)-%4I6aW3CKim`fHGK#9)S*QgyiGwYJvcSL8+9=;H#Z-Z ze)yK#_JLK}Tj`?8&w9F2mSzg3hFf z8zQ-cldOuN=F`D-8sz+F5-sh{?r1UVJ?BE-cz>GU&DG|Ux=@EKSryyn(5xVJuz{!? zOwDyl>v6?K^qkUx?v`nHfB=0ZF2sT4HbAPPith;;nz)Ng4IR;Zs>|hVjfiv1LF?y@ zd*3y@q{ZalUH`*9!oQ;}xs6?TJ0HYkFEYmQiPo_htBOu%OjB3JVL{ zy%I*q1r4xpYy#1mxPifQKnWropx20s!oJe?3L)U=aaSVH(gG+NL3steIdWzXOIZ6F zSK1WrZhiE+hB`dRt-o7Z#mQ7#AaN*1JpAn!xwrZ#xDy*V>5Ar~`irsB^e{J1H8RlG z^GBaPFTUdvYzpFsI#l?U*k8o*pWb^e7Lyv?q>X*-ERGPM3+6wpohvSJj)D6v?~RBgpk^Ytmi8{>AZI8!0yur;wI*M5ehqN~bgT{q&Re!E*F3aSXGPK9hk8RcT=Sc8DK7!(@Rsm?Y7CRU# z7Gc$oK%6@#82dV5mgki5B~7ju`Rr0n#8lMt{JW4PZ72se*yC`-46H< zx%MDepS}{jU7dNeO-vbvVQ{?qJ&wzc5_mU$W`#9yK$2{2XV-Rlw6e6d^{KB<%7stZ z*0wZ%>v*c~+D=NZ$MILfw4In{f`|ywPfDy;8wZY(y$-V9dxt!}la}Hw4hpd=um@Za z#*|uPdzcCHePa)zTx5=ph!We|rsqM#Ul-^*Vq(5tLi}~E9hj^w48Go<=A$Ggp?vM{w9s_a7BXj}-|>w1)NA@bb|Yy3h$2f2dSm2uwV+{OB2rSqii;WJ z-)W)aUAw!xuT4J0I>9%Z8f}aF1PBBn^t(xkIvb0Vyp`GYu%Y{!#WcL$pFd;5K7QN+ zR7U~)CbM1B(5Mk3u0EwF#-e8hR#Ay_ppaV09>>tZmG_@fV-Shq!`8O`83879k!3nD zTu$Xlw&vC*2_zD5^Iyf>$u(q~ z;&iSjw!GuFb{Z1a%Q%hiiKw%pP_*P7*$0H(OT3kNy``d18FVoB1I~qAt~V|tcG&-{ z{c+P{G+UXO1pzckHG8Y8&sMY^igqlgXn4%9ss)PsAPbC15_I$rU#uGO2DsInd1l&% zv!N2MUvMVupf9g^Gio{IYn{;xyU!N8URZLT5qf<#rFhYYnmclxUc#%^Nf5MqUsF>< zO-Co9q7wgJREguSFt8k(1#r}c4+J3TG2CM79^5GdQ8faWOJT*v!jD*fVPJprc@DPZ zcJ~n!;sEX!%(BVD&7F*SPwov7rSt?ccKuZWk6TUve5b>T51@93D$JDdQW>B}M4KA} z(l8(ZZMoIJ;lXSceBT+HHR@)l*xG%4@KxW4Cyqr@O-c&{^x>yRAI08L^R*F~1d`#C3@q3uv%dbS_yrWM)Z-e?&K z`-ob+L@EfWmH7EW{`>i^c|Lj6dormk|J4zpBDe4wbHUt| zIL~bKKXLibr{FI7{|I}_xG2}IZ24Srq*1!N zJBAqIIdSj%xi9y=p7-SgzZt&FFms;kSnFS_K8HdKV&_;Va;G&XV!=pzo=jOATo&#t zbJQzJWpmO|LB{Dp>mlz+F5Y1;yOc?SD{$v?R(EbW%~m6wF$LnhCg)EVApi56Kig5; z{P}Jm)1zf!juA8F4&7lNYvB@29J7{lld6(~!Q02dq;@6J2PLMLJptVLWijt`_EP(r?a4#Gi8hgN z%wRA#?(!EYhH^b>*u-q&pTH*Sr)aIzAE!QxP|`Tf-V<_zNIVp&jK%;z2Tof^a- z%G^D>Xx{5${e(h0p#C2$M^BiH`J`K{Idb$FNn$3p{@9m6anMEYMbpj%ui z1IVDXifSGJ&J~yzxjCHJx zGop=6HT!schuUV?b%hYWy^5TALTM=*pbZ+ISg({L+`90(3*VUA8+#nsmTw1skh1g% z0NTn4^P?|*N^N?Bv99#|P!Z*Vw^oIi{Lh!eC&|T()XA(kYm8N#1Y+=aad-^4u2JbJ zl(o?xyLg8dlbmgdFyd0(323OCjt0 z?R_Pi#rUW*8sxJ58N{s7+tEoM(8Rtv$R~gE1?;)uTNB}ry!%x#m^(2a%J@1P?R&o9 zgZHF|7!HMDXa(&u#u~h$Tf~sA5UyRELc$x%4U?d$ud9vf6EydEprdZv=4G9@7&+|= zO3CEKmFcG~(c2o;axDm9smGk@^$aLOEG6QTEGQhep;`8;#HM!>i<=)hci9!MfUVy$ z#+l}9CuB;l>Qy!%z$=AtAl60JRn$}yjnt(*JSczGA? zvT=&4S2Fa7b-`hj5SM7?sZV;z7JyVddGcgweLWbk4P0Jb0cvuYgtN2v7^HkS;^N}H zgM(c!hJ|Q)VV+ey<& zOHE5t(w=qsUT%wraxI$SEAe$9ud?1M5H>GM!_cd13-_6>r90iKdNkz8{RvkII%0*- zB`Uf1Cf(k2C90>3U1vcc79k(?WAYkW?$%~Fe)vERR!%g5L1G&|H_kAj186egVl_EK zMoZxSii?Rs6We?D!lPPV-}WEoY)H#PJ?6%lvE-fv!U1%m(`Lf@Cu&7kJ`|*=7?K%V z*>A`9IIc)s3E2G{ia$pdA!$n!H^VhOn{iq)+bx4ntILl@=N?PySziXsk6Dp{Z_ zJ?ENO^1<>+Z1~#!)T=X^ku*2X3p8txLr=?xfyA1aaZH8_Tyo ztI{ia=2qO6oh5|@!EvG1?P6bL-JdI=l~-1wIVf~y95kcA=cXJ%?`MrM*Ao4Y$>}fm z<%(v0t$Ycz?`f`e31wZS6M~f!ODz^*z%Yc_Eyd`C-cM_sTa$liMo)3sOcN*>fcNgf zmhuZE=a*AJR2)u(_5adnD(u>-@Q{kCL!rVleW~8vSN#gaz4>Fw=N(zdqTepgQycXD zo#>aUbT6Bn2}&L@x97Qvbfhy<8XQS=!W!Eqs1P9s3~Iy16(~@qfV{!>F*LHD5Kr<& zvtCvv6@vH8@so{>EN6>F9U|3@&#fIGk6@70*h4MmDo)e7tl@YOwEW?AUeQB!PoR3U zpS`=cj-<}pMq5o=1RX~TQ!0l)UmP_-^x@&bCIM9vr~GzIOx0 z(W4^=DOuV6UC<`}1zm~w9^M5Z1w|~t1{sZHiaTjHu^Khe3wxY>h$QaB!|1f8vT{5G zoPj6j(ZoFD>ADS6My+U*aoEnAznA1!xqSpIx=^%cPp z)6mdx@IqHpb2_i>R?cx&%DjM4reErooV;VaxCZ|*wt8#4FQMmHdO{QdIOo;=ha-IKb zOiXW}kr=lCVTb2`M{RJw)E4Lj>78S{mIf>>AB}l!rYI3_Yi*{fHwpZ=C6p!%xd?ZZ zK6)dC>@dE=PydkHX5rVur+)xKN9nvV!a6?l(`|J5QA1Ci@4GpamS0%->6H69xvPtd zn1=_}*|nC}`8Zo&b;Q8^dPQknokaZ*!uqv*uVZ$YcTElPRS<&Xu&w*y3USJTE;Av{ z%u35FaUg7a4`Vh?HOr2Pv|ZLXO3gO4?U4)5&c<{0WDRp75!D z8v1z_BRa)OmzmuX&Vw)cLtN9!no)3+shbNl&~3j^x3|Di#^fiN+e(`2v4!%l0Jtm! zBI`+m!JUczAp*^-VUvLGpA-LOzIlKLX4F(wKMzbS#xv-d98&PwrD9lsh}NXZ0MH+C zMq157U0pr-$HK2)DkvSX#N4mVwm|U5dU|>qH8#m}Y)D9a21iR4&$>}5JBv|n+ilow zt0*MM9^+*9OC}k^uSgJ&&ekfY(=jl-=I_SxzP=PIERM5{BU+rCtiAF=M8)b1!=+(= zzoq!@9UmoonIJQP`uYq?N0+q8K1D&)tAHPC0ea2XZG$XQ^|EwpYe_g{X_*7U%4T<< zWT-User?SpIahy-+CkrB-_-#p53mw2!9SE!zN2wGx_MGf-KgcKu9~z91YxYPBsp2 z1)Wi-t1N(i^@PRsuxa^u8Df@y`$BSOfv;{L22xm|w$N!t#q z-7kmJkxdT0XF(7td3a&@A2y4f9W9^7k*w91#fWh5Ul54Pt8nCp5>#(%m+wg+3{^6& z{X!E8#QV%--*rTJ$)Kv#M!ueH*I5To&c0sMR_Q7n1{wBze1CaCcX|2gU6sbEgCncw z5VuCX0@3tyl+}PVcCZ7sg*CQuzxuaDFJvgQFNuPP5IXjaCsPD7IU%2S$v}a=5*vXs zUxx;M+tm2ZU0g8RGQ~@ywLa4{>sYhprFeiEpjQ)A2!$71h5$L!NeY(^IFr8+XMv= zjx+j7dT=CvtXnh&ilZ+|eW~SL-my_CAH;&!^klJxib$^|y<(x+*4Nor4xF}U&B)SI z#hv0wu{U049-1@rb>f|>uG1H&3ky|NM$xBFuKf+*`8d8M$7f)Emfn`OAP+nP^U~ln zuRBQ=<;lUW+KG&;NSvT#`(}SfU8{2Q(GEA;)gP4LZ%NZ`>)X#R8JrK@T?zDNiw+b! zg-=-132oX#&bbNs`w#^e-Eiz{o1%$+4_4-+t|wkk`>yVM`mX$5&Ry;NN}4N1&|Y*y zLI=mLG|Qrh)tYl0c-!U($kdm-Iz2ih;&AwR*w#K>YFxM_w0o5~Q2#FZ1$v>K@8f%- zITUB8%7&W_Toeg!HV?xi@>%^JM09ArAUrl3_Ph9M9mb`g$R zdnBTreDt`>sV4*b>L$&g>S0D)1?IaKDKxtFCRkbT&Xe$?n z7_9n#R3mpV1}MX4QDNADv7d_fIMmmS4x#5$;HGoc_X79y7(_yFO7QZn;reA3stpa_ zZt?V6x?YzxfZ-PFo(c)ad)SSpe5Ly~{d)9vs|wEuK4^^|Wx=LUh+73ilm!h(%j_P_V4${*sp zZvNQyu!3KJjAM@{HZ0_@Y|J%d2%f@0I;D^pE-Ia`egLF;-|FE?hpS$zj-$TQojN-w zVZLw^USXHtd}RD&A;Qd(qnqO~iJMUjIMoeP&udq==|VkjQU7IU&LK+|hyoHN_<1!v zEPwTwh!2a#NC5?kUNa;T_OglS7YZz2m@Zi71sN}$3>PZ!cXIJ9UPIzMsf_CZl1bKE z_Tw7OB=-(9>wkr$0C+!7bBi{Dr`sUDlEO&d2LejHGza$&FkixtN(^0T(`y%;d{w5isSx-k0m#GnbF_ zZhIIt5?}v+2@U`tPrmhCWP6qV(Z2bcGK*1a=IgB&UX7JFGNy^vZus(#4i5zoXr$mE zxuo0HiALe15PWN_a8ZKyXv9JohH{bDT)2dshHw&dwx1!i73HQGz=pj)CWD73?;ST{ zeBeG^zisW^diH?Z5Wg9CfN;QUy0$h4?vxFVhw^6H!ifb1L-h!>e^n1QzWv)nyEVKw z?1DpKY3Ssgv$Ny!KOU**dtvj2m>E6*E1J8H?gUxBY3sMbc!Q~}uMpj!g@tM>YZ<6dIb-)TBf3&weOdR005`MrN#(>^WP< zN0F}^tnk&IW@T20k%{jo|3)!}69#WqER*UoW=i=wgZbd|j7-v=OqHUgNBGBSjpf-l z?;ybZDc_QiKC<06wE3Oaql=M7*ZwhtO2S;~V4-=?|8~VS67q7@zE8%gztyLhsr`v8 zWuF|E%`%=F=cMmOgXyIb6133vpKp%3!L1Q!1Y>d<%XrNxYDgDotx=%*&0Nt@2j5&6 zox0z3dcx-w;TNgFzI4uW;fUwA`e#h!3#-TZsBn~_E0)_oEopD0qt1?87sU9rInYL` zWG3HLheqk#F{zO};pCshq(c_}`oGYWxM_X#v7i1;xdPut4KP0XHf^&lb+|6HM#c_y z4>TUC^<^BNX}>vI`KoAP{i19o(B2SJv1r^&*H`S=pKB!}ydk_$K z4hb>4S-=SaK-ylQ@D4d}9Y-4MMug$k8obt5sLlzV(VFUs=^i8c#bIiIro-)5&iB-M zB2Tgu>z^^>)Y(iuOjA$AIToxUOL&L@UUoY+!5KsPNXlaISrmz=JVSWcF(KH9=`hjS}WHf^>vqhE|m~o0ku^lA)G~@t*xiOb}4DWX5QYe>@P(6 zKX0P<(n&kSirR*X+V88&lR20wjtwGGexJACA)V^KNExrExex&EwL(OZY;G9m*uGxy zOAfrv5l3qLliIkO8&eL#Li3xp2nj5dN4ZVeA;|=n1$Gai z$hzWFvd^GH<+a9Ci6~E+8&UaajNh75tzuSVIvhK-hTlGaS;zn6^A)#K#;4F` zoev|`wZjasf;YhOlR8qWV;}Z+B7VpWSV>jhz%BQ4Fgwveg{`?g zQ{Zg>X@RL?$aG>i`*TabOv z##Ptl%^7Ds%SHi9X=r%~e9QrqGYn#xfz}O@U!)@dp;22vwgvj+-}Sqv97yLg7JS;o zpQNnm^5)WwwLt$?+vVmsEO#-ZIW@;o>1li|g8f_k^^j9(^}WOFV3NP>o3&^ZAvq$2 zF29R!HAW-jnC_^G!z8zO8FvEZc_R1ac|N(>L!l|{s!K2F*kTdx4x4=5P0Yer^mv(gYg*vX_Y}oU!>~ zBn3@iJ2w6T&Mo&f&Z249|0c=+1>6$3A5LjWFRP$`Kpz6o&}Y|;>K?opSIeS3WCzT#fdvJOz^px; zk(wF>u$(JEQ18}@GLTh&6tKL*2CP$SH~)a8b)M}$lKfmh?g)UP70{Ct2^kp_0ApP% zf1g(~G-vNTtD6-~^nC%4!*%>#KVuc%cAJLy`}_H$m&|Y8^}WS-_jH|#uSS&F?8RAb zutimpVNQ8)ni}dGs1Fd{)4SxAGl~W{Q~`OE&0-5#v&`F&PoarIE#>97@VFdkd!r?^_u4qorOB8fNVa`Jlh>M1ipWD`hM))OD3&bTTOm!|tw z$GKQYe!zJxjNISf|J$4_7|gA#to#MUDs(#VqR&mcersttl%l)I{q#dhO5}$RIO|Qp zBUaTKbq-Vu?we#q`Veve(m82*&q*Jz4M}Q~>9}!QG#|0Pnr&^Wx8ck5y)C>OKPomHrpdwC^LqzN%( zz=h6$8eehZ>guWj;QO-Cjd^(Uwa4PzJv_2oTJ-+iQ$Xp343jXncqb;anR(Go>0;VO z$H{_|QBB!favLy!$fW$@;?Kz!(gqN;7*N}d3+urNp|LN@{AfwU{V@UVUPKP6UWSLh<$WH8D5O$<9Uq0NgluD3I;cSM6?maWL;> z=!bR*YP&ab6bEeJI_#8B{Ixa=H^;+98@u-*wagp$h z+l>57DP`;n(9&MHMFs`=RLILOusn!k8rUCBXlXLd|L5_F-4vi}s+*7_JJkv|HDmdq zo&}rA(Z>P+L2W%jEQ}`whKEHDC#@#rX**jxV!AkM{v^q$h5z2<)C|3G)l2ORL~K)i zX*=$0S>&9CDsn*Xc|t0ZW!L+fRqAC^#!pnjU1Ed7ub+D;=9TRxQC6eA^s)*6dGR-4{-59FUysS+zL$s- zh$9Vee$z&r+dY#>!Z3^9RL$9w;$|kW&WNndnX|Vn>-DKr<~^TOB~ns-M|UxqppEw> zq9#c;>N{)kr_+ZG=%lm2i7et+1e}}oR!kU!-q$Mv^(;dS!|Imv1d)$BYqqQf4$iFO zH`QXEUObN=q`6+#$kmSm^+fE}5l_##s9PAz6x0IuIJ-0C-}ZruC)Ms8QV#deMECx} zF`#MED>R2j2L|RQ-uL+FI$x~!J#8LsK$+SLW;5D-O|XH;hR_#^d<53EyjBRGAAb|;O<3GP*50~n8!^c?lLK3#e=A`}xx^i3Kkd}#q@<-AK_e||Xj#?kq6tnO=vGLJl_?G%S`)#y)7z0(>i>o{2Xt`f;!goh|@NAH!%)%{-r61ET(3_Gti%%+QS0SG+>Yio}2 z_`k#{zu%2-CV>Bd`wKEF;DE27eRRcm%Eu(s=5TO26kycANMKrGpnXe|69d9x)^4_zCq0yGt4#Y}CF#1AwzZW6zh9eq+bI;Ojiq|=`dqc)AzKXeQ$$7+z0uRHcN zqaNxADxyg5XpV)%be)h!9?z^|uT1CeumeREKrs#z?vhSSkOD}@Vw{hmT}SSL>{cIh zW=4Ik&ar};PbMR~XHos{tjy__IayIuHo7P|75BF?Q=c?YA7}X_ef7%Ar+P6yCwK;;*FwRK|uT086{~xdm5CpYDpc~C4_FzOI4t!(=Rw)~` z7%yg`aqW??$yX(j=w|#%KwlmBLa0bMv3pwvBWkSu>%hfNb0RA`;BHqH+YQX`WJvND zCLKsNW~n@ABFZuLme*``{m9~FB)hsnR4E^m!Gnz0Q06m$ay7IB}f znQ2DZpy7xvx432f{VQP817_P1n_c&D%IqPQtx(gV_TO^ZRhGZh?C!Ni!%HGh=gssH)vGP%?jK>@pQX%L zN&aPrDl;EtZmLn*SDC-sQGR=n5Ug4&8hjrXlUIJoXw2JB1(g1Wnkc}(@xFtiCltFo z%j4GAZ7ooz`V)YB|0Kcy;c(AmT|SfV87!BB{7}eUgaIQio07H~)#N~H=hg(mRdnzC z*>kl#?&9`eR5oW^QIQtHTafDd*&Ki$1eE;!KQ-$Vb^@1=TSxErI@(sPHUUwd;ZjcA zQU72oc1A*5wu?S9?py}f5^2_0&(AU^%g-~H!gX2qO%_P+%nVoCCEgV_`v&Dr<}HPi zU9w2;+XRD29kz1bnXDD2kwx@YP=ux*fP3|lLl9wdWjZ^k1*$tYe2bnlJ`0|Ib{yGn z)^Yi91k4p$yHU&}G51pElrCpqBVne506Lhdom2y3Yo-d9{yTsT>0Jfd-l$N1k288; zwaL=vChA`lyUlD3=EFb&NO$An_TUCw&w!mF;`-WSeT)a_ zc>&HmFftN-XQwEfri%lJ#(cQ&ZRKo-(QRULiZin5Vm=z%CAD0dvWM56pJX zW!Bc={rmXMC*=abq7)l)nroy{x&zbozR!e0e8hm*Hou@CxXs|*&}ybmC9<8J{D?(o z^)waV6lk{goA|fNPsYN+y12wUrKAutfWLK$0=5l$oNYy_Oc3CA`_} zrAXH+?|}tzJv(!9#-Hmw&n1)QvKK#hBhMR=`p@C@^648u+I_-AZ@9pG4Oc%AVZl4x z-!=GsL#uBL!IuxFdu*xT+Vd=#b9LPW(%0s1AA)h>ICwMR@+4on%)r z%~b=MNIr)kX&N_YZpqGlK_T$|CCYT9*d371+CO8!-h21u3o%g`Ygp@haipBdiHSbH zvxg(M16vfBO$6!aWXWj=P{UTc%ClJzuB35$!T=J8=OKqRy_TU&cVO{77RR@wH%QkP z+rMOEKvzAE~^2ptEr(ST6D57ljeudO2p@NCwz5U_^XjwYt3(;%Kfu6IC0M{EIS z(t=EdaH983+R&#Ub?RrG*d#oAZ7W?&pFR1hdLmc5yo_RYb_Cp`G;SylBeXB-zD-_Z3xx5OSlX&tn}I>5_j%1R zVa*(*y3N%itq3ZXBFZg%{?xmRZUuQ!M^-8p+)SQKt6GlG-3E4IU+l969we%kn31q9 zR!o$4 zoo-JWai}eKcIWVw^*ihsMT_}9o5y<`=DC=E6Tg5HGj(7$V#Qn*4>CGbpYCnm%TVPu zzH?9i>9C|eAVh89UPbS{b{#gR)Se%Kv-)Qm^HoREIs1x#;;Y&6ZIhGgC^xlFqup!} zMyI(BU`W%Nbcl*JIvpeXF^RaRTeDjn7noAF`?j5Pjx-1esbjeNBX`^{S>USTR*$5V z1zY5S^PNfVPg4#At?vS4c_TOd(w1nd6fCW=f+kfT9>U^09Mk?-g~0W^X`$nZJFBXlz}Hre3^jQWs- z$?Va3Dia;jZh5fvt-qE$dDy)(MW<{;tIuebfApG^JC2oj*>YS{` ztkAna#Mn*-JNB`OS0xrqN|wo3@=0k&YwMR!#v!5+7kZwAzpnWWHm`3-axi|#l8yLk zP)K2>hH*3pE`f*x|1t>T8GET2cKGlETLMRsIZ{Z*im_T<3G;@N!m@4w2c;KAgC}v^ zRe!C9cfJf6B~sSKl46}Ic}Gm3JG+$*EMIZ$gG=B*ue zaAWZ!X%gk~^R$T6(RieRoO<>9ZzpNnfN^V!*3py-85a_ntAw4@298RJPk-%E=Jo3McUD8 z*6T0#`z5EEcaX5`2W8VwzPQT(i((6jf&~jwKrI@J6d*TxX_e2h!uN8r6;5x>YLI=( z4;)SuOANK27g1>Qo;9^m*n#V(uIz}FCp3qBncrYXXOLMbpIKa$vi;dxk8T4X$nut5 zYy%_B_2N%ND67`{-ObSUj`gF+qYp4|iTS1ZK{-2XGMnYSbvTec>ZPnl>-gj&01RAf{@d^w6_g6%*uN7*bzW6VAt(5 zBgpdU(AWD>1=(6bov^kxRrE!6*UO6|sqJG%DO!{)?Epw>Kkpo(osYbeymlH(12&eF zl38$*kK-L{bCaUefXCa*Ofh$|=bEY~I`S(XZ+6#(!&bdJ=GU7AnKnVQcX85%t=jNDT$Nk zv3$4AO@+&%Wn1lgQ%jt$H~wF_38;-vf6%d}sq#_;c_4mnJXLaP0mG@k_9nve`Vtao zNgMX2EIu&}qot-&Z9klL2pe8tUDm{&*u}0e@YSuK_Ul5&qhB=i%61YY8~$oO1*`$c zAyHgK_f`1gM$O?}0e!{D6LdCJUUD8DR3qZ<_cavV{>>;HZ!6Z+mRn=p*;{cJaJ8(> z-;7^PT^+#h&E}FD7fB9L9f#(!yzlb@u{=j-+B{TzL;P53vAl}FJNqm3s?KiMJ*CK~ z&q(%TREUs&z+4_^Bw(kR&cOfz?{FNDQCi)YJ0oeSabd^fG;Yk?^G1=9KxvDMWq}$G zW5pDFB&Jx^%-sQLkIzXx%+bOB{ttFFyOLv^yO;WF@o)nCp)}Fc3R}yvRulIA)_Z`s z(Uc`6Y$+?EuGrQUJPPSXU^q|`GKzplF6fjpi$ZPONR>2$ut zmZ=7Xg-}klxfH%yi$*uWzSHp2$KN2VMm`+1#c47NpXyvWYHHd?cC3G&v$8Cel4Q4ZBAe+FYsh^+m>VqEI=_W0j34u@9ssrp*1F zL+2!MT2?h?_Yek@lAcM!QHA84FoIMG_LYY4FsE^v^TymM<$P$ZGk`A9v#}-SN}`|1 z{uIs{`MTF}O)*qkp%Lh}eLDitMpj-JlCsnGjbD}IF#RZ6;JV+|%`N9XtnDOu?+zT0 z;!AG|$3&PC9XVbS!;xNZ*}yMD!%|5?(|g;ygM+`Bw1|H8z=~_WO$&{t2tGs$6##f)MQ{-v71drU;q4c z`DdT?g3HidOZwo|;$gzfN%JK2Nt@4>`;e$VOYf~6NO|m=r|uSPin*7f+wK3V8&wkF#*;7J}eDC<2XiuW8)VEUxMilYhJJ(sx>i12&@>pHJR*8ji$ z&$xc-2e>W&^uQETj_$G5N+R|&){+#W;n^m?W{h4ShT#QU>{DEhZ`G zHpo@8gQ80veRI#mSc{XQ55r8EG@+`kgD>&d9o?(}B1$dj0o5LB;GghcK7%u)*N%;I zF>>!L+s>xyV0c=c84)JEw**ZctAcM|*w6 zWuz_cTY$KA=030eG7sqj>%LUGj~txwE!Vv6+IIwHYYRTKRkL4mRPyPMMCB!nH z&dYV#3)^75(*9Aiya0nt=CWDsWfg~aeTKt-J4nwUz}?Yon`oHiG0Prg@wyDwXgc+A zl8fTjj`RWIL06GstX%$w1z0w=5%9H_`qDG zB)Uo;^g>>JqW$5hhpD?>hgPc5c|qz27ixDxSk5v;)g7Tl3M_?XIw@GsMqKV}dGc;U zdzC~AdYe7)7~hP(hjEf+h6RSiAuE^6y_%i$27i>mIbt8Nu+n6n>sylkT#63;2ep|d zg|qNoE2~H?`X2=!XIJ=?BCo!bK!ksC6@Pq?HD}AqZz5$J8P>Ur;TSN;%6O=hwcu_8 zp)DaS0Vw*BhRY>=2@*gi!dDXZPW|bLZ^jo&qn7J4#-w=)G5+5;NVHq-P#TlU@39R_ zoA`ac2(0Zj_?0coO&CCb3M z*UZ+3FABF12CSw)2(X=9d-0Qb1cYb~mVW69+ZYbVI8&(f5vjt`(NXx1X#jY*S+lyu zI!0_2r;@-l3&8&mT<%z6rods@-U|Sd2Z&{WH0W#TdyP8}XS4VL0|c@@sh{Y6N}z@4 zUGYL86+8#v^`^L+1ZUR?KP0waS0uap#&&x*N)@~kNO_>R{NKLZqT5|toBx~NWYFKe)3H|CQo&o8il=8*5UStaq-xnc)#f=gQjuHJmkDHS?5P<@}!f*D<_%LHK zCGwblbp3sT@Z}Eo31I&ZGo75nR@uy zYQFy9m-3fjxkz*+TkkKkuND?wrjo%AzgVePXg*Lo)U~=jcT!sDw+?B@I%hxLQQ3U- z`)qTtT<5kIH22k4Q0~buo_OfyA-Va{OxFvuG&gr5TkGBlVz54D8=d^746DlRX3_QQ zp}g&LwUlq1R2PlHFQU6f@Qur{Zo0};^2 zckPT9;^N^20-WyHKKJ~fc+=7X8=U;I1K!18Pn!JP{Pb;2uF`BzyM3|*aKVSMfR^M3eHEW-oRbp4v%+I$rS9zueqSc@;ckpPV z$#KnBH~zPNGz}Myh_7Q;6-iK_wd&6o4`g3kAs0m3f~0htX`k-;D*K2OytVi;Zd4@E zR)eT9sbv7kylHDX-OZt==WhKOay&Oq^0VyV@xUyR&XlKp>u6VFxwke4n{=ouK=vLr(R zi1GO>^#^@?$EdB@DoZ>dW5?9NSH+;A_hvEvR)2tDh_~qgUn%I4t zzqzz6D-c=OOZ!YG{U29|uq>R%P72VkRFmN>5(}nLlAU672YBMmm$p3!t z-(rCG+&lk&%9hN6g2ysBxKJpRJ^Afai??9N;uQ{p=UI1!xp{v*3KnS?AYNIy-VFt| z2qBc08=_%BfyB8`gK~|f?QLLplrleHn<6+kI4DDc+K51W4nr!_t#=|L*WH2rZH`N= z@B?Xr>dC`+Y|Up+(%mvGJe^8LD+ymf)9(^4?5y1rj=A z$OK&|IXRVMw&xppfn*ibb*;crz%%czd%8KCIGOyHt=*_Eo}q%}K(g}@nXm``^XJcx zPES8gYU%2-z#cz-yjJ&Sd?FcU3&TF~6uA#l19%$@lwHR7p}hY|#d@%xutrVW=w7`h zOSv=__nHR%qbdQt9SxcSAuZx{^m#RX|DeQlxUs`~u&m*R_>=`#*}Fs_PeL4JHD%C@ z$c8Oo8d!a5I6Af5dVQ#93H9fO$LHrVq=IJAOsp*9IRynM>+9eX zH(Vq(g!Sfz9-fRv9ZjzZXVZges$m+ax|-TbXE@%=SFhsWZ-LtM+4(5}K_6lI-k#07 zckc`UH`&PU`4JSFVB9%1-{{)E+I3?T=f`LFD^HFyQ~xZI&jR-=8v!a>OiT=Cn7)qW z%a=fg6KJ)$scDTG$&o@J4GR!VIRK+K5O^STpd8NMc?%$xz|a4~4llK@>K#o^tSxvM z3>BNyyB&F6z_#}uTH$hv8Q*qB?WT*bt*y-mP~UzR+1b>W!O~PtBQL?Uy>RYXd3kz7 zh2j<#a34Re#2Z&1or3|IB~u5E^0k3M=77iI$<3yK`Y(4N-P6STmmKf%g6CluV0JNK zsW^zFLk)uhdooPb?ttWuy!z7b>D<-{17mCf*Iho2seF1>DH}LFyvG+8iQwUMVbhW3 zIvz(mrARvTFdy6x6o9b?@qU(MHc0$#cyn{=A2-W?k@bPO5>x6Sc}-IM2X(2tugwl> zEo|1^S-G7dXiXRA=gm8u7qbIC^fesrDb2s-sM|oo+VlT$fBbbVwY3@?4N(dS>0GVm z{1^3fOy>Rh3q{rV(50!nvZO)Ik(N=Tkmzm#7cDa8Y1s1WDh=YabY^p}8e70Yt^H!m zva1LZuv7KOxAb0j=y}Bg5PphRnUUn*Rq9QgIJanAD?Bl=kAF_M? z%TKj2Ad)IeB2kP76VhQF$mm_`aS>uxlrRp-dV4ox?0}?A8bO-tyE{7o*%q2@yv^6- zohE>1vf*h63o&uK^62xpsJZ3L5xwQG!9%$c&d4zS21t=m0+oPRuZH)J;;Y?Ak%8CM z<*PhdPZAJ0e#v&+6Gi`LV+K4U^VfI7j{+(U?#LF8Q&<7@C}t;xdx zR)|;+?)=^0mUO(PnPTRM;%k6 z$Lz$rI7CE2;(^(Q*1IvStzvbJjs3^|x3X7tw&|p+r_) z2O!1ltaO@^-7Pu)8SkK^HR&oVxKqz*g-w3m#VOw7#jjzYl3!TkLE)`ezI zKo7UPzaI_Q-@fMN{y1)QJxp*8I|bB&V&qH&kHVx;v-LYADTF=Vv8v&q69bg)8aOB@ zsCUVmLyeghpi@6yWdGV;Lx96g)dysChgZr~U6AVolyOl)hf#?9icul-PjC@h>v<7URZVo1aZ!L#P;4>&gg(f=L& z|6h_is~*x+T|*AuO#0ojfvAkc77(UPU{PVj=|k3G;I%Za=7F@@RYQXS5CM?2r6KUT zB6jHr3Ush>$9hx$>pFuBY$^C+pj`YyuB;@95f|QEUNA&Iu62wwaW|Rrnw#@}Oud&n zrj%&V-G8|f`P|K@Zbl@u4i!Xid{3d5O#T%L7aq%^bgkE&X4S|I;tcuM#{>K!U%0Sz zRMOZQ6*5A;HB(5@Aax#`Hl#OU*WwSvWBJK{`_wftK>&E60XAF;AkA;uvvKg}L6#{# z@y_+Y4d!vwixmGfvA^NqkAx~)%*?vr z9~RO4=ojs9kBK?>^66U9c!Bmqb$B+t7^8l0hp#_y$4h<=i9$}a{oyXO;eE}oSN~jV zzs@Ts!}Ia(BqTgzfh17RYEhNV28p2918;XyBp5_H^*znE%(>-ai17Yw^YUgqWyB=| zBim)|@y+Zc<7P|Ue!cYN&Md`I2li`CzBlvYf7B!O!2ZFxj0VG80lXI%wX#6m3pg@g z^|y)dZA@9ofaQdNgm>B_OoD1mmMTbxx#eyEsv~UQxBb%_=W)Pk4R-iu)60j8@n%hYjPslx_cHU&0g18`a)|ARFWO+|DUXy52+^nPS&DLUz-ru}% zIhYFvYJn#7V4ms41;tDQfoZ+w&f8XC)G%qb-xN=-*B_I1e-4Pb;~y>>AR~t^v6YB$ zB3HWR=8KKZ?UmAiJ~yg;adO~fOGYFzi5g9F9RV#E4R}A*cv=)v&*j_3JU0x6NUf8> zn}dX8yNKH0-tT}vNRXI!I0@`@Q^i0yQvBKG2qes_%OQ(RU8wh+1l{ons-@NadSBUs=@6otFx+n%})7b2J$cjubS zqEde)Jp<5CO>CkyU^-u%c()T=MIO_{T zXaF+Wk?KXQ`gX>O{V;P6ZVnyF&6VmvgfeV)Z2x7{lY6mv<3sb|D8*kO1vHyp$w}6VW?b^Q;Bm^V`=@3x5kxoHE>5%Ra zlL{_peL_xshX1r+#B&a^G}?VJ8aPz3U%FR9zLB~^eP>}ed;&L z)%wCYjaS9Jtx4F`PW3la7^qm;V}3>#7yB6V9iC+e0hX+_@N!u8?MhGe6eT97+G^=T z70Z({i(4m?{UD#EY2zyoG6Oq_+n0C4318Xv8jSlFH2Z1uB3@i4ghhq#F0c2oI%h7- z{Y9$!pOBN5_`f-j=7e(!W~L&9ndEylS@%2qcb-!hch%-~2UsyEFOS`bj=dW2^gT0U zADG%wqU0oV8q||dD=KXM0&TIzKk6h8UU)(&E=j>HVd_WZK5Az;fO5^r^OqLhFSwtL zh_;_Z7{1}C6hM|t3uI$x)al5!{eS6GTY~K+*J?#eb8HzCvYbhh%XOBAo5$TJ^}mFD8ZSg z!OLr$T_l3s{^c8?rRA)I=}~r_4G;Zu{X2_E9HKkHd*75f8bT3XVjS=Ekn~%GdpH!z zh_|AU!1%gXVTwpZUaC7&wce}Yb_21Ob>Mw}!ujc~6V(ZbW9i0~hoMuxG?P$R9MfX@ zTMLvxjhsu2K$skBX{H-2SuB5}sp9=Y9be;-Joca4#BQ8gLY9WUAHQ+)0)FBj$oZHC zlNIr(cv@&mDF(|oWu#Rd*fT1a@kzwgAQMcJ22H4~y#?1^K{!RF)Glly^{@I*6; zo(NrrvURgfQW6!VXIKG|V1J0bkt;A)<0Sl60Mb>PGNz2j=$+8xLSB5 z2%bZ$B3JVuvWC1s^z=!N-PHI|a+PL?fnN;56=9YQ7${@csJnPuq&}B*cX0`Kb)DI5 zyO=taGd9r_lw6$VPpI>CUG2y_8J~;k86=@odzY&3R)gwZ8jY#&9(1#QZJutL*+h7FM-mNj!LDz@2$=jzzfF?ayP4K(=FBtfYtdVQd zw0=)*zi8Ute(Bf#H^#MltrnhrkULt~{Y%Qqz}h{(C78;lXBqKVu6~{i;q}wJn%*UF z%QLJ$+J4P%`JcTJ@>95XBgmT6Ee?C%s;_2v^#Arq?0t4&QO{8{-Hc9+D@k=$4?bN{n6mJ8 zJ``Ty1TDD^vD@ylZ=G6GjhBu(&3#LvUR383z(>7 z!iBowI1;HcgS6k+Av*w*m^28JY)p}T~cVV=am2}5PQ+G4}YRP2rPz%Gy* z8oJ2MGYZfd#Pw`4f=>AgdPyG4*he)4X)*jd7({Cj|LdfO<)2X6?Fp>Xl(AHTEVAam~qdK`G(;${{&W-A;lQ)00G0 zqLL*iqp+4R9YS0D+7~;RWZ}JcR=INy&J7vt(2cI=JFixLU(tE#;nc0}YSx{5Mjvml za2PTOyBRYC1-rdBD|ALN(4e#3x7oJbV_q*U7CF3JvxfNf9ke*T<-3%x~e;@kb@T8h4 zi32_4W7_2&fIz)6e!*AkBtA`fy;_o&mruq_AZ=oJg?)7lITroY*(pfu)fck zA9$izW}DB5k35|VPd8vS3I(c17y@Zw#$+`8>kCD&X@&Lc!z|CW7I<` zDwL-tC;L4t(a|;{@~QLz)vyV$aPTFVs&J0tYDGgRW0HN&4_LGG%Z7=< zW|&(c91aZK5>JvyTDtqI;vtT@t9u!$xAw6izq((&KgDH-AMFwn>|@bJ?5Ik*rQ$Du z-aCxPRX7d6>)`N46HV8ZDDOYGql@|Koe!G(yNI9!NM#VFD$MFoy#= zm0KsAMBY5pcsQ8d3`l`K#e?N<$X$ND7UXt#-DK%ovGL0F=;)!GoafNgGuG2ED$C*d zZcu)dNPxil2LlfxWssnd{q(C-@rL*6Nuf6Spr_OH=gViMc&0gZ7fW?*{HWRB)bH=9 z{&>xLdtMYdrPf9AfcgVn>jI~L(7V2QkJT9vz zxr;gJT~oJJiESwD8-y4eDR^YCppYyjhbBk`u5~GOoZeE4tOoFR?jhc}X3x;}C-BlV zFw`2BTY{O62VtU-@m~fzs+$*MuZ3SNLxdOkw;Fb#I|Hh!AqIDSAd$n}Cw?SG!5>=R z-{`=9lb@eKYUtPFL;|UT(us?XkI*TM8Cnv#DH=OLHfto|CB2>34rWIFt}FiXU!#6d zgHWzcPAa4>Gaovnuw>OrJb)~M1-BopenMn_tAfoEGq8+9LWwWD@!G*Ovig|A6?)5X zJZkNEDYEBO+8+&q-FE6m#Y1+LzkqM`!iM{#Am2ma3DUn`xi_(}Z_1bM^W#m+d1Fgd0)As_MS^cza|*4J-z1jx!eq$r(x**?@I zv%QuMgW8HD0gd<}i+99tXlXm>-RXiB9|Qr6Tp3`TUa$XbQXd3YghI`6@V`XStGH*% z5Rf4t9N2EB8JoOrp#vtHK1`SB8lF6tYOZ9>q8;|>Gx_NYy}!S=F9G1W803P4DBdz1 ziNSguEomsL+opfoMV$6jZ#tipzZM;Q8wp&h#NPKeW=Yi|?Cdx|VY_bkSIUp1B>En- z=a?g|ZZ{ED=&BI)a@bzwwnA3%(ob zN*Qmi8hSN#$0>!a6^;9k*(+HnGN?y!qhZiXjmkS!Y6hNRg(5WBJTuX@jHVK5OYnTs@N zxdfQ*dcE3+@AjnxwP@4fXH#Bvs{JpMNzh^a<<=N5S&!W&x|x$RTKe6wH_;9mp`jPk zyaY)~fa~dn?*aIMp^k2$>Em7 z%RMSVj;gQhHf(FbovoP2IZVWne+s#OqbEBkLLe{K6#NHpgy@hl>AJUSX{a~ztfq$c zta!`KIa-#p@9frJX5I;WJ+#ihUCDDb>n1!pBm?37>0dp)LLE&?ke5J_ze;5nm-v`Q92Vk5Y2Nb*F z_srG{LfL;|m8+Mm{VZwQD;>0@lDbcRk>QqVckAMn9&1^rfCK=+z{tADo-Vg*Gb z{%xOflKp=vdc%o`p#Ld%L)}gp_he}+uK-^$I%8&F9JsYR!XwsLj*g|Iv)uTGgAqap z3^W51i2R%XYFQK%bUvtA{<&pMCwyITAI48hn|DM11eimK1KdRN5#+q&j1!nN{ot_c z0VFgd2(SDB?%^-K&QoBnII~Cr@+)3}(fn8e$-q`5EzMA%;zNUUoH*1xe6%2flecY1 zaX0ra8Wp9|}?AoX1Av3}i@xuIwIVx1L_#&J6O z-l?%qp}v=(`cM;Mo35RcfKkFaFciS`;r=BZ__V^9UgIi?z_v$ZOkQ(m?#;srt2Cdf z6is@g#Iw~0lH-9I9-R+spiT1WH18<$)`~%@`pvyf*8M9J*Brwchi|%i_R21yLUjU|5Y5ChuI8**Nl<<>ykb52gYnBJK}Bh~66j-h+#0%^@fi=K$9D=SaZz zB*9;6hKd@brIjq0;7aU+dP|_dh%F(QpRxNDX)XWBArZiEA-!5n=$QRRBNG^bg&g5Z z{?Xc(xq^tlt;>qon*3IL)vVNZalIa%96loC~Ph zV5~F_Adlf*P$mH7*;Y+^AgbA@?seTI_3Mm2KkeL*fX>%RxUS6wx|(dbez@UZed$p2 z5)kko51K0{9MS9lF1A;Cy?*uR?-0D`=00n&86Yh5;g>b%r|kSN!a))_~(nXuQK(D7Dwva)~l|2Hrt-v5H&ecWMpVe@M(CI_BJfL-xx)c zE`0nWVHtpWRQjQ7^9}z=T39GBVcVH5+ID;6>ax@x6E+00VYxP33meBygufNO-M>=< z@7Qr8HuNg+_RsC~G}D-I;d|Dr3!kP zmin?=-qFz_^z0cwGJAh*kSDCM|bXbbPvAE%*9t=|Tg4X9)hO4Pd zJFo1|+;q)cqL01M5wpZL#);AFYcvE{5{B`bPL>42kAI2F-GWXx2B*t!s{-Jy50s44 z853=U_X{wfD9r7ZN9lggBIqjfjC3P$N;Ok&;g<&jjSxUw9;%oTIn2=bjU8TIS|WD0 z@!X7Tns26~eE!lFr!=$OdS#jYtRon^biqMTb}I^34|s{imSzc+YCp9w_ZEwaEY1C1z8= z`pyBOsG&i(KVJF~2wync=Ep?$T;`UnII|PpWd9#Txk(~lPT)UZ^qc}N8xCw{@?jhf z$kyZ}h!kmn*M^#rdLX~5p{#ZkGi|uf5DL3-o^d=OXxK3vmuQ&TJ*Q;e@1@hhV_CZW z&~@`(;WSWdtDB$ROFpFW#$=gsbSfH>aI6y9ib|Fhyo_X4eO%=C^0eJ=`(*K!r~JNg z`{erT=t%`qzqfAC%@m|MXY?H0;m$4@|2zaQ4F^~Ls<;j@dsDir99({sftu(daaYt6 zTd&{M6BYG7M}~}pqZm{N7bZR#Z4{vvf940f>K0-xxW3uUt}_dPoT1TApD%KFI@&3< zGl#cjZB1{;4U$l$e_HweULpNJ`y#_B$JVZNRRKE8YU)!=;4TNl#rHn@7G^BrhFKc^ zxu?cf>Da6CDIvij{rzcMNv_pN@P`SeJMH?@r^1qWmO4I-54ZGV6S{cadL?qX zr-Ol2nGmM#eK(E!TU|=G2#RtnR&{r*bb#Zw?zeRgW`ePm#|<0KlYF1yxyRhhe(L(7 zODGSL@agN#64-Er_u@=RFY-bc>IY){+t{@dNyEY*ykzOV?*5c#Q%9Y{0p!|l3$*M_ z0n7?DH#feUn;VD6qr)C+t%S1|(3=e>7t%uB2`hpD_!Du!Jacda@_2GmFgZS+uVqDk zLHs5PHV(cIAhE7{4{Qjt_l=Ibey8g_)RdG@f#Xx>LcPPL276v%AtPW(fkQw*yUmp( zdnP>RKm!7*3+PiLWkdp)e|mzox7Lce985IJOvzjLDqbeNsNVZ6b26&}kRmi)tt#iN zS4AE;b!V^f?z3yONg6LBH1i^7@3_h9y!eljulejJOE|mV&3~W%!nmCXZ>W#}&Od!g z-<0e^J~R+&_7^rDusj zlproZQ|a3_(pR7I172=cH$<0Vna1A18D=iJWwPaN&{aa4dCe8!0LST}h+cQ9Py+E6 z&rrJRmrdHguBt`$^<2q7+7-Ax11xua2nlCPD9bJc$WXeT zU)HU8Ryfeqn4rNd`y6HuOswV>;_cM4=_HN2(igm=7lxebtDU73D`_4O%kq$2M?Ps7 z_y%eRVlU`wkEpzTLUQEwOdtL;^e2Dy{x?HF?s)&uu|{P4!(Q=lf5Zrz)S%Q_zsO)P znf*z6KP|h}V&3+>AQ0mJ>!zFYxTXK}%Hb=#j~iTg*jK0MrP8s!0;E86>f$t@6ryVv z8^O8(@xSKt|7LR`2Lu&@ZUbl_WQ%fb*7Fv+4=chI&fAvjzHqo-2!L9C=|y z=eXEOH@K32?lljyhgR-@C_PlWT0DF#_Ab)kh8oMT&#oHGAMSGlWAi{Q+m925mUoSF z_ZHl2QyTM;yPG_>pSb5{-$U}eynZ_J3-q1j{#O5=TOjG<{*eFyjL1-0OI04ie2c6UJg#o*Ke z+{X{=eSR?eGsw>mfiH4MPS7i(PD5}DV)cKtP1T{vtoMO&M3OrVa&6r%DI&X##%ZD%g*1f;rY3%7V*YiUqB}DZ035pS@cMqAQ+J};b<_FO@yXxD z_#5VQthesti7rz(u5AGIG^@UX=J8SuWYM$|lFa7tfMl@s7kDicFwjH+hMdJxd)5QH zq6~cUaHP}(LxY9QlRDCXzf}Wmd$D)c?w4N&_trzt$k5qffs?I9Nh0_lU?3b>E zNw}OuZ)}c@SP)_Poc;N}qdJkg4+7U{06~@uddxYzI!?y-o4w#4IFyO6|NE8yFFTsZ zZpN9J|GfYkK8zB0Op8S`F2xGk2gk|Gk>_1Y$5B-8+9i9MxXLBUHj*KFIg&`jCu^zBX z>{`2ZDyy9Cg#n6G{~xX*ybZgG(drT1lC7M*NWtEGPamYQHe24=N3OKAJi43ojXcrL zJ?^}J>2~kF+45n2NrG{hjJ+yMFaglnA_e!e-=%A8&>2@cSIdp{1KLK&!#!-Wc&Zur zu{ZVcUlgmyOycjiiKihx9!ddC{<$Lr(|tbfVagX0)nyt!{LMIzV%YE*+PO`)Nqc=O zH=#iq(oPu@czZvFJ!+1IeZ0RT7ZbC8Y-em+oC&p;qs!QcB*ZN|EOc()-;Z z*?HR)uQj9${WYoKy}Ht1IT5Q-J5N2|g4mSKI^?AI*VM6t@P5lbb)|57S+bP8Jlehe z{r}CC+(R|;GR7gmjuJ--#vxfGSt4%NAUf zu*GsbMQ_h+PO5XbDlVItqk_#mU+~^13&99&AJPYjo7l$Mm)P=tC1djxwOOzgry}0> zd4g5CWpUzo8bAGLc2F09fjr0(^0DEgp16s$0x#qAN|9a6^or58ZwHKX)MLWYLJ3jjLdj^Qx<=xqQSC24A!yRg(ksX6pEHZ~U6Qt~b6{_s(4+Z+-nmxz~64>VL7 z092-bk=7<&assvzWPm1ABaP`K6!Gs%_rnKuaC?E6DoK&=p{c1UDupmnkA30lycynL z$zleNK(^XCQk_#^ga;2VVIejtDFzl67GMJ1TJj4IGeYuU>4MWeJPoZf49gpC7f4FY z(bt0!-sv0rZqRi_3ySQ%-g@Nt3>mpU_X`1y*OfUj8L1w#tYzFbFQDb&L%x7t{?qMx;^b%aB1aV8(lD?hKC1&5fv2`eSo5` ziK!{jiqzA~3rk>KqmhrB-o+gw^A$3}!6T#HK3vO^SZ?v!YyuRQ94vV<2`u(YfSxq~ z`dr1%e4iN5T=v6`LGW%__b}qoaZBgo*6UoY;(3 zk4eL>H2CBk)_y&Uy_jGgj<=;!TJ z=yVKuXlZcz3E;8*_u2-2^P6mZzxd;TOreZY5$pT3ay@HwIoR*@M=aQXFTnqs*h!}Q zuy2-8K!?><4mV^^$z)~zkllsx=n7cHuTgQ`(bIzhyeR;ZtgN;+xX+~h>Tv$iFfo>h zxco*0o!xdt^x)s(;^X^eEx=?*LqT-gv1AaQAm-mK>Gbz={{K98el!#_b&bInbp8C{ zxF{~vtX{0d;mDfmueP%RQ9tr!m=Sl1lD2l(fAo&ZJVmkRs%mQe?treiuCA`v>J~mb zSSQkSy27IHA8hNtvxmHaO+jaJ{9)TR9#)ai&E0R?U*CD%6L^*GV_MCs9e6#wC1l!* zEYz&kgkFo-h`H$U)wFPuoKH{v7Whs5$^FbhPnMIINlWiBL_$~0aPiRh5S@|Wm^}_F(ov5j+ zf6W9v8f44kp6i^iJ53Z?lO_v>*FZsj-sp9_h?gs#lG#K z!OJP`oVvOrvTu3L+Tw^yWf^5~qXOj60IL<92E$hYi`D#-%PO>6jtzX{@A6gfNW9h~ zUCP9TV1sPOKw*vHMf=L==*d{D@$__9+09PFD`=Bir?;w%xq$I{Ri#IpB_i z(!?cI#@Z}THm+&%G&<(T%paWY@CYb0Z;?*v+7WFDhwyxQp8Y&ioBcAfeCpa>Sw8?q zu-a;4y7PJ&nLmT^qMl(kj0;A_?rI{^i7D%|o=#ETSS(V;xwXRD-0XAK484ehtoHE; zcSd?ol>2*{1BRnfRE;efs zQT-F#y6lf4J22>dr_He5)Uf%m+wcl2qSk|uR<##Ys3$GfsZe4Cs{QEV>q9P`S@aPSRU(M6f(n7~#-Dr@nVsG-YdWZybU0-yt z1M78>J_ewF&2Vsx?P@D!yhBlthyuh72~qraRD2f2=tz$-H3B$V|8EYKm|#pVmmpf+ z-QLk7^WWg_%zueU{%0@9gUY5__-?T}I(Zc`EP0%_^SwS0yk44Dzfr)g__@3*>I?t= z9@JK?#Q)j`aS5J{0Lxz-)8iql1=xuWM9T3jt@<{uq*x1$PaYOo@0qK`p#j=#?X&#x zB|ms((_ehd46Mzjw{` zc&O~af*P(eRj&&k!FaqCyFr&aKj+?a>EEFbXCTiY~aeBBo+vLbb7gcgNH6*0LOXF%;e>4^*^f!+I(;)AE5~h$MM1tg+pRz~R zLpKNFTBX@h08iDgX#lNit?Zhe2Y=@L58U-o2TUNxy1=`_5*~JlfOW~3pHG98uPxjK zi6Z+jpkOh;N5HidNZTDQ`kS{GL3QIUJW3t(J#FndZo+B}$UCetOLhhZsa@;){B4^^ zvi)I|7JDm`JMg=%wA(fj;l$R*y_pJ|lZV+x+`8nk2dote=7a``+>ixx_BYzH80-~a zz@x7Rc7j90%Lk3xO)dsx{e#NoKXlwdXXUnRiaJK_LNX}_u~jtte|{QWvN{zRb{Hzw zUL2!Yg?TqedJH+F17E{@*QpNYUM<^Eh+oa`jyx3Kajsm?)PH3Ud7d5yoiFebLSn{m zL2>w6@XihedCi%RV(7D96Jn6OQ?P|PN#eBG`vL@0{xvEEqk*v}0l&$ilrFx^+{SkrhRdF*>rDckvKf$A!)K51jmwyu^UxyFLWZ+I~w6BbkS^ z_Ae@ze_wdjBI4Srlpa1Zsj^CIRawB{eAU`x-8`C^#BMTYl*GY@Z}>p)x@xte4CRBf z%9Oz=DoO7cE4BHW=QDyLJxl`di^RoA!v2)DL=kG#wRnQ7Q%XaMbGuMBP#GKKowN9t z4r3Fn8Ls%qr>k|}n{Ux;JS&khC(rFDkA+E=-ReatRj61@$iCcCFhj#9^U#Io_+DCZ z4jXUgG}lqa6*%0{VK0f}iRP63`BGS;$z|9EcOaz%bziZx`oRLdQoM&KvOUFf+6(gK zdg7WI1)6B;@M_*Fgl?qJmK!fJkk+wGjhgow9o+mz+$cv`*(Fl6nuT?pllBYO;)tPA z24Mf^+Zje|{=?=ODaZA6wB&R8e0f-CnJW4LDA^s|<^G(nqy+lxp$JYoodEJHoWG)E zkryiZ{`m0fpM!*ILqZ0ODr-xd14zDbrkyHwnRPI(f8m}lydkK}elKw9ayEclHU-a1 zHmYkL(O_9LG;u`VF3lRLm(!_Z;Z(cKIGK0QypT0^H+$V9(A1NVU#)1!{IXrA){XE` zk#J^sr#~etdq9xscvMD1>|;Z5OZ&HJZzBT{>bpJmZ%bI5x0ur!kh|{IQ7vQ>Ny?&$ z*85N2w)~t`9*`Ji*vr79>}3I$iKR-AbY5ND)NQ8Li+krlUwF7IrUNYVM2myOSs7<6 zs@=>9RbyH2+!uUqpcYLg_yr>{;^eCCM;!2?UTve6Rxc5bSF@FYqlxBQP1^}o-=fs_ z%!v!exb1e3L$9J4)TIUJl2KXv=TSdn9oU%r>Mc=^hPqshypM^mX{rmcYhLXgs-Ek% zCB9A9P%|ah*w{qt*$R9*6F#W%G%pmrOqAK!t+U&0#!dJ6RDB1$kX`Xl^!2r$hr019 zr-Z@wLO)9WKo3jLT9ghNB8+IYPMJ5nEzxew@zrdEPWX#+O#=`=mGfZF#y0j$>3k8N zyVs^)&85BF`NZ=GUwC^hs<;P3E2g&Qz>+O9)Vhh`+pt|=iJnHKC@*Vat%Nr6dOQm> zVV-m7B}&wq*7uWwGXJnS!;gPoBx2H5zz$H#!z>s_C51|#Nfb_6ta$Qpd1Du{*g%?p znxy~MPwMd!Om608YcM4gQebjEHo1IaEACx}j2B@;;9T|_7`?8&F z5IY~I24hV%8XsWk8+Fvf+I8s+Ccf~}ken5KyD(g?;d2~6UYYh<^ANt<=fNtSasn!DaOrewLC;jI1RQiny{NW04~bzmmck zXxWkzFi7;*h!EJ0vbmNJf9}9Le75!U+Id{KThW4OxEo#!O4LwzxhC*QgIs&d01Eby zoN*d{x-+8T+Dw5UqOj|gEx1~HN|zO5vCr4@?8Qv|g`FT&Tz(^Bh0TE>-a0XYJraK; z##>{O$BHHLH;fA}K{LZnk3$UW?oIsX;8=}-L*2k()%lS{6z!6-5?%Y5OH!Jt)v@yP z0Vh=4FMV23Z9n_aGQXoY3EKv+|HQe1iybgk4EV9B%q92(UVmB)%ztKT4_=eL3YjV9 zFF`iGJNS%>86~cju9`o#vBPHd0$<_i$$ArSKv81IaE+RAiRX5?#%-m@)bozLY6?SH zl9l6T#&Y|Z+ZdvWz?BWKU3(rbLlDa%#CJ5aRM9=;3@QyHIOJzA|Z%6U|lKP(SEbrat2pUg+GJld)WgnFI^p|0& z!dUI$@~6DeHsKw21+n8T$&pE9j-z11gk`k5!BzTel&U3;+K zH9&=gq1>trG3FXz$=fSJc2g>3$10y_2JLT>2t&uI5wCi3z5-FPH22_u>FdE;AWZ8X zqL*yzw7k3?dI(2M_*@UuHvVnKs<9vx0X|C1Rxr~hl$jPbZT}pgGbUMkUu@`l?edJg ziA9Gx@YY%kK3E8KyZ$OTNU&c+z80$YN7;_cRX|>SIp$Y7iG_s)AeuX0H9f1SY2?i# z-)GNew%yJ9s!?$2N)&*E+taQW?-TO?#~}GGNG3)ho(k!J6<^{!^au{NID!+t4@^jP z7sH`PGkQ94k#Z|?o*d5j4e#pw{r4fApxiOElqTe0$+_3?R1wLWAnCy2F_H+gKY_2> zv0H9sOk{Ecb8arjPgb^B?Y58GGfc>~DNeWMw?YImC=DRH>Sfoq0hH)R566=ECpU(( zN4mx1I5n1dp7PRxsiZ7n-kk?Lo6;@zM6-tit%7_Qg}-iB%!y86L&6@eH4i@rV%~ux zTb;x+6}u@dVGPjY7M(-QnL>Si&-+UBA{%&691qh;i-Setr|q#plvOAsrh!nfgn4h7 z|2vk*ja=#})x~L7I$z|EWsL3>qW8*~In`y038?dAqjjF+q-0wARPM{3g9{pJWlbnk zr1pUkzcxPx-5$0%qVSDTW39kS5wP1mett$V#<qIw?P?gtZb zegX=S^OfzqZ+O0pys%0ZkHM5ga2&E|GK9q01O06czOyR z93E1}^kI{bgaKyCgd`-?)YOQFbJgMi9e!|d@Z@Aw-2Cg;_v-2dR&!Nt)fUq~Vq*NO zs^00TOG%+bknjXWN8@nYEQJH!+ADWA=Vd#qK?{Sb!fX|{UtHZ`7;9@YoOd53%HThK zD0;OiYt?Ha;jjkanOb9deU1GX)yNbviN|+9;GTt2vbJ%mkK@jXcq>PC+A^&wtILbn z{Ni}EO7VU_X}*{3o9|Q3ZKD8p|3a~4B8LPI;|p#4A8&Qq`?A~JBZF4PsC5ZbJ~{!H z^N)o0?O!diFh0B{;kM}-&SaMk#K5;Y_LQ_x9c9_cNrP#I?$~ zRsC-D?IO2j$McBz{C#z@Hf;0Tp3ToxHq7!QO;L>N2hM^2GVJ~IqN zbAbi+8V2BRZPdl-{;{Z?`AAos_4KT-Q+1D?xqwA2VY}FvWDKM_#kn_cbJlmpUZ*F` zCn8-{S}us(CJ@c&v$!CX{S!hW?5zZhr_g&U=hS zYmrC`-qwjxP;beJNoA8R2yggfHQjYx-qk&oY5rxr>YPsuWE5u=N?%r1mxIf%@5Bwo zDDc$^e)n6_eNMQUAPj(4kfmJT1rH&s%V==DI>N3BAMN{to1Pvh zUizh|g7QGOYu8SGlBoKlo;KenR2TOgN!|_*f1Yl~&#f8?3=E}y6qxpjRb{c=g)~O% zvQ7I(QOuMHI4N1^=kbxY@Hf~VHLe}GXwj7i^v{r<_7MjQog7ksF8LwrT=!i$%hq$9 zV-RkDdj;;_kZ52gIXyV04_%9)N$2U>;L^B@Mn51Ppe&T`!Lv$whtM1Ts;nrIZu27h z#DOC4W*_S{69*>W<*S{MWyBV3@9t!JXXV^}>F%e?`H2t_;!i>(7`j!+OXA_VZj-Fr z)`IQRHa^QXr|q%imi+VIIn(oSg$cQUoTM83Om8E0&4=c60zDRW5+FjPL#cOu=^tq7yuF1_FYD)&R7CrxsT#zti_=!}HlD zK=YR>?3HY`VOA>OaDG$kb^Pja{N zsuNXW>YTa*QfW#r9WrL!uSLI1R>0#ZfuPSvt0q;1bFV;lB=QBOw#|+=HHr!ZFPIK; ze=>|v__8oNMdP|*>sv*{qCE%Vje0Ogu;~iHMt;e~HFnS1RUqR-^U1R9X$!QDIa+uQ zVo2GvMaeF#$wZYSnL{1y#LsRK`qZiGr`Rpwn1*Mn@?AEuXM?KaORNH5NI+EdIE<|w zDUyjrizqC+(9Ebw>$UBPT=}Pu&L`Z`#If;Sq7VwS8y{8r=M2!2C0wJlnq8TM z6LX`TgPOukG6T8A1=%DEl=#~1r-wW5*YP;KA_ndS#+M1{BUbA8Q5(h0GSKQ>+5i`l#V9A*v1*neM-Ffjy zLA%EA5G4mYP_uuHm~}Ofv1RqB+gdQoZhoM=lYFsMo)#jCF)+9^h+JaS7ZwvuvxHE) zgBZpg+4Q?V{DtcXOT|xYFD}dj48w&nBywS2+tI{8EuaE`WLq8o-pz{^-+Iw6u#qYw zmY(fGW|_fsx@Ti^re=tM9Puzik(rj07^LS#msI>$P{lch`(onYaGXl)xFM(aXx+~2Rp7x?{9FZa^Z!w_# zang+x5fv zL$g@-e@6$LEWdM^C`+k87OBh=J9jl^5dWW)+3c3I{|G%u5bRM#_=n`U$x8D{fF5a ziisT09c*EP&Icu?m17B5?g@ei0@=;_X0#dO%o8_p)v8_CH7 z$MLO5+q7y@UymGq4}?`A#iv9+?RHhm^;)Yx^#3B`^<-4%P2l!hubYJ)nSqL6hTPp% zxI?+p5;LGHQO{OG_OzuBBr0}QfB!{!u-Atxb9~)1Y_9y-j5*jFF#ydMA+AL>@$TK>d$Y23t&;IWsQ4KZ^%-bc2OFcv1On7eOSx z109Vga>uW|OzDQ-<5jG(w1a`qWnAW`{U!;U{``#NJqae9B7R7WvEG)in67a zUycsnqw?bW*5OsxY|ux0(&A}v$pz}?a_mnBydl*qd-?F9*}v28*ESXBJ^vM}X1E+A zuA)-DxKlx0mE=^DsAquIWOjOnh&aeTJOyt9=Ka4Rv-3&=^cT z?`goUIgVK69WDH+V2s+Y`iT+r?J#h-5VA33@`>%upra)tuB9B2*nnftU+2LK37Y%X^+fy;jTI4*6#QY0`Kx zfAL|RCpgP)yX|fg8d1XbZ8mVYa%Z)Bn+J$YY+$#2W&sS6sTa-ePAlt6OY7|BiUa_Y z2!FAmx^3R3c6(er$gvCZa5%KzaxU)@PI|*VRr-*q0D+a@f`|7i-Mnsj4fK)`zx|(zVAHv*nb(!rUqff(tcgmUiA7U}#Z%>P~ zc0P?~<<;}`_Vop-=?d+fgv06UAeZQGUWMJzCp=#^=vk4h!&~vq&FiGf8}?_*RuROE zgd;q>3j5GxjlLlK4)eVBlc}r%>m6G&we6{g=ZV#CMYd zWcJ}V)+7tsh~+RKBWc!ZWuW}bZqM$WzVMWzld{u;oZXa#G|8g%$LsV+`NyY82k@(&7o89XNUw?mQVlIw$0A4vV9`l}N z{1r0ULc`?~xs>lwk)_(|1hcbzBU4ji@Y~xuFBs+EpNP|qkNm_u+>(WAXm_WGOG+?f`$-od;LtitBF9b1-r+v{IYo+Y&2nHOcjNLSB_}5*Fw`fl@;UFYh8?>6 z5p@4X?xkEsWmpc_!}OiiTmVGa^~4AAEj~2W0$8JELg6I)l}oRI)YHm*e@{&2vyWwt z-rb9&xKRJ&5dv!MejI`ticEH+=-hEz$FDyld%@lvugax6_lZ~SHWZ+8UXl*9P3z_? zo{4M+A|3Y@!Y|#py+(5b-_Bj{hSR)wRd&q(qISC0?>D6b18mR7vf#_>YvPArV)X1&d43Vx+M>hs$EEZRmRz1Mjz30flTf`_8cBNRwfMy5g?SjhRl`aIG#j-(-+cjzGLAAh3+9n{e1w25WO%j; zo@o-syY5QbFg5;$NH9FiR$z>1E*=WPWbG~mjq_zq0ezTbVQ-QzZlh2U3XuT8=>Eb! ztCU*ymI$Ijrg}xOnG=UQyWUdr-wMCP1)rRHT)zZ>r%|!77{VpVUrJq$X-*oV$a7bQ(t^d{Cc<7v z3zvQkmgMO75V!NEr7?gV(q_!F7QLzTaHw`ucp4|WqM z>guH(#bN5vq+kToFEkVtYsYJ=6pg3D-zeU^{WNJ2I&!SG0wFl26o(+C>L4444&(Ro zRU@3U#;<3>qUTR0#};`hQZVa_agoceulErc7oXiZ$Q6kHwaWDrT>RLMVQgiC%uG%M?U#Ya!yWDvVQU-0e1SYVD$Kj#40#*n;Lq(($LnX=HpBH_tKzp1KC(6 zzV3)r@UqQ_cXE8oijKcif;cGU0)p*RlD`AAl=ffpmeu1f=GAw&`3*ncS|Fk(%s$N(mAx`&<)@A ziT9l6ob&xRb6pIx_n!M+_gd>0>z)~Mx5sC1N)seS7`)1f$I2*6+QqxLySQE+oN=>c zS*3A1M8~Fu!C}PJwzC-<8;gmFMdueq`rZ%w_}>4%ux#M9E(+H2e|MFEi~d3=tjGt< zTS`J`6zAI`oD(+CB!AbNyD`{p|I@l;-0x^q^SfZN3~{c&SXV6EFVhK;G3YY~Lk)L+ zw{lxnXx>q{bk?xKS*HF=^_%D(7oSq(~KsICNXk;9h2c6d$^1{~E*8RaqVWsnN zQT2r5#%Y>ce(K%iJ04Byh*pghz*0eXA<^gegV|0@Or(v7NldP+WCmtQ-auGf)R(0H zb>{r*Rl4+S2QmPB8s~4A=>WysF*)TW#y&o$P&$jBY;~p=2Lmgc(A8#;J3kUjyVo|{Y!KRchjL$Yo&>-D>` zUc(u#s$OtYu)Vg*uCUOiif9ZS|YOmTEXb3%Xb}<#nIC3=h+#K7>W>zxW>PhyxnuL z4}d?@xo*7pkMQyP?LakO`N$)kj#@l^hS9i}eDb}pu<&h5v1&OPBV$zkw$a$CF2L=m z)vV)qaMFp4VH0P|TKD`N0e|GIKdC~)49?LZ9#j602k64V$11tE&+hH0-N>kgW0Qh{Vq#`yTj-f? zBEx9dB>7Z54PY9c(>;lbiVlp<_P@a>&uP%2mrr05kR5hSpX-YeI8e^W7!u_EFaRYVJc;R8sy_f%r_o z>2qRwT3AbqXw6u0SEeIig4X?^Ra|&-I**q7de8d-*;1##a;YvjDvFUMYR2S*)qD!w zOkCZaP+7DV?z;X+@8aY_N!aY0>Bm2VlKkh+$8uQ2Z{_O$JC2@NKXEyoW*CHd^=gI$GH~%=n{_QPeXhI}1w*$%>Rx&>fe_@w!nr`$%l?sbj(-Y7rnwy)O zSKI)gkx%4`WAaDMoXiyC-d+6i3q&EzHW^QEu-$}h0>oMn2o(wMxbN-g2tmj4@~bqS zcAtw2y7XRMO-&^077$rUL0g3uG)P?*eE0yn>QX?gQO|+Be~_uo!wQJT&g+2niFh(8 zT35)fU?ggKb=Azo&fc4->p8f@Z@(v})nMaOe?H2&)>8rMUSD7D5THF^>R6lshExFg zau49=>T>l+yIX#GS~iw8F}+RSGSkdjW4C|CZSlRQrw1#!e?Kaf7fYI+P?%O1?sv=f zw$`W4gD1y}QeZ0azc%;!9Np0WJa*44;zyUqtCkD$^EamQBzfK1LqZV7MaNmz1w8I* z-jMSXny3RUF zK7A#R`{zZp<^qa9BsmE8T-!IZ_YVOg319>n-={pa8ZBRr0yukLb58udt-0PYF&R1i9v?XzU#IMMdSEEz2VtvO%B z@8IsOVWS#bh@jE)gc9dTR`qUpd>N*;RG-;Wzt<^a^3f{u4x4-JT$6xkjuC`XUkT~K zM&4({Zjs3+#pUO@e+cOI|25U}CC~fUh+k6EiRk2|r5epBrTsNY+N&S$RdASQ zvBS=$Fl`T}PT+5OFkJLw2rQH897Gx6Xp{EM&%d?wU)$V9VZt{nUQEj8%WOh)G=FE`)ud^A39!S5gR}2%E95W3w6H5 zRFbmqmopQe+DemruWs|~4u>Z~ER<2$pV#FH&&!NXpH~Q#TI39Mi24 zKl}l=PS#qLh3QG0>p|3_+j=VZ2k##rXS26_Bh5mPsEjhyc(VQIQ3=NUjHi0dtbn3s z^USn_=~_as^O4*#4`H&jmA-;qFy#jYENMnpK{xhP zT*?n^H8zJbHW1o*)FX3C6okeD|7&cv4Tm#|jMcM1WhMz|oV&PW+3GR#VGy=FOr1#4?yz z^)O=C^K^>@rE=1iDJAOv2}Os@Cc#1`AT&c)q4@c zu$PIx`Zz*&3m`4ccxAI)I7^(Qteh%NPo6V%vVGg7wBUAfDLnFjgztecFmb@A&g z`svTamX?{3I3!OlFEA;jI=X|vaf<$SX)AAt?t?cJIg!KR@rIEVf$E|t4G<% z=5BmZee%fg9D$=1-gsf~*?Gh^L84d!wLslx{wj@!n>Rygim8gp&!?n}?Gh1jFX)qp zMsWA4Ntz^$Iil;8zR%-A@H{*2Q+M8FW!4*DMo2Xuo?;L#>=i3FMcv*na8zab3V_8i z$!CU$YwuyL>Yyt;UW8}u{X$*KBdLfDEsBr=`rI-$x>YaR9%>`;A8bf|xR3t0tyLfXG^?%Ab92vF86-z5OJJDoYc+ign&HE_f@z z31@cw4BiIJp@dysxvkdPB3fE_0rAf1FMvHk#N!wace>VK>j#$t2Lp3z7VxoixBAY4 z#H|%T!pjZxGJoNpZhe}b(&yv;BUBC)Q&K{sk$d)!Yx<$%;RSa{Yo4Cp2FW2-BbRFC zh&g*z>+JPH-JHkTKF&M7I=x#uJwUm7MUGFmy8p6xBe_2&w7BylpNgu7GeXrBrUEN> zhp&;%c%xsm0P3b=q?(5I7G__jo57pMAz6rkO4w9oVt~=PD$E4hb#M4~KSnY|+;ED) zMgOCO@q|~IMrLC&B)cV|8>t)P7Al=cP91yY8uX-zo^|q(x%~m=Cbp<5fSL!cH?6a>Lwi7ft@d@~`fMo{Z=3Bao*fhn=x541u%T2PQ#pgi zRSFb&C7DZdg$2Y9E)fs0`ifO3Nu6mtBZIuh;;xA0vg8pP11f{L$SAJPg2Qy+DdRQl zGnqrKkb$vV?RLajPm$lGo{4aBEmGeFhPjePjAMBJNN?ANi?_{w9D$o~I_oRBGBt|U9)fqT)7)>l- z8Ng`8+bUGo^yfC z-DmCo?r`2pZ7j8yrJ>s634*(igRK+LH;=|eT#S_1^&e3;Hw-{p#vuvx zYH#0`Q#Y4a7%V1`b#I*I!;VROZei2#;9k$+cZ`0ELpcW%_A-Fr;_@8BGtTSf$ruIR z5i6!!6dh)M0C-+?{%{VaH+DPhGLIW5(l(x^q@w((qVHv@Kl`h1js6% zEO-GTNmt3s7eOc=lPk)Mp*aoqg(}A`J}G*0NHRONbMYPUSpSUO7tqyjZdW@%xrnYK zH)o|?awCf5Q*(S`$?f&i9%2vc)wcdz@?=9mHm-{e2(mWfPQ;guHg^!QmZZ1eS(_|S2$o6%mgA7oha0gCXEeU!I|r<<@!CadR02cC^5nKT_If7TL;R2&%S>S)4#8Z z<{J^<4=$W~+H_dBIxt`yrDQC7QUy*17_V+1uv2Pu!iz< zE&6ehVe>&jZC1!DoRk&wWlOc-ZLbw?C_LDo(fY*KOWEn_KeH8uV$+#Pni${sKNfdO zs9|5l*W;I($*->&bVaL_kkvB(qF2wc^pJ_pp{vNWPBig_c$<>s5lD*2 z{lYysGVo(E2yR5~081__@@1Z_jnF|~*TJLtO#mEg!Y4G;^H!!(RlB5$in1)=wN^PSg0zi127nt*q_Kv>j0R1?NS!Du5aSvc)2-|sY8 zTFs?{X-~JzWFAvPtZYP4hgYM=cc?^+?{8U(sHN-NC5;@%h@s>K<2STllXEQ2`(-N& z$ApuNSJauk;`36BzWiGlqNW9;j1Pofk4w_9K z3eartVGK%4oCZucSv|4-A_a6} zbf5?QeLTTr?z6nwiF9T9{v)zx)EDAI4|=y?Tlhnd63e=k??4@xIy(20L?I67^ZixY zoei-Z_}HeWLkzofC-L-jp|KYRe(=!kV%=k8#(b{E!^_?s0KwZ^_xs()J|Xr}+seG9g#!^MJKH#t?ldC| zlRnXVMh;;cCuK_O78>{}3yhGgYN?4b924E5@v67-pEH?(`TZ#o&W%P-%S>=9t&Cok zP|s6%T&e7~)q7v(>X?#YE_&#Hzq$2y2v4m?Y43&4n9N05eO7xgkjB7Xy#6v3MYi7t z(a`llok_U-K%7;~$Luw2^lo?r{4fYhN1|S`8`?>ROkfq}I?z{2J`73IM55a#N5(7w zzeCzl!Q5TZNu@+?hZG3pzp=$?pwh$uhh`E;yj<-P?D;v zKxsCB^b`2jl{V#kSLfImv%*+ob>~3+jBp8pZEiaWcEC%6tHDirW7stpVBZ` zZ&c^CER>I`drf*M;Y5yTnivB><}b?WxcsWyb+Oxe9VW-rlwDKhOxo3y z1ZC$bs<1?k6C>&C8)5FJY=06}qOx`pb}!E0%CM=PhCOrHK6dwmrpt;yF70P;M}LTS z|0qOnbX1hJ>8(NOw^-Ch-Xc+RkA8I%xAI=R%%%&ERQJM)Mv96Yy-AX;oTRS;f6u4) z`FM1^b?5*z|90$$?OWCCn_5lKCK--Wd?9%svMKbe@*CTGC&!{4$z25+%bjYcju#;3{hUjM@17H_fl8{98i%(9I+ zgE@J};BrApLY78qi)Q5B2KkkVB&dhM0~*i=emMsywRY6R`9#V~mRX#*knRWgN>`%~ z?CjujaWvsu^M$Xc>(``A$KB*y_T-95V?B-W0vk7cAf{ zzvpzBc&Iy8jN~^@K0@S6J^}b=*Y_Pxu8iq0+W5Gk(!=V0q4E^qpF`G6t2|h{YIl&D zAT*ET8``s=A zi%Z=wHf4gFByzFh{WUXgH2<^;6ua`HuKe;uaAnQm^7*jM)b%?w3F}!2dNtio$==np z+LfJdSvTo5&%*OCmBs#%I+G*lQR7yfg_5cmgo#}R(+rlKU~<)%ltHM0fV&yMto2Ny zIdol?*w*=g!LX81YlMYp)dfSn%am2~mmTbdB2xMqFjzawP|m}Rh`-O=oWq8P0!7@7rc4I>(BbOpI}Du!aMzj2}C=0 z{grP0(L~KkayUldztO~2Ep#Yz%N`+I1iGo(4V-<$xC68$h6u;S*&ET3d+*Rh{&=ud(+TME{xP@0R4XVBb;Q zot_$t&hDA5k!mkG2Bl>~b1&F;zpJOVsriMFm@cem{v`^7Tr@Mji=?&rdUIQNjl@St zrh9Ux434q>3t%b1)1bH5kc`Kq_aen~>CLh0Yeti90LH`Paim*Ja_XvBJ;^E%*5z^{ z@*2K<{)`?m~Y- zdWQYL=Q`B_q!raWEegI^ePe;jAE8;OFRQtQ4SPrtXoU+{(i}!pz1u}%jabal)JzEa zj(*m%_eFJ!Cm|$>6{EN6SHZ?2U*%F{iGuDN4wKoNmUk<{Tu~%t;aXrVJGfoP(*6e9 zdz&Ao(4Uf>AnlJO!oDej%&|{4*6EAHbrdBzwha1R-IDyw>l&~0)n2sgcqp-BRV}tI zAWQq>s(;6rFW-k`5_sg5}Z=}Y&!urSqVY7D@mdw#S3;Z;a` z;d{5#6-MuT<{`-UZV&%Ot2G{`;l71i7=h997d6WOgTy*9jSOh2Y0wk}Jyw~^)g+J~^o zLH>mq?&+>EN@sspTR3{15Jo-2`pf%Oq$QCc+=d){$wpMxiwj!ERQPWHNQVHIOVDD< zjLWBGvmvxyua}~$ekAeLeWV1MSvy+3k!?QW*Jt z-4R*-;S!wVbaJ$5Axc?3~1jR1@lW=d-4-oD#k_(yP z?~QmkPHs_DNyUX8jYXLZt4Rc27qEkd+fE5R+Zk3L4hUy=%l)GlhXpADTUA1A&VI-p zTK|mkJ-qR_8|m(dF=rBB3N;}sOCd7EJ%E-wm@({g3JK9sCocA5Qv5RtABi&b1;Q}M z4Sch8nRa(BL#4;?PNCHyDVjr?53G$;*9OlyUryk+5l?%-W~=L9p^ks|hinidd=cD8 zVBNsPYn7A)E+3$4G+h5aoXTthlAl$F(+_!pJw5`f13k#H{!krCi>_jC4lrxs5H5LMmml z^pnpnWnGhM@3&?dY%+dC@BH%z&*f+!a)Ysz-MDc!G<-)#NB1UiSias$8_@BbfA#S2 zs4<^ICI1{L@_2WdB}X+;XQ>JJ`Vn02&j{;2p$srv{5_AY>7KanSi zOER!ls7RSUDnLmY#MlhTgqT=ag`-IL^b8E30c5l-9DrRrrl!6nE-fvcHg91=Resfu1wxo;ZJm$-J+T!7%m6a8w zq4|z{S2x&kAw+qQsZ4&2P?*=m z$c}XZK5WXE-&htHG5Bf@7iH+==K4?*N;1x3--(32ul;QJ`UEelrAE56TeuRmWtIBc z9QVgVo2npah%7x80!dX9E<6wls4O@?rce$IVU@!LMkpoEzqd@t zF3n@pQI9#*Lo*v`s!1?end1s43KFTjqAgtIxq3i=Q8z=-7s{j3V>{>Ke{A59Vl5}T zIroHb&V4KCDcw+uysKUSHGI4`i(l~-d(mIb-+JNw7-JN8W%66v>XgFG=}QX{qBY)1 zt}CBF0}%qpS7$?8MzJJeIkatkKHs}O4bEeb*rn#-muJfCJW#X!5}!GLl#1dDRc>ZD zA5){q=g@!qZxAK0Yro_H*4(F3H*~T5!_gV>@ygL3o`K<_yv=Pi=3a7g=o!W@A1&Hk z>pYZIJoBCVp7uRy1c8yzULHEKub7yA3=a6GTnMLVXt4Tyv;_^!OG_E~I zL<1&U^h1IgLkti0J8N8b*{n&w7ksV-i${{ib%$Fdj-V$CS$VPVWqiZaINz4g|8e&5 ztNy{+Zy7{npPsc2pS1=GzB(4r0-Eh34WC3<^zQz+S_QiGCXV&SLZhRD-uyBY{b&z$ zECVX!3B*R^zt%YP!{(6Mi`#--6@q5&t-}-kREDIR;FCveTzcM_YIUei%1-&f$$Z`} zv^zO}I3shH%5BPT^9CyM;v*)A=9dDzr$KM+U?pv^6sF85v38}4543BY{^Y>6T$V?< z=qh2tp$|Q^ZG#GZ`${FE`@>O`&jUX9DN_yH{q&FJ1? zpI~!3JPn^GNz^XTfZ)&KzV>sNQK}J0nTwp;T`vM@_>|gb%Os3<$`sqUVVR{SH;wYE z4s`jPxRSc;k)`yVGT&`03woh|ANk*kqL!-Ev@i-beS8QIZ(Ky(IexSD=$S}f4ubW?uTGAbpfDN;yA)mBJg-bxo#k6xG>Ipxd?2d4*rtz=Vf*%kYU% zycJ3klD{ro(2eaw`#aIDgy!5{yK-{+mT^Se3LrN>r~p9qXDJ2R{>`Nuhv~U_B8sb< zmwg7Ok#9}y|K#E-QA}2}Z6MCIqx>S3?wLTvnJ_sRbO~Rg5Br?r_pzaB$GwIa#h**WW6M=SkR}j@+1U^Tgq1{X*SL;*%>WgTYbV zHkG5Q#-~Wg>IM?!w4wi9WRNa(^8EeXZAWvBp4&F@;gdbeEbgnbE8+DJpI(+zTztLNUyc7Zwdmsp|B9hm0F zn=fQw5OymM{Z_bo$VS2{06=$o0^6umxTw48Ig#w>&=vVQ;mMTAgF+^pjpU7f~yGM@<^8OGFW`l0eL>LLX=@i64h1TwxXH zg`d{CGU0Zwa6$JZ($n%vr0?e^N!m9Swm_jn5nn9D1z#?H^@CCx$N4KPp=kJ~P>U4b z_-4|3i|*H#@9MAWI%a(>8?Z2C8aj*SS=emnZ3w$96cHDVkDXu?o3ZPZQ_FNMZnxQi zKCer6W%%a)sk%VP)hd;=_)$WBD6NKS+C|%+Sg4YU)bmjid%IibiD$%+t5;*(S7dlL zYk{mMhAjS*ABqiVp)_uU#t4?E=!;r6wHah|)0!Iju-jY|I;bRSb_3WPoPNWT;(|rA z((!ST6-Hl(G1rmT(sXP}7^M@?Bi1`v<-e8|UB`1|xQJ?ox~ESiPzD`*BLzN%VtLzBK#y>T>!VIz-L;wsVevN91xyPGeD9K z@8_czBkZ2=wl%Y4rT(#Hqj!G*R3KjOv=$;jHjJ1aEJs|EE6m(7M}=i$3nzb%%o`Ttly8q!BNRv9(sC z;?fNyGTqPBKa2Sl`;_S;60WQ}cY}ti2=MJc!~aiJL5(v%Zn%C2ZoOfDAo*sOoBhCR z$O~wEGeTjn%)b>#^>qhN-`oml>V^U+zK$no{wocE1YXW2yefFC7AmgL88T;kBQ1w^ zSl&=mDwNdD2PMwi-6WXoKk#_KeB2FR>%Eu~9VWc$30c7Pfs=Liw27HW=V?FbGa-P! zHxJ_R>AJeR<0|XT`N+S)MrjQ|j{+2-pN zOKPY%Ms+>Xl>V6B_-+}Oy2`uDS+n_?6Pk^5LrItvBbcjhC*5b#r%22M-DAs}F9Q;x zU4@wod9SYKD7u&-m!hdn@xCQrk8-rR+!Blyao=ePs)cksO>OgwcdXsxZZwnmJdTK_ zKIm~=J&*+SNEHUR=ucs^98+Znn15?|lym>7Oyl{9D!-w7Qt2j6RaQk;PvGBUFmTS7 z_I)sR9?nN1g{>zY7!EZ#rz|hyHsG&tC2$!O0Z73ub;GBZPS8oSzPJP(q z(51^aL!6q1X*oaH84J?)4T_IO-(KzSgvDDvXF1s54Ojabu~Y9 znO8HW5*CnK^oraN(c&Lb8Xv=r(O>mGAif&-ws^d7ualNDM{&dbo%}XjpwCM>Ia!x~ zd!XZ4LOyfhn_tp$03SYxs17zYW@tt{`Tn%XaG5d}`HWeuZIsyY@E3fw3E5txk`8h1 z$Yax7{rZZmlSIJ39Z*2t=`z`*!9&J;gn_(IkeP0!o!X2qy6|9L`DJ_=O=3k>BKEst zw0g|sY}qf1OZ=PN8k&lX#-P~As9Uv%UQ59FWh8I7KESofR1d@$uM~u=#is!H(HIgn z`D?0smz8{Ml>d|I?1I|0-p-CS7~OrE^B!VKj~zQFczfO2($2{5$N~3FxH1OnUfj~; z7i_b&pNpQrx3Tr4zTZon5+E^f!#c9O&%VA_wbm1`BTI0KjHx9F>@^?;(Ive8$AP;A zW6=39dCF<~;R=y7g9!vhz+n-5ywaQlSWVh|{o3XI5_)}O1IpUk`uFG~pd#oE#vre7 zz5K$@XED#jpD|-{uD0_m9!qh`jZACO#2psWRWO$3?L+R?y}X<%8;koH=?8hlYXvEZ zk1_r8g!q?neP1L1#by{^W8!<`+>t*On^9MsKTO_5Duo&LWF(3r@ruesLiF`tQdWBZ z0YXIM?)sCqt>U8O0YXaMyRLw{%r^d^%9HIClg;KRB2Y=VC`8pWbK+^&$7rTKB4C@y z_*Ob*_4?bdcH(L_Ap8X)Oy^z4&s}V8xOr)X%BPLKFv9Xw7sJ05S9aDL%@XEP8Usbi zTDpgq5^E*Wc^B6r5AM!_R`b;gTeyz|_Z;#dU&2u_-76z3qiRVu=>G8p{eKete>nlj z04EPHwOn7=^z-$-sri_-ey;Ap5!JfdXjky2`yrN6_Qu>*gFZnmtB&akKRk+veEM_>+}Tgt z?}m?T`-pt@jdax1g;Vpzd3GkJ@&tb{;8O6|ZaMk)^%0282!1ic^N|KmQ=>%>BVB;x zyzsOZ9Ytrc8Hto+FLiY=+d3mVBW$QUpe1EPKFMUjfkX?OfzdcHPqa88&MP<#9;QS) z*6~A0={h$c*U#%4*Ej1+a#?!3I45|%IGkwuCD$C4ks?|gp(W)F3Ug?bBP$RL?v2;8 zGM8|geZ$q2{FTJ1|orUVCIRzq=D zdbBcY<1zWKzDjakUUe_O^|`SSe6xe98Me@>J+UZ7nn!Wz^_GM@tyepxz60H((tn!N zceQi|=^tn7KQOpLVycSg%lylWLN?K0(Mfoe^Zw2slv6b#pK&iQ?6VXn_};;NsNGlN z4vzKWgS|L9eFD1P1{)$$XBS;n?3iEK{I$W~me8xysYL^OQH9~c?|3oqutH9R>nITBy=b=nuY(qr7MAU<4g@EPva zd&dsHK;Bz``cR;v_tdK~EBDXs^6%gIDpDnlx#3apqW&c8xNhaf-kQgR-@3~m;de8& z$>}5#@D}M991M|dZfNLOS|ap=L+hK!5@y!#fd_^irpTfZa)gfqSw63ciHTGSTgV(U zC+F@kP@bngK`dW=f_Az;asFep#>F9pkg{k+=eIy-g0o236*|9`yN+SXs~AQ~m4 ziH=SQ7QG|{J8lrO;pi~->j(kvK=S1}e9KJ^NYW{6;L8Pj6%`zS4KLsB>9O2M{?mFH zkD8j=^yd$ZRp(8VR34|uIU^&wOhAu{3xozhp%5Gzx^XVHos^vX_U&7tl%gi?vJ=|$ z)ezI)3bKC)H-ygE!~WEo{O1))=qFzYfBcwBeO6U?yzU9KQ8Fa{=J@~T-~MrPUnIWl z7bp9tDn%w-Nc`9B{_E~@VYM4A?CL%fp4_iI_Su)CAPc#uJ{6n;py} zaWbaT+#ny_wT6YkISEQ?;x>L*5R;Vy$cXEQNeOCpa{7;eJYCb&hZiy z%@#0OB4V-Bw8=8`8vm5VM|iLWxLLB{gzFR=s^GhrQLgCmdm6FTHNvGjxprIo%I_0oB1>qk?yDIC&xxje6F0 zjJ~??ZEbIFULA1(v@19SgeauIAhcM3ehF*&=-TCb9*uwh0&tdoOTLeqzOw~U#gVht zTl*Hp`nyNY*Z3AKGOGO%?O3Nd_LoWA&kxGp9~DehK+{} z4)lc{KSYt7I~49$M!vXBR&PQ5ZhWq;JsbIux=dyXIxvJb4`X31)ocBWHP}Y4v=q|l zb_rEAt>E0e;P$nO<;K2fVrTgCHO?(^|Lpy#nW7}&A1Tz?`T6brjDU&Rfx%^2I&Vk) z>A6Dx<>QX*iAa(}tO({`EC`3V#^)JGm9asA<6KK(<59V<8DRpbhMrKex3RY^$txTe zm;HB*Y{4KMOm;oyW8%$rs!{z%HC_9Xu-$LPV^)ukv0U^ku5;-l`dEa|p2s<}oq<1_ za4+5%DScPm6Trwuh;@;8xAuVjQuoyxHtiC5qsMxK*@t5${Z0Ai3e$Zp9W8!IX0ShD zNqTB$AjT#-Wqg~C+IlmsMJ}~Gn=jnBNHm*rEI>fBu{cW8O;hi{+^L;Ln>3HQtn1op`+TE}Qjy6t zgOf;Tu54-$%w~zfZ&T;v;&BBn^pzFQ&!i=|d7MQ`-A|a@!hh|9U%=W21$^o*hrw|O z6PMim)k@eq>qsFa(awc@j8LMD`&P&ig&CBi&9fCoUrhq}?J|wjB_GWL_uuEs8Mi_5 z`QL&2YUI&@%I=RkY@k?t4y!aRQ2)YE*4Z`GumAoe%UV+rtH%l}3uU^_<8<{^RM(xA zFnC@|H>KR?3-L3Jd(>_NNoHA&e@hSdb=P96q>a9|Kw+i@Y=UFb)e+^qSGZ9lK;>0% zv87uNGjgBdjeBbA#?9_H$9N~Q{!?8?iJpkJ0Cdv%9^ma^x4ba2#stmFwRy4WCbsedz)I~%s;+@EIfz$-Ib^WqP^&nn*{ z1|&Z_%R5Z`szxkZD(^VJbEENQB5L;eC14RGOzKuBDlZB&DIeD@!#zm)m3Q;-YOi72 z)asRJoKe*TXVyEXAo@`E$vL<=y(bbBxo7GF&=7{jj+{s4HR|Hh}K{pp-c(9j=h&r#a&FlHXMa%ldx2cp(t+ z1lf4<4Pup1&cvVx!1S3n^pV~ox_RM6T=OJ&<_f67qN*Kp67ZG&gua(l^l=MGdE?aU zTR7HrT^-lqxpRl(er3dz9p7j3V2Z%YW^`SimwwRNbFk&2B`a22dB4Zwj8;!eF#jw8 zaNEZ=WJ6yEX4Jj4dBU^*kxwchyldT+o>4!OLMiv&Xh+OoMjY<)zAd8A+@tchQHSQF zDvcM0y&k_I75^gSy~^{untEc3qYRy|x)VM9!H%DR%L?sCki|u8myBaNzI&S> zmG$tq67;M|Qrd$(Had1_()A8-M*1TGD94&+fSxEWg$Z}agYv0c#;TJ!={zd^2EI

R6$E z$E4~pxO=aM7dbqd9qS*`V2@vw^>^^wP4ruGqQ+k-HG8w~b?;Yz%5Q$OnJ`ycAY-=9 zkz4F?u36vI;opF5wPJ_ZXm;CFDM_2*kB_$HR(ZW&p!hs`W5U|&fh&JCJZ!p$6Y%0~ zwxdD2p$3-JV)mVJ&w$8fnrb_;`AaLv*K?Ir*musmA-{Z`CT3gs5gF_j9Y9}Zh`Vu0 zrtsFa#uZ*F^5Hz45+zYh_{02Yg-u+Zmu5X>K#*{7Zb$Z~TM}bKOP-3eYp^-CmXbxq2N?>o5WVsP4#(oV{3bMi6>)|=&+ch>912<)LmI+}bnY{z)|z23U>>%$m- z`Lq8wgAvu^y*H|4cY5AC9iH(ALP_Qc-#|RGr7C! zN9jl2CbkX`ii5QtjyNpNFnH*;wy3kD4CbT^xV&Bm^Z8U4Lq7Bh-bHaTc1W5-0P2Mb znp)x72Z9g!d)~85I0*?v*n!<{^`R%A?yG6BxFU>?I?CL5N6aLCn)pyIg~7{SB-==Z zvcPd)w9b49LYb9h*P+}OvMG{5Ff*CMO_1gr8~(!h*`0Slra__yytVko6!8eozBjys zdd|lF+Ngr-Xv>chBc3drDxRvey${Kx0_*Yqdlrd;|E8NdNNyft3lGobJCJL^8}$(9 z-?9qZwJhZk#-m?? zsG-n*WD#civ(o1wiw|^~nq4i0nEBmAuq}k_uJE>_YIL^@4AM&nJgBtLg!Vh z$W7RMm5FggUG!%Bc83`d|K@56spd59^u%9r`qP$bzN3d-4tMJfV=h+Nnfx3J@ zOQ9F!ywU5&_4Ika+KV&)q(=gb2TGgN;VrgyXsQ_CIG>A5xqU>g$T*cG%f6`$`4WB zDAA@cXz4cPEoi(1G;uUx-Ovb4hE0YgBF5LJOBiA^fU@V1w=H$+-pswx{Vqg-NFlC8 zYDPxE(?K-c{E2O+&rX8%JXB2Fg`L!C@=vJiqXVyg3Q!=pcmQfoaRWwjU_3Y*d|k3? zh1;%r`iEpQz8=ihlx^^8;SrY&y)cbYICzhPAT9jN=0FYIvz0nw5fvh+OPlrd>9^?Q^HE>1`LrZsJcrgcEix zEj$N1^{(4@;}1ETVPXDwPe{yYSWT@rTe-!10Y9OBh8uU|-#H`(^i1ASz3ZuqKW>Oj zVx2IMcHUkvwg`9;i8{rke~ETP+pT+qJ9moz2BY?c5b2oonD{+*5oY3wNRq%QC+J?v zNmMeyNH@_hgP1^}lxOQX)<@{Sp-WNG7Xkr1q)J%L# z=)%~);5C^s`1_|ooJJ@(Q58aC@o%J3aYvxF5v2qo1IR5gDjO+f2ug#@0YkFtnqrp) zF|5V*`||}crL`Re4~IV>s0~Z{H*_ZkUdSg#NawH$3A4N)z5BgEd9JdWq(IcH?dw6EZIfhn6&bH0zg7<=UL>AU8r>0-v@T z++d1&w}g0tu^2;3q}i_`^Kss+?m4gS-C>uL$&&sVmm8j$3DVlR*}SbCV!qcbaekNm za;4FHh1v{`^1UR<@cWSd(v3w?_v&g4tpeP-R#TqP*jb;i?k5sSejqrL4k1PuP}tID zg?-u|XrO<&$-*v7{3i8|51D>3N)}!*tAh! zx0Oeqon(a8FQK%0CHc6v(|3cwy!o!}`I~o*n{&!YT1zc2n!}$0%pNtfLwq3AfYT9{ z15q)*K&0ZQGRpTS7;HNCh7uj6DZ)9`C4udkV5A1hp* z1=$!KPna#cS;Fg#j1Fw9QVESC%z}1Wj(Shl-Wk^=)#|;vt2LwJ6Q@>f;B1Hxe)-(F zkC_5}J?x~bvg#J{ZK&4Wuh03pdeT|d!HcGbhkl3gP^S^;nf|M+qUnf}KzFMHDub5* z;yIc`z&MK`^OgJ0muK_P5G=t`q^z}yH95=<)b4VE^${E$k!r0jgwaV;-Sc4d6ebx z8pTD}R>dt-nCLySS#;r9mYI(Kkkd&Sowrw|S=68Notyr`v%qff@H;|%mQ^!asjUtG zu4A9Se_?wpM1~5TC2@(&i!nCg{2gu6({(0>0^L`CRQi2!)E9_^^lmZEaa{@pQWG5DxwP;72kW{A zby|x5Q)g0Ea#RD;ae9kHS$y@OPZB(2TpU~wZ}iY4OvtEh`Wu4Y_w7dd_y35*NNyYW zYOokfUuk0T>QnA9(dMn2T2lJNgsDe@|UX!fM^1C3OL&&wJ+nfLWFw*_)Et)!LxlLbpdF1-{EKTktJLAzL7o z+GILoWtYL|hj6)UoN>zDNPM3Z~d*&F~v4Qmgo7`?F z*2@$x-^aUV|LiZ~{67yK;pDahUz;#(Qbi8Ut$+^T`T01UP|gQkU2=e@LN4lqrlh1a z11zh6&Z<|FL3hx^JBoQ6dEM%3Aq=^IR9Nks+Ze2EVl7*YgE z!3*2QVEp&(y}dscN=nA2rdyMLaNk>*hCMwf_^CNFuDBO_?Y z$i!Tc%3-R|>4GVSf3Bi?-e82m&I()|C+(?DTj_0<8@~C-gU4>qMzM!}`(M43M-F#; z@O+R3j!LjRlR7Vs4Pg_zM;JgMx@0-T}A^CIlUti?4VXy}|QW}k>IGBXU%B!?36C{iXW_u*czY(y)xqQE^9!VRAi-mHGS zK4ZgE4nxETK;V_`20#D^muiQ_CM>i3a2RQ&1G$T?+T{;gNJSr#)DNI%iF&FN31jlw zWsKz{6mw@{7S#$r;@uLy4N-(v(}teynBqs7!VU)&KU;>@voNwAfjxVQ~2Q zK~r8KJsw`pJc*I7cECsG7EHlnb*zVAsk z+^}m4Sg=bL4RDe>>rYv}ZAs?KnWDg*1nW3JcXX#fxJQq#a!bu~3gUT+L5m%^m@vmzZrV|B%E&;g&kQ+iQh{tfe zaT(FDaQQ`Q-%@U5o#rV&DYg4Po}$w0(>t?azh#bREpU_eu}6gfubPZWIi#!6TY=rw z{WCD!?4xH(mvI|VA+&*q-9z5_z(#wDbN`Rpu4iOm+!25ObartTvc>(efx_uUb|nga zo*NFHRQP#P%h~QZy@EcG$_iC&_C}r2aBmSxp>{5mh8vAIWgdxrN;~)3!@yj+_L13$ z1novMfWvZ~x)%T$ZgAJI+o#78b(@9|@KjuW=uAw8AD|GRK`+PhL4P$@ZfRn@0H=qp zabhAouU`$qP|+7PT5)6$QEP5DCJXELYKGAj`LDFWlP8mCLcnuR0jM)#$8n>!Ch8^$Be7tiJmXYDIBCy zBYnSYf z0=KV@5jbmmvt9nJz zA=)QYh{H6)nAo&b?my@Atv4LWxAgb_S0lfrm|RCN@|gZ&U{qGj#};Gi^rd@PW5eCh zkO~(C9#E#cf4F~vLPT|a9&c@Q$A)ZI8aj_e-7f>$hjwmal9SnHLc1sb_)-Z11%cz@ zv-EIJckrN>Jfl+pLD-Q?*nVC^Jx2I( zr1%DuBhg=vGG}3F;ZNVyf@_eTxVN`+={P5=s>{wY)9(AsnPqBYW|CK%ST^60efjc7 zUPDuEv6|?g6CWrUEJf^d_vng8kC!z1!Gh)NXjf_d7{qQo`LSql1G%#X%>c}fv_%)y z{i7~2r=k}nP*YOTzCD!xo3md;fU-Itdhh<=)Ma32w+#bnT6pvYRlp3s2Rp~)$ECZA{`8(Su-A@w4C5)&bkl9FyT>Q=ID);4+`VbfVMRYYQp^}1G*vyHlpOSyGt$pk zAw~34?b;0=J+w9F5OxmN3%|YE@XRMEQB8#o<51&~Wka}#;Maho!(I>1h%3&~zy88) zl)Y|Nw-+PyPFPipeT$?}L^DX}8PQ)Kqal&G%tXH3j-awVf(QG6^ryRBJi@_cM^e{? zF>C$sde2Z5am&Y=acuFgd9*4n>w=y69H<{cC9Xv(bKf5ne6o*}7#bcim?jNb5TMu+ z)mCAiHdTW(C;YJqDPJi~MX>OoX*?s+3dL#XtPL*dcLe2Mt6&Q)G*qcDSiA5I0+YZN&^}fiZ%NT9Y}td)U&9U^8q3i zULAJ4*3ly>rd=AB5fZ97?4;H$@zQhm!#~S+Dk`WbvY`?SYbtjmPPpS}oD2Wt<&ZH4 z>x>&1lChErwrdBo8zhz95HcHlQ~|bOyf=`H00PHj;DW|BA(G!Xp@F+~s{b=Ko$Zh! z|IOJeConf_4`$|{9!TWnwb(?ZIZdb>RvFQbNIB2uInu1iGJNK7iiuG2ZH^^F-0DgP zNq66J_p5gy3ptZI1_V=f72RG8UeSQctI|~1QFWIMqImnuOm-HW{P1)&#=?)@gzs>$>fFm0qC%}u zmnKK6o7D@NB5*~jGtY^guzib6jH0z#5X>~_-^a@W^Xj{i2LnM;1WQd<+S};2yeu%j z6dK{^6kpeC!CRmMq{niYQ31eNQyRo~b_+jz7noJ7F1i1EST{FQrz!5S?bA@DFXPIo z=0Hae)=-1}KL%UxU4yA#_UF-y`GWa)jhVP>)YpqzmQC7YAMSK+Y?;76hFgNghTFmO zTO!tr)xJ`TXUdae!<4O{m2qU5fOk8!;dd2$Vv+Dox9onGnG?6}$50z`k!AYT_Syqj zMBRR@X^~TUuk}Eao+sATz0uC|P%F^Eo96M!kHcW{!iI8G$v+j1Q4^=~ zrF&U&>cPt>rJ@dUcM(DR{F%a&*(rYmq3X&14TMrc0^*0XWMR@^48J&sEC^#Yrih3aYgssc-?xO*`1&5B^t^`w>|^%?F=)XlA6ddK7L>bRi00_iy+fdr zdaGW{>y|*TdJ>6sIHb>IE)ew9Idy17YDfl9aOw3W1#SgCY=Nn@&oor7FyI38B=h2# z(%Jj^30l)oaE6cqPTvfpZs$?mA1b_N$qc=C5=pTUbFszV4amHB1XiNr{c{QBOkqmU^!@rT}&eAm8!xY zylkUp^?DoV9AKdR3e*nW>`&3J4^8#$;*+ZY40on|V*|@Hl zn_B`X-PitbMz19Toq1nRWe-5wiA2LMRaecHK)??-gip{%ytd=q=6ZXkCp24KzQ7PA zsq^_tZ?6WgYkKjFmyBq=M#sSVaAE!*wW;XIY5=-A9wp0`g0*g#c|4f9c z-gAB*YcqYvph3&YPzLoq@GPps*@H>uXjWo1ClAP_%5nC6iSJ7vp2*nJn69)Hla`(G z3>TE*fq%l|>%VxcPr4LKL7)@vH)4W>((sm?obvTHdJ&oI7-G%pUGk{%blSZY{pDh4 zeuRZ5=#(`i1?!1B*Z0W3{tD`pvY?E;f2{ucXdN&iGyp%)|+c_`0y0CC4SuB-|H7 z%#o|(@R3CIeWfV?$;0zor;{2CnxR~&0}7)yhD-{slO_Du5hTGO(`Erh>c%G|!FsHf zZ&~3rl^NOPV1jLd^gf<0IM2ygy{?r3*cYoC$_08+rq_@@I#bzX6Ynu^c zG$jCFiT4@;kNkS$z3*HIHJ7?onacv+j*xC4XURxmV>3w{(*zmpRVX~YL*vw_EX6yJ z0$7E3(!(1c^V(z(EG7*k8m<@N_rx%GZ?V`W9M z@)%?E(N-Bi!p~*1-dukM(c4p3-AUmmc^k9d9=9OP-S-^Is7PUPTc}|_-D4fAziXv8 zVCiyOvdq@4gnq7%x})SYpx(^AT3$8sL27q-W1(2AoKc*vrYrniZmY1?IiHyMfYRZ>K&&RJOl5dyiHOZ}>MEV2* zb;&8=ZY>!qB&&-Z6Meb-Q-Fz_y*TKFvu8D?&C0^ee*PsQ#XzINc1LhZ*=1c#-2HZ( z>Fvpqh?jsZ3Di>n&!UU>daTW6!8?>}BXY7zaUO@PWqlN%6YRq%WDlQ2_6_j2yR)fyx`mf*LoJ|2R zmG1qpzo4|6V{l;iuXl=xin&=D@Z;`+*s-iYYy&S3vjfXW)v8_tUA3$q$4jtG7Mr+X z=M9u5PFh%gsN{0~v1b~fLY$|G{%ohmkDk}Yg5u$dnj!CPia}q3SB^fB@npDQw==JW ztmM*fx~nFhw9ql&*bimt%m+NuxwO6!F`rfva7G&@?R)lo%gyRHdvPKSd3i_M|fP@x^^gV!L?dV}cFtf)sAJ z*zp~`dPS3^89E-|DW)seKpi2BA25Eai$50Zs4no?;Ecqq7(NG)`d8vAnkth~H^W`} zMs4`#_BNa=(Uj01MwL%KT=yFliv0#)!BMMM-FG;>ao9}{T(7^}1dxc4u3i)QG*Nkh zx0CiK;?;H-ohecY!&H>^jP|mucLtHPyx&Y7HKi_M1EE<3ofz)4*l1C4=2|8%pxG!*I z_z(#acwR=WB>D)b!8@O=d|H5hK|)^$*lN!UgRCDE-93t?fz%pU#nwn~B}DRB=wrteRv@y ziItt+h&}RQiYv1Cf^UfnGn@W=VRjkA5%h?7c_?%%{cpkJc4BU#+<)-U73Bfb3*>|$ zA9$?S!m`ASVo(6`7;%^`vsFsdKS63N5l1jXxeV!RBmtwH1rAIq9;R-YgypJlMe!hA zzP)l<{<%A6eHFawF(GKGCrhX=K;aJl){`E}fd4)z%nH(DE67cPRZbaF+6Ozx2p%;R z`cqyyigc{zJN1g>KMwDiO>yymeBz4PzrJRtV7oQA;(6Zm2Xvo(p1iv7r|+Fpv0`9< z#!*|?rv=;qZV@jZhBj?a!r(<%V;~CW5viXeSVq|2eQBrziDz$>X-SB zl?oC56|IwL4(GJEzk(qtAwR`=eE#}cijmUl7zsk_X>UGGS9)>rBmDO-CG(`BxPBG> z)H>x4!L7HNn$~(K-Pf{0NYeu&ne!}Er*==?Ur?wLX;^W&Km_QP5nbyrrErm7al4YU zfIu-AE2)bgJ=B$k8=lVafpr&sAPHMgTwVh9D|b8xreOVUdyXsbg)&?)YT=LW28om% zNW{RZ*+C_ezfS`!+s)Ypa*puS@lf$~TSdsP1<~3Lf2$k@Cxt(oL##G$mc!7R-8wL|!4XKXIM&RvN9z?vzE^){?50&Z)$h^%2GYg*^^DB*k=tL;ffWOuKqtBgCLAB&=k zed0ugM&Cnc$~)nnzQMlqm(~7;0z0s9j%CW!$8WWket&1b>Q7}Yg4*Cvp#C>f@xOorButUUy| zr!Fh3Zn-w>3zwzk3pu`3W>`dO@M!2oIo^T|dIT(Xgg zs$lqEu9iIoB=zq<0n!DL)t<2c%+aOLR9WS#MW&MJVl^&Z+j*(ZWTS%#B!JZ%Mq zx7z!GN;PY?_H^ilw_bk<;N$yJq?y8LB^P6Oil&(=pBN3Bp3Keg%#p7lso8pGS8ZssO#MN+={5Asbu8{WmV^!@9Zhr|0`~@ z`k3k$>`T$Nc7+*;?5(a|G=*;}R`iu6jo2TgS7&sUxo&?Gi#uay+T$;&NC7ziX^G~2 zyZx@}V^Sz*mFTuq2hJMCpiWA<6p5q!-;j!k5UMPZ{oQL@KXpd31pqUS#Bll}HK2il$;smMUn&0Y{>*VQi}%_!!d=X)qq$ zir!am9=enFUq>VUE(7q*E~*TxS5Kx)fU*?`N!FiN$Iy^iD${AWGVViBSCxM92IzI| z;THfZ@eO&nv5wQicjw;Y4&jBmj=bwJgmE#G=n}KSQ=>ns>?I|X%{H{o+JTkpvVLOz zuLH_RwW3~q=D2z`m@_cjA<7J0DqQ{saB9cOK+t6lt5`wOvco^R&c4xlGi?=P&r0Fk zrBR-5!HCL%o9S5r-Ew6{TOHWzhCwfSNEK1~7GT%4;k?~w&OluawLq-92!(NSUB1Gf zDbmzHEV!Sv&_t(t=mND*iU3=Kc-^7)PPKm{lmF>9iSo$-=OLq)uzM7OZU1&G3Jv*n zH_&m0vn0`}eQYL>t~Z3_tz5N5M@X^@Mn?cBMx#pkp_2`$onAwNI*6-<*Ujjg8hk{_ z-H-ZBOUIYj6g5g3o^mW^~Vq6Ezep8z+sNPm=7xfue?A;Me zDY^mK_{~JN+h#(sIcvq@I{SYOY|Ga45p5B6Ir7{s3y~NvQFQ)A_W`%`$d(l^kqowk zJ=860fveCsOy|QH@Y!@x$>`pdN7qws^Cm@}(k9ovHqJ@_ObLr$WmpIzR@63 zO>WI2uQ0C5A1((+`d%T58IjO~g;_frBI@*WrnnWZ$tn z^2&zR>TxN2HYD(Wpkv_1Hl#Nq1gSN0pv0}{=>`512~89sqp|;qla=gUX1!kgsl7Rn zb8Ng-nbOhzb2GLVnnYcK`N!~GEqcByepZ(}xy4H`Xam*oLqY2GwjT+LcE#sUbi8~M#JUrm;pm1E;hpw%T(H+TfW<7^=3m{`xD#lYA-syMOe{sg+Q2? z;jXWvobS%g!r{B|VuaB?%6}%+KSqjfoF(weBCW!Ku4NLwoa#qFM2D))iT@M*w^#ft zszkA86$kUS8L{7DA$sZ@tgX9eqHsp$2})=GhkHN^2nM1K*4zA(mXP^sSMY)%dWpLU za;MNnKF{#T+2A5gy7e#+@l2}O&R7`#PZ>WR8P*Cx}v z)=c>|%C$|Bf-5*k_{~qOq}V0UH*@|mx##@Ue9&hsH&6Lst*CfD-g4IT9i7(-8DBG6 zT9REXid99-<7PG4W|SNL0j`p9iVhCUI%SBAafJilLrxIS=k9Ole#_&}BAmkbQfgk2 zaJ-8@13fqR$EMH*kqG#RQ7gXYtR1EjR?Mw!q!}g-6$?M^xrcSZK_Meu15PkKg-4I)%>%>CZZsp3u<_?pd4a zJV@5o)>3vZ-Z4j7vs>N~ej^ix!&yt~ITC8i3WCuI0_(jz5WM+KvGoiFqK>4kT4skZ z&aS_A&2WfK6ja06Eyo3tpA+&D8X?|-kK_rL^*6M-FTi&igj`SFHFZ_}13p`KoCKqf z2!9a2b?ifN*p2$oQY@J6E;X7Lo2KHc^z)a|$kLXxt4~PG?QHzYyu6so4_*Q zL>bqk3CRW1Tl=c|U>h;i2*OFYD3>zuN*NsKx_O|g%rEdL?^*{*B<}uf3EWbRc@%4z zR?f?E#^l+ktUcKR+=+GRonuqWB=K3xbjCah|D_EdA0IB-xPMX-zJy+^W3d&c`#Pq< zMTOmYUxeMg{$qtZ`_Vm*v2#g`1MoDuP)UvCsZ5V zZ|uy@lr~FY&0FFSkCtFqBTRo?rwPw*W@{FdkTn%3F08Xgsx{dUl`Q=Q=gPe;+QqI9 z0ts<}CPGo6@Mull-?u#)JVH9Vh-pJV{sfT)7~rgY9b9O}o?ncIzZNiTGpa=O zyDnqx1M$h85}i$nlfIiva4r)>RU))1^fkVta>4fd6XOfpc|~HM;G;`m-wha!{4# zQZ&n8f4Cij@3wyCT+}izd;RNOF}r`tv~OEBK3f_K&j~3y>X6?KqzRP*(R2!By$llzrZ&w z|K51P4nDbtwz8Cv@jCqRc{V<>-ZPv-=kNU>hchH2lo_11X`^~ifYN}e4H!xG+*>OG zjnVa&G;WAa4Bk6((Yd*7LX7IiY+*dz^m|pdJrv=Vn0puORwrmo33%K^w_>s3QO55* zRo#)4xR2+NKrE(fzQ{>(E`DU~i@qFDlIKYsJ0&~kgy!_nQwFif6)F4>iHSL`C$G0> z0{GLjo_<6mA@h-?G~#-ZaF0wG4$=f}Kzk=IV$IOv>zpiDdz*)ZHP3rNv&J{GV1fh^ z;7fu$zdg9mn~i;_w$=ai_(W#>3DZW(!_ZAn?4ps&QA|DBr5}yng{nQ6q+i3}#@^ay zFgmzlVcO77a{Mea^gn*D&nNN8Srb~C5RJQk?tC8Adt1b*;KkhFYfr6>a^5k;SkPkJ z`Am^xH1#neqh5ybuQ8%n&BbL0demT=`n$gYqCXzTjh|d0K60SLM@qT2AAUXQ5klg@ zJ&hF=mlam>Sif~GX7S5n1#T;7xm#ZPmnvkN(Pzz@7_*mNb5`?zIE(+Wo~H(%&1;sp|1etT++Fu3Af@ z&oNcWOkn!aBmCZpx4(;A2wKmbno4N&P5FyzQNd$*3!qw3KLdWF-74<7%JfHFsw@!c za^DinysP0;f!2FdTUT8Wy6&oUXp{kF%p^WWZ(3)HC^eE0v+aWeGpUBAF7u zt(e=znViMZ5Bc_JdA(npkmjF7t3v}zB(5{5p{KjL*Bl-^bs7v(8Ng2XExe5OKH(W@j5;X zlo1(Ym*VVF{T4XRaWIftg%B*c5VA!qLG5<_tuX1d@)k?GEH893P7Ex%hG`;<^9iW? zT}hEY$B~ObDO6d!v}jNxudl4tRQ)P2@W*rH{e?V+_6kof7R)BUl%AzMaJ2oU%OnzS=st1b$Iaz9 zq!lH!TAzjrPrF7{FD4GZtA<*Vu}&49p4neQuEndv z)}#|$Fk|fzU5!U4weRR~b&c{&2;MO**PsuxFV*dPD_fu;MD<7OV*K*ox{9;6Y!vlE z5i!fTTuD|r*8S8Z2j2RH2Pjbg$)Fi(P)%%EH-L#eUAO5@nfuTab#Z51k}rsf-sEAF z7LBuQvQm*ifm*!sWAS*6P8e3O{RvI0T)O%z!-+QF8!N=Eso`ewcvgM4*D5Yi0ihi~ z%8NPmLm7jgs)g^(&+;ytJWhptz~d`0Mz%r1T9UtPA1i+JP*gA})mv(lfIQ<~uOCI) zntXqla4XeEOL{rR0Qg1{p&?~wz#7|2a;K=Adc1*N*&&l{kD)b$rz;y$hpNc#(iM#J9>8*~1R63NfcFVw1M z1p;O7zIO+q=luEOpPo)i%4h#-Y;3Fr?iFg3+2U?>bs~WIdvj=pRDlj~0#UUautJ}n zyny5qq_bJc@821PggudWUXXU=94-t=NfB#$gYvZ8NrKQ0hWyW`r>iHj{YW)5z8W-P zP_#QUVMLOUY>km|;D?qqfAmL)S!@f9Na$~H(-+iin?+m_Xqt$f4dmp~aVracFx|Z~ zI>U6k%0Omk=MdB0R+-_l?l?N%5t3yroGw;j0;U+aGS7y$|3if-b|Fg0nJKiH)t_tO zl&dQ;Xe10wI)UQ_!~W+KBDio_>IFY-SDV1&qA$30(mY+=z3nZs8G<=eS={g50T9et zh_SH@SUsT70_naG9>jvb@S=QY$iT%FTS8s~`C5SZ_c=%xhM(wjixYPH>6#*-$Q$gq z>Gr&^x)Y`;nR>UkN4cedEBgYZq-43f5jX#oqdrtXxKxI~bzM?OJ_W6^eFSJa72GC_ z53&FHuxgxol2hf90c)+4G_ zdS|uW5NON77?)*$Cp8(F>9&uG&X+0t_--}=uKC1CQ9I0xR4F4`*O%~6z22KhByXEg zU(9_uzE>6owZ9pY?FveycTmHFNlO0NY{qMNgV_94#Kv@(*jm^T+f}2^tJWqqE%m3C znX5r}fDbJoG&3O6f|c7$VjT8)w~6l?x`B%PS&1dhw~y;?=ZGa_W3iHZF)&`w4)<0L zrD|wNw0_sHzbBCIDH-&nn5@E2Io#GacFvbeP@@&PEogvryRK2X>ez6{yy5rU;ETIn z4462bpy~u&T`Lh_z6+w%-eHiD*sCaAyrti5Yd}y>=F-o5rD2R?wu%@XDeTc`9okLS zOurP8yp%9fHF!g8j`0fZM~1O^yb}LR?{BSWRdK)V8O`fl+De*QL-oE@u%<@+u?#fDv)IYaXaz%IuU7@o({6PnR&Y23T`d3sq}*}O z!MN>fNz_cOnvO`L7!4Wp)Q}>~F}s;_>^&-43WGc<$^xy@6cxELNB`^F*QwvdpHyc%eCWtH=8dpiMR8#$k^uE2$SIWI=gZf3 z4aoy|ZDzskF1=CGhWIRzL+)%BLKTo&ozwW&Pp!U`ZPSDcFPv3@?v3Pn3M;a&ks*DX zr^%fyfz%WwUns*14586EAu>Lbhz3YcBI(gA1%|PuKBH_BGQdhSF>1rP%R3Jw;{KR( zS6HI#MURBaOU}~toV)%N#$@GNE)Xbhw`fuchN_S1f24lu=Ym)BdcJtZ*Jc_=)zwaJs-7yl_kW~b5~|k1Qx8=Z z_cemNlX_nOMT5vQK*|yNoT)ILP>~7$;``F97{jlZI126bM{LQMhq@B-FQ)zlZa7v~ zWBH~zlMYDv=&~lHT73TE_5+`6z3cfX*#UA0FCr?)5-3*<9_(&z!RSsJ1PNGcgmO%_ zoEqg|kT@nTe#Sejy4TRq@OlK%%f`+pRprhk z)DGE#U&hzGJJb~NY+m_Ju^!M+qJR1k^BSoYKKILq1BnmtuMH%ywegK@7&f~QnSQG) z5Wp*FE6Xc<$BX&>LlKus2kA3?LQKH5$8?+f_y{^Lr5_e--1!rPSI}uJo!{wn#dA+~ zJHyqMq~2-QCv8_QN1@{Fm;6H9+{}&xysKDZt9!Ow3{a6Xz2(X*%>9v`_$PNLe0b_( zXh>mP5ozk`*3F&)0Xg>GV4D_5Uo8U`YKfta&R*2 zV=RULzMO77$}s^y10MuuQ`8+Exl$4j`=4VKe=4~(Fi~oRefGq6=lD@vTs+Sn`8WW~ z6_gX$oL~rYeRf8;Rl-Y(8s97H;iyLTgVXC6Ay;d-G=GoJhKcGw=!M3#uCFhuBAl7i z$_~!6Wdu>|GFU%;yc zV!~yw{`|9A>VBb(snLcDqDB$cv~?Pgrttpkh0wSBew9HbJB||)9MzNVdm|>?V{jy; zba9%GRyGBfLGA-9c26}IJq2tFp)f*zdW(Wzhn=>ABE6N_7KReV;c(OPNk#svMxP_D^V=1J! zTC@*?D3ig9Mb1ciA6JM_0h63l`GD(Ex`oels3doN z{^SY<;d#^N9ByB*9dL6xy+i_^sISvHdJavgBvo3{f~^@1S-d8v8`UZC7OcPlu95|- zu&E&!2YmkCs$FH=qFp680uMhjNPn!o?{}aX71cUvFws%PBaQ^EdF?q3LI7c4$ro0+ z+h;9Gr*?<2_g~fGuaB%-giql9eBauad&`NkM8sve_+98`&{OOc6KUr{~u5 zB`ZCATP?-q)n>MA)6rkak!6~-mY=_TQP?5ow(MA2(>#`q3Cm{OR7yxseTlGynao?x7qf#KD$QFL)zo?i80=`E$VshQc< z)BROQXrseR;st{7DLrFgyC}`vDwXgqoyiZRlVF0(<6w`vFAEBU3l&7%@Hn0UUEBw+ zc*=ExozpPh&QZQ%krMKwZ`zkBA1I*6B*p!aOV(G%Pma{Ohy2aM93_)NaM&ayC9tEk=6bOACST>`)SQaq zou_1J=;=%D?b;=Z4z3T>#ijc3k{~C7QMFdSY|IowZYV5T2u53d!kYKlnr(_&jXBx5 zmCu*MY{j~LG&hR$FwdW0FC@zON%k;KRFr&l%SFb=rH%(hW8b)vx3#rdYAo#-n^7?_ zN#DGSU-=dj8|ydn?PS5iC?<`B5y$kD&3~E4$@i*YqGmoX{XMc3{pO0uANkl)F34F# zM|DNCm~=GFvBvp(-OAUu;n;E;fisD2mF&`@8$$ZTYZQ~O`91MBW7T*pxbw_TlM7y1 zr;8AwvZT4D{=}rO3E*ge$K zw~GAl*Wb&LI{tLCFKpbCiwufis;Wo(6lWDnRAsp9g}OF58=b*Z`K-l663r2W+Cm;< zz{G&>3T~6fAx_)=gq&5HFGjmpJ6`hKcJ_e|7Uj2zpmG7}KyPCTAaufmdkzE#0M{wQw0r@w{Qzg|pt#&L;=+ z36-O1UQ~`bpdTz?&qvHh-rWb`{j<-4CNBQHWN>(xJE@TK>iSwadONO&6Wn0eHYDWo zzb^(=u{Nv#rvKn9sx6FxJ-T^e{qDgd-d6{>Aq8$2wG z&bV+zZu#AS45z_AkCaKx6Wg@btoLdt-11f47kl(>kBqIPh~c? zQv4(01wj{k&I=wbKb4O6%)Lp%|K4ift@wPN_}<{)M85fVjq~5HlaWpr8~Dcb{Zzby z==Y8Mp9LWW#k^^wK)MWhEh&hpCUgjN9r-K2^tt!uK?Z--fN3sA9dv{(KqF86RT`00XXeWD?imaj-twi+=Ck7$SUM@U`o2qy-fa&wR7q;_kGt zv{bwU45h-x1THQv@X=8?1;LoYV}ibCrC~2hZL76fk`MEVahv%h)$w|}-s~_(qK!#L z0?YG2Wpbt3`?NO5+`9(*sea%t1{x}ndBu4$X>*osPJ67}Y@sqhO)XTzI*xGsc!-=1 zJ%!87oEE)%Gh?T8Bs}%rMJ| zEaqujbpPj8rfT9IP7mN(ugPTN(mRAkDFCk(zfwUV?IlL8sv$qOG+>`C(vspLllk0AIK?{^?x+z1Lr+S4s24zd~7NC&( zK550N+8!$BO52%ZD>|Zi$Cyc0(LUxd-V)$mA?hdV!S#PH-QV}czgu8eXK09>QN>$% zd@PHJb_172TU1(^9|Jw!);N6tH$9v@&kAJeW7f1*!2G&FRy5I|Sm=^snYTF!7hv&L zs5r^9Sy~|}KFrHV5EFzitnw9;o0UB@&H$ZC-?E$-+b-5yQx8wo=an6gdw3<8qz=!a&vvg?&%_6p}wA9EUQFxl!b=IO9G3v|L;-! z%aPM*mL_hzpu6o?#xKtJQBY;2!cF6@*Y+M9(U--*BTl6e%Z&G-OZLS5^;v2=Jx&$_ zgJVj=f0NX{ad+1SDS>&+ZhMP7Ea-Qf5ZQ_yEw%I4WJ}_myPDV*>n#b=6dLRnC6i3N zI9V;29^B2C&A>El7w^(xL)t=DGm8THg@YyMUQJsERn`Pp%Kxw*vBD$;2@WwTy; zV>*_yz@RgU&&V)gRxnWoaGx}Ebj5$Cy?m|=qW2^~_x(GEs(fQZO~*MAD(Fe;Ii=jk zwY2i*|NBk;{DRN4p+(uolN63jX$MXoGF>A}=H6_#w%|LQg)s zxF`;Ez(oUkdz(<9kQ)aquz>%nVYCY^_9HsCEB~6+sQ2?R3q#7_bNfA^>bJ}QiGqkr znVF)i$CQPcMTStci5{yJM~X$bXh~#GXJg_MQC&sN5?5dDZVB%KJqjb9DggEBMkcD`HkI^+&&ynAtETcP~}T74$=wfk5XkW zZ7aT{J54V!p_+LsMLD*Z0zy9JYB3)lm~XPT$*ru5W=p-_ZUl^lr0UXHyvlyp7^#ut zWi+m{=Egq0n9wv6OE7+Mse{rMT3XH)7wztiXQ?>>QuNX z$Emr_e7TNAGjP`5%!gFA-*n?L&GBSowMOvax(U_Q1!;accqTw+i6~uqjAO~X>%r)$ zb#>-Ju^>p6ulD6VXM~KcL}q5@z|fGQl1Z1ti-fFo*X6iK_hGj?lEoq{v|RVR<^}#` zIn(fcgZtskL9|O7hU6Du&1Xqlw>G5LKm`rDh)?T64PAH~9Cia(v3K^|c6|S50(f&v zC%C=0+nt`%&%jR%bMj_`t@E(xB9#$oZEg+Y09nJn(6nMsI@{w{-PqzZ_Psm&z~_;l zY4u#ijRNK;RSNR*Kekbc7&}(eQwyqIn(z6F1P+>AxG1>gqQ3k;jJaeVuq z&Cs*2>ssqv=Q`I~kBG&PDcKfi#zCg50BeCbUHrE}UPm}^UNM~HO-j#9;sN!h|J+@-`R*&A} z^f#$d7YV9a688xDGVPZStP&?D=kMP|P2UNPEdQQr86AjsYt}ZL|6Z0ZPlp%h;=`Q} zToDT^&J)IOw}wfY8nqs_W$r_$%AxZ23@>OS(B@MHol)=2qF~_IVzb!54Ai}QcV~(+ zueJBX=h28w$}+u0E2Bp72%JT_@&fO>B7PE7%7^376hS_^Yg(-o*_;GPV4BMRb!|tu zy4L6=hDWD7Q;GF6z(fUxlsvl%5H%JrDK5M4ZT9^=GN3oR&z#%t;hAWt2ZO@kx|q|a z?k5wfSOU9EKhkTlhS4OIHLJ=G0(MGGK~i}=*7SOgtZ94saa9MwZ1+rS_QYC5zth9+ zEh6W29t2W`I=w_#!73JGtLp0~d!Hs&?22O?8&U%O?zeQBA`XowWPK(+1V}|$cFXh`G45_q9O<9Z-B(HJqs;Jk= zjJIT0$B6e+Hj%AKYUTd>jEeC3`#QplvXA#!qpRNi#ALtRCJSg?3!(jL3?um*b}@bM zxq`GKJNwfcM2f{12iRi-(ZCv15#$);+pso|%Qq!aF|&HPLm zif@7>;~l5a>d$76Pu))^Mf)J&gJoHrWWQ-DwGy={T*N+;zA0SMfW&lF48 zQOf?x;N*R4u)|nGq9_9ZVX+LjdKFj@$0a-t)&d4GCZ^eEX7rVsploZpWHkFtyePv> zgJjQ>n7>poKwcDG(k!jcnGvl>M+E&W3qg4wcG@==4322MzI+;E$RARx>*0k^x(yK5 zF-uAOO!h6PgR}X);N)vNiQ+cQxqBb%K=)cRYG9)lbNVZ|90bnaBA6W8tiGp|ohLvg5A+jC5>>9e&Kr)(HVjiW&1x2uAE5Qi zV-)A6W^>c~+g;r2v?%wO@dMv`Wf^XnOsgW9XOEcYU{-@E=Wkil(9Hg@`G?B~2m*N_ z9GSyttsBqr^R;yw>2hwaq(HM>rchW}iql;JGfY>XaNTikAO?RDl`$zCZgq1}vR{%V zNk4nCre074x#5-cjS<-0rbGqq>gfS{ljpa77m7x~ zY3gxua38n#@-*3xw$q63=FFK~d{5N0CV3=IQ%T$m`mqR4nRS2J^u}`naqHc-u!XVj z^!mSt;eYNzZ;uC2Q%tQ;tByvim=yMtgjq9v-a(_9etZPvoOFT{!Ndn;S1#}~Xc(4u z>6_v*IK<~W0HKV|ZHrTytDIh@opa17XV#I7!Oj?j?iU3*-Xx(p(oQ+nII{v_u4C6v z#v%b&cBpLb4k>)PuyV!MW)Bs9UH8t~x3c!eh7biHdg2Bc<*pl4A<0Xg=8<>=1xkt*EcA_y!Fwo<5bY z=ynXtz&FzJvgq~03%-@kMP_}bC&e;vXV!!BGeq6W62 zHsL;FuCy~|1T^;>u4(;(winQ0sow~^q6AfJQVkci z6>iq+N|RdE@$wfFGpf&=*U%X1#^5xKWvhkN#Vvwx?jB^ZX+g2a2ioTYGFFzKr|l=| z6a@CIa;4qr2;QWAsOKt91U+QZYBxaWWnq5r(OU@fz~StC`A2n9aVluG(Q0voZ>yN# z`b9ORLiBX#t~I9+-zV){)1DU|vxUD^hB@DIC0ZL552#J&iq?#~Ynvtay=C3cV@DZH z<0@y@NHU1l|7!Th-#>q0mmA=e*7VP56SUZhh_AT#0mfI)?fmTZ#h`r0ghJE-`?|3d zOUS5$+WQ`2ijIw^XeQlu&J{cD<1f?~;gY2pCGGIQSXnc9hEdK(&@BCr02*J*l#kJw zF5?l!xv~Qj(suVBE_RiyTR}x_xpbYuAR|t@f%YHU1=FUjXH0nm-eVHj3l5W^E#wk+ z)Lt3rM_PLAG39R?9y&z%O@7RSMsuV7j0l&u4^RsGn^P9JNPePrMttmODA}n8MSIt+ z)%o?QK;9pO{KCp!E5CcZsQc<)2lN5%^ORzygx8A+DAV_t@hWG@d#5$S35uqe2o8f= z=JB?=`gwNxIm4P2qnh&pCM0hP1f7t!IA+SbsVs(T*XZ;Tg)2Z?o(WN`IaXe7WiJ&S zu!2nci8YJ-tdUB~%e3liv^s@l&Qkq_vWz94R~z2#gxuGsA752J+MgO%2*<_nK9ip| zlmkV>Gu>PYANh!4ZieN~oJ=yZn^xaveT!^0t}p!%Xqr(>A}WBK5EKpmof##^Op>IE zkL_c}7x{>Qwh?=Pwl>RDPDsi*vm7U&O?%BT1&WO?m@OR}N^E%UM?@!iExC#G#Us9+ z9K%AD*PR{*hYDWUA+@XB?6mHBu0=;QCeQuSGQ?LlEFS-b5dX(j6d#%hO=p)D!zm)T zc$xrR>RSkdX#n799*$ zw=zq=X%yyj4ev!q0t)=xg6MRI3Ae81qG&^~7u!t`>KrY6BQLH3_c4ZMYAlRUzF&;} zB#|8E=Y0FlrKbC;2wR{aJ*Ms5@b7SFL%9_y+H2P$lm|B4jl%j3@tAgB#Luz zxIM|k@Gf`3VHK-4<==f;6w@35kBj#OP}1c1gY_tkocE4q_3T>j@ac4HO)AEf%(yyR zaGp-}Ig;0?ndT0@5uFN=|LAC*xi?p%cK%{+!m%`NL#~G7`Mce}#C6VGhzJ%r`Vzxz zKVExz_~FAbu9;w`RAiw#MsXp@73wX!DVmJPm_Ot?P@F#Hs#uX6>CUsbQckjbj|oi@ zMRp~}tf{lfOJ#XT7;3x7Qx@PResDNPo+!yZmDEevzHzNE0ps>N_P=z$c%7l@`O#(J z>9)|Nb%5}#+lN|sV<RCMYM6vxCk13D(z-;|H($Q8yN&C-#By_krcCc&{H^AX z)wCPtZ|!}WTsZv5h|J8Gejl#cGsg)x`T1(5CcBNMHAS|800D9wz_P!Q{=nwsBP+*>KaoCkh9o*gA9DER4$PZRlq@jqh&XA+~;@P$V~Y!)`r7j$xpAOC@q zkTWaxh`?0`!R!iqb(8(AF=#xb&882{m4@EvyDyzZM6XV9RDp;{eS^E}*)O@ShyOdMmw>gx2k_?-UJZDm z$soHi_}R=EwSMXH>TJ5)7o~&*i%e+4uHAS+eL663T6qWvLW-PfYHK0+MrlH#aZTi^ z^N^hS06sOBD@-XFYlHhbCgrm0g{vLj%GDbonhi$}d;i=Rb@3q{=?0y9 z z{h;mp`O7)0{B#}Hwz9_h@e7aE)8pgU#`DMrTE-Se@7Ny!ES%<(l*Hgmt=6i80p@PZ z8`%d$sG}!S`;yTzid!5fr}1vb&l>_vq~F0<@=Wl3cparikprd?#o5qEPx-ZY^DDH@ z*RFvopBv3z4&XBK{(;wHX-mf&HMY?}(zkpryF1zu+&jxuE&-eV7n%?<`3LSlG~?}4 z-t_Ggx=>;$2mK8espD@+f?wwCobjM7bBv3~IM3Pa(K{>$3A^%7Aym z?1hn(4*NG+EG#_I;cJjA8!q1kfXu(t_kU^5u88axlaSGDAI0d zh&XGDAIlUOpOiLCF4sDwy}jy12_y2O29s+}#dJz7sd#`%*j z0*Yu}TkU&XZ_0Zr*8EMoC&-o0b(+Y2P%6=XVS*sv%hA zW7MlleF0st(}+;!oGc@b%-GrN|r6u}1&LB%cPF*fgxJcVo#~WN|x5ADjhc-q7~jI`H4~ zpnVuwXsZ0LB~AZp|ErcV@>7@XfMYfg-K&yC;;fI547H%L_LPQ2cPzW00>E%j6`;4U0ELY+vHZvi>}Ou-@O_L`zMzMY3a9M+GI!I zEScQ>d{zl)+JKl__tzjw2a9ic$v8>U1NOyvvHN)^pax@6@66GXOREURkANLh$_XVH zF%kTK(bziT9x#DELoS08=6fbJbIM1}R#gB-;TWuQ$xK@k9e`S8rL+T7gw;ffC<7AU zwkKjR4uXcm(-47g#Fr_TOL*Y};}}eqP^<2gK;;6|sybo(-Yw}R=YDvm)v~wetFh)f zM#@8Ge3&?M$Inqy>*+>ulULWC$AFx)__0p%3o#CPBm=?)y0HS)Bd+yWqhYb zHSrFKsEg*q3Vg){;^rg7Ex;i@h&=rhDJ}F2^ zNm&Fa0!|zSWt8?rumzo?C!nCwQavspflT-M^=qHgA)(O%RnUj+KNun+BCf8k9YBNN zl1(7f4}veXL6}v zCPZ5qAVqR2Ske8XiC~>V^)tbd@S>NE zqTAx%X>R%AmJxIpAkQROkNH3|tfq{(U*2;$F`|r&El)P=$vd>K0HIrnl!X;QwY>ko z{W4=t2|~L6ex5br^*NyR7Y4euhSh0P&jgYlVGLG?2>T1tax$nX2o-kLXG!q#)oA2? zA>$oKhxG~E=aJ8iPsj!vGe{^a+idukM~ww)MpF-ie0fKn^&jkCzrlUaZN{xvgFjy4&>RoOSJ@Z2xnf z$Bs2^qghepuJZXf;2ZxYMAz{4Nk5)y;@Sy3mw~bvm}NvqNBg-;%bITnv6@UpP zgl-t>Y6;XKeu_qo4@bPdRJVs+tPAL0XUuE)-?v^HJ!Tm6Jsd;a9wA?Bd)KEZ{>#k# z^HN7i&88w<2Hws7i&kB(LWE8eq=wjdrdU;t0mOc*w?D9f?OGwC?wpv-HQ;ys-hgXk z(29?AB%gt=8!{m*@lHZYi0(dIv^Zti%l>6zd~;pmIS}USh#3s42$b$SSw*I2lo@BB zp3ydoTyZ-Ns7;m@`%#uUWf#^bo!1akMzSksLgW>)lWPEiz1paUNy(q4L=BYaNC>o3 zwx(=E@_YsW3FH@hYQ1HU4Y;kOwyoe>aN5nla>LO4;Us7Q3yODmFG}iI(yQ<*)q+`2 zH{V6%c^AI=V)TPp#hK%kS|9&JH=%)|ozyuo3c>1|>W#)gVRsh%_s9^E`I;xYzbZOi z*brb~ba4#ivbo)Ey5+&Dms59EA}|DT_q*D7LlI)?Vc-M7S3ScqGj7~e2DHdW)MKQo z4m4fqG(2*2nMdn;Ja%h9dqvn?NG47kLr;Yu)r3n}!w_|~WmixUPCP{=^N0|pcchK^ z7MGaowm!igW{4(h5woGr9U;Oi<-90Cd2Me>g22E(XtXDHzqf%U1c9C7t53LR)Jk@3 z58yPk(tpKzI%#|t)0JjsLoe56{srKQ+*`$RSRHPrU$6DVtn6yg5F!NSvRkin)1hRT zfry+6v%s(^`!K4CcGq%U6OQRpN{HcN@a5@<)F^+QNbIc}!NvSI2@)|i0dLOLyJ+~W zHV|Cd%1R|v7Hu;WvTWxl-75%4npT40i;G7k2eE#^=yvnp$sZv)9f!W@h4~2Ji!7y$^jXJw31$X)PKlOMM$vHSZ zn0LT-M3%46{2^#)nAB`E;A--FkYf{Ca8xo$LEEnC`r*baug7+E*lVEaFjdh~e{Pg_Rd^2%=115f1i0g($5zESY0U1IJh!wBtude};ZTKPxz z@47Kmc2iZ7V{0@TwKl3VTRK{66|)UuPR{dx_6}~AGZH?VUqC*lq>vvtEfGqUFNO&^ z!;4Uj4wHB^q96YD%Lj(8q%~*1C-ujf0Yx)%Rjx|<BhIQ+&#hi9gLIi1>vSj8W#C;ztt=Y7%sRyr-rs8=3Ry)L(}Q) z_g|)7$Lii4OSfIlvr+e91iTUZ5mjBTAk~cPg0{pgDD|RSTd=QuXGyTE0b}+vv^|`@ zCMXIb#lO1}Urcffx}{SI^d+;X7r@}ad9qW>G#pGT+`R2(33Ri?x?|a%RB?Ip|7rlT zXPxB!x4t&IsY$rZ3}!k>CmEoh1isoJ*OBx+$#Y=!tWi@qYIb#V`}O0^sDkQH$H|7& zGcGPVa!#g_mZl~q=Q#@JZ+s=0Dm6eU+|yQXy4Qw==~SV)(V&x4cM|^-^$d|Fd_ZIi zXl;##v{r{p!`67^ij^n(7d=D11gt;|FAyih6Af=0>bT13lo@*vzWd3N>-E1KlcpQ( z$7#!*W2aas|H{%Tm01Rw%FVKwf^Uzyh)HN@Vray?zWbhT0(n-Q0iy;dO^+9Vx(o=4 z@PVM{uSh^i$v$oBWuu_8Vd>RyX6wW)ujKfVQ}1%;y}Q&*vg4IB(4%FkU1oMb!6t$K zl-{iakY6UnO3+Ef=}oax5>{CK1-6lXg}N)jTax4bnMZq_;P2KU`RowEQN+>juW@cW zPtLmVqvdmOiI&HCYODK;l9q3IJjj0(-jM`|_&sRnaZn!HNs~=2qUn)1?Ojb8G7R_Q zK)QPE>x-kRk<|_%Q7-ClSbHV(h2L`uQq{{Q398XAkNWzQw+`f^{#FXGiG7=GEyZm9 zsIH=-{a1sq6p-Y*_pjyDZU#Q_ZoEKMF6zCfq@?6-M95z)nRd%p;XKOd&aT|(>JQI^ zzb|s*?v4EX^28;XbmkE9@zd+n%Uk8t)9V0sgIhE9t2(+}O2)w*<7~AebHQJfdRrAXy^kxUb|IX0-1wA=)L%=}e80Hq5 zzmm6ibV2A-e)kwsr?$~{#2rH?lw~i54R_bulPic8bpV82w{MBt$YDLMcAMT!QfqA zmB1Y-{oCVS;dl%F|LE@j1-}?uh#Kxc=YAT+nc{^ea}u$AB6;{0C$nX!rxx{exi|~| zXz!ypPqPsh|B0Jiu_9`K9SdX@NLCuV)segLCiPSWJ0nKm;hDxj6uFmOIVUd7EFMPB zNz6F5^*^nk8m|7;~4c?~^weI%7&8JL#O->jwn;`}Ml^wqA{stZ>A zE+j=$etOeOEW(^Z?2wP$2WUZjYI^B@noSb515&f-_pj`jEXu9<+%Y(!XNhz`*o)YB z3F$65dG@YmR@U+ea5PA z^)G(2aT9$F((tgQrB^XaCx$WrK~iGoOPDkH{Sp769-Z?6p{#}&n7^sEfo-6HvCiY; z?(|8zHAE6lQ9?Qwg8ATLJc+t%>UXogC;#ko&>qe5_WHe>PFtyU`a)?*B|sloM_#?F zO(bp@*M&&FcQ*uHEfd7wMpN0S`aQIy^?OKW%hg$C^D3bX_T&GzsFJ7TpQFb%V^VAT zt}B8vb-b(Sd8y6qD_qdxb~q9$4icy3Z0yD&qYwWE$_^P|Bl zIn3d*0vEYePRo7gN|oNKl80T}LN?|KMXbgP%CYAk>?NuB$k}0!wV?qRHjCsoW#td! za&(kEJ62|@2&E_A&ej|Hkd6!Oy~%cz0RM>@t-T*I={rltAr^t~OnM}xw=v;E)e_i5 ztTi=oT&p4;`(#V=>`G3oV2M2(rm3ZC?kv6h9A8p(v@Eow z-_LI5N6>;cNOcUP-{{lbUf`~{SP7uiD*9mhv#4{4($etqb9Dvd{Z9WeHptE9k?M?| z+lJKElBDsUo$Bf1(XFMY%@`k$t(Gy!#(4Q9O-uhR&0OQ~h21T+{~Y5IACa_X2T}k} zKby`V27&0$?HGsYlr%hEY^9%SfBQP4VpWhj*#fjM;hQY$ugQ!DbkvDRLCPot2ZKoi zmU5@rsrrc9uCMJTfF>rdX9s08rD)Qb#y`md(4WQClt3`@@-5fR7tvW=fN+*SYZo?# zsBr{vFmmaEzD-rOJ#agZ^Qk|8ObPB=B<~va*OdQO=+{LVn$|)_%VK`8y&xE3VO!wY z6FI^*HK?bMq7{uujs820UQ-L+eJXs`ix*JsK&6`x8mgQFbiR%}UQDlukHEZ`!=rST zKgT45zpVxTiIo_w)l=tpn+fi|Yg}W&zQ95(8h-TbOk~+IvkYx2Ef(5?u*lB-Y~3+w@}8Jc-j77e`z$16Yp*?h z9E7x`d&M-?&y842@j&tvhmvG zewuKNZAwYW^H3Y{(8DQla2IA-#qdL~m!2ixmn$8GBg%WEA}V#E0Z0&^ALN%eZ_n7G zkRusO(h=OWC*39MXX_ooPwOkNvXe_%MSw~tE%-qfsF~jFMjYbr#=&{xF>5VsGei}0 z^s2Nhnltzz_>xk^-sNlM9L@|>{*Kt#Aky0bY_Io-&UyZn@p!#NIaq%LjC^(tp^G8S zJ{{eBGJiK|E`GNd^KdHt(|hHMl`F3I?_712m^RP%quU)?==cOFkV11UP~n2%fvA~U zj<=Pi_o7)0O}_~SdJGn!9DN{W;kfXv-C(81D!y8nIVRaXA7|rol;g#ymD@i}*H5_I z^I3Gq>bMT15OSftMfwMP#trNJ)J?&>G{m^SB(I??@lwt0HDBE!D*ZR;#PH>szY9tI z>GK*Zh6CcgI~|?T810p5%Y0+Lwbsq1UV{S3Wc5_J$QDcz9{hDxBLyW$j z(Q71~26J|Y{Zw5xgQjb0B`Cvm!lyHqWG#M6DK~HC;gOxk32{5WqqtpAl~dKx97}Aj z+d+&}z1wxID~k8f1gjXeQ7>_(74Mf@=xlnh{)cEvQZG_|^MQEcj2b z8tqOVl5DS&tbsa=n)r=c98Shf4Qaql$n9EjGR;VBy5^KbOQeV4%b$4x66#WCrXsW7 zqV}wa{B~C{XVNjX>-c7Cm71lJUz-&e821&oQnOc;{#z3Pl4uy@Q zqBi5o*DortN#~{NpBN9Ev@2Gj13hCpHwF#q)Exq;`TOcHg?T~HGqZUI{#%5?pOcUAk7b7KW9ir{ zYkO}fF0@@PQ%JWwR!jXZ^Db{DEnm=P!%1l6VI5^|BUDLGWNQY9-e{Z%vQvv=^2j-N z$1i8Ucqq@bNt7L|D(9TUlBSM>^DOXhitDteZIu+5IoZkHZ<=6ft(u$#Uk}G) z0?NTCe=dWJLi?o)kQ-+)_4|I?D=u5(Lnb4$ZzdZp8bOC!!#xuMLPBearCx+5nO=kz zv9rN(HbHS*#E97vw*HtK5CgT=(-E04v;P+9-p1LlXi0VsKD@(2E#S7g5M}LTMm!lA z>gmt9>&qRi_@Gt-f$4168r$kz3S_tqmuJNkaTToHjI_T>&iXynp9C&VXc+978<*l% zn*O|X`;xCBcmas^Cyjg%(dD1olkQCBn}Q_HRn1gdcI7)y;1CO*&9#@@o~w*9lp80M z(cZemudC+i147XeO(g$yaV-M%51nH1UsQimjD2lq_neoHjO5WW(0&S2yL9tjtq8g8 z@UNe}fKkk-s89pqGg&n?&eb)K<&_l-92}hW%}quwF5=kOSO=rDv2mo-rHP4&xus>U zbD|anvD^A@lE1ZUV%`VZ)@&d;I=WxoJ5keYnE&LsNOW{WD4QN3`PxxdBv0A(Ki;Pc z3~})`{%Bydq5D_1y7`Z6b>{z;t*XYdV9$?Iz7E%m4YC`PnG==LalB!E3jPjoQPD7V zCo@)I1s5eC{7dMlI8e{^KQ5LAdNF*X<7q#lXp7tLd+Uv7_H;_8{M(!L2#kRniK8ES z$8hgL`eT`b_{CK5l@syrQ~O-1`7~tY5ZWmcv_kJ<SpGZFFwSA`v?)|FHWO zdY!vcGn67Lw7`ftx*H@>CAEKacQm?mW3GGQ2cNj_Q3#8UiPVbEmqI3fVv7fVtW2l7 zGM9-03Mw79=!CN$#VnW&_RI&LK=&dW$q&b}y>=!^Oyr7fT4>2e--Iv^xqULeEgLoc z77_DP-fXWkZQUuCVbnSAx919sJ7`mAhV~f->b;#*5XHfm(E|TI*1E5Bv+#9S$`jfd z@UvzJRcve!+~_F(Syg-vJs}nGlEtgx z9Y$!Vhz)3p>-mc+Gp9FaEBZ{C3*m=bvD`t0S=}cRa2&a{(f5x!CrEYL9{DI9-GnQ! zUu{1n-s5Vt)HnBapG2+kxJ>dO^8~a|rWA`NE^aSNFaK-X7fR0M4z+@TO5Fq0+}Z0K zXO5=&CYs=OyupY1jh8=@W`lA&~>uW&+BJvHsJs!7+*11KhW}T)`9gD506yEC~IQ-S;;L35u(zKXvsw zeOo5(^Wu%va@3Len^E{PV%8}x-kM{a?}(-AT$0$;NcEu3oq$OVy$epr4h<%?X;k;O zVXCA?mjCt~aC`A`%lLL?-Q}|N9Celene$B(u3z(S6Ls#*XWyVwZa7n}NT^>B8fx zn)CIS!5Y!Z11OK96D$9@_t?upT;ZBcWfhJf6$s?~5*bJkfbSD9rEx~c6RX;(8E`Yj z*apqdW3NjlXds=xBU%)4DBrPE??}Od$-pN_C`zDr6=RhF6%7GVg}|c~O|GHsDz%!L zege`H;k`(yJ8b6~=@{Rik7wz1glj@i@b;A_9RUACgK@W=L{aIS7l}yuzC_J_Cyy_j zVHi~m&W?MYVw&3Q%G)VnS#{nQ$#WP#sy13%@PPLA9#`N&Gy_@7k1sH>bx=wvGzGCl z75bZF%AdEUjEZ@KjZ$yFb)>7K+7Kpb2^QqEV7(X1lg;KeZ$Ft>Z4+gQu!hP-yI1 z>6#Fjmr>~JV{Vi4K@{iEjpbeu!#4FUG5Nq18}ox+L9U=6@axx zOGZju6KxU@MHJ7F(J|Vv_kKO+^n0x+zwUTp+4CS*KSP-n66DA4SC1D~Xw4o4w0qnM z7&P)s63=^*(F{|`e);SrDv751V&QOVxIouX?MuRhOeUDr(-t3xAtWBAa}!C3hIPRF1fatiA*o%U54P-S6A8=IGGH@Ez)t#>#Lh%4e8tX&Gpz{I>@TBBV&EPg1s?G z{PP8~(IBFm?*?Dm;~3q$#o*p|V88IBn#@xdc9bC_j+DfyWb7GT)DN0n(_<|Wgl(6l7w19a0*=qY#_oujHgF4t7I+DfE_V-<1HY%6`r*3GnIUyH#5p6wgZ(V*~gwZq;N zm%w24i?1IDXE6Z`@jA?mUl$!HzM0KiQptEkhhO#GjDE~}q!%@=OI1JJbw869j5Tsb z6xK%_s(P39VFN^{boqXF38xhC)o8m>i7uLpajQMF>!Vjz%y>{M?bSWW%Jw)6 z!g}`;PIj>S!yL8kZ(q%Jww`6Sx9?3CJ=H^8C}s70)FB(~-|-vPW6n4QnNnT!$XXsD zs7l?8vZSpab7@sfYpN~ST3n5Eb#LO%-7cqdw+)uG?m+6Ti$+)3Tijry(UDf$ zU)XI&jqe|x@>Q@7MF}^cu~ZscB;cXM}kR2ts1f==5$G8-K&|?A)ejk|H(IdtI?T06aMasRSsk|lRh7*FO zW?7U`y+RhV{-;%A*Dm=0b$Vf`=|1ZAYcFvrky&@G%IYA+O}#T;Zz}}%kV784Z(DFl zcCX(n6THESssHsuOyK@uT*ctl@Htu4J0&o7KOy0G-LzBS-hVjHqOl!u3rvex+K*bE zTvquk&wzF!l1OP1?~{k(w~lLr2OLKyC(=q4gqYvzILqQh{2m3X&e30YaMscBJ}5j# zN93jQ348lw<1I=BTvqwWZ*RnmRaLTZ5XyzYH z6u+b@24~cSdaEi|+|>%xQ(n`&`C~f)-G=`mX2Bu5O{Z+3U3*!%sCpq#mA z3F%(RID4#^jv(``uojvK3phT8oUBMwg!yLV2ynbSx$d9ivvT?P+FM`YT)N}`tfK_K zS+W7z9EBIR&`}Ww5FCm#&#G{_?MpnSgNZ&i2`R(8>Gq6SnbPu}cy@Ui-pX}95;u`t zy56$p3|jG=hkdbF;%UGw#RGvlQ9)A%inC6AaXW0`6!m-8oPn6c-rSh*uz-pdp!E>0 zUbFqm({+b2sVJEckcL+fnvMfn-ewv-C8pkIkx6ez<$+p-i-N62?$Z+_5~ z|L9Quk!L?Lq-v9Sbv`c>ax58YfX$wV1p$1 z#fbW=N|qGNps>CLI&)OPGP0LzBT3av3d_Yg;g1>k%un|{H8($1G%hN{T$(@-8u+5> z4jyjV-#X4c&t|8TDjquOIN|D?C!{_L@O6LI0wMlan)?|plZ}~T4&FYG~n!4v1zh?oe^H=;Y_za3)syU72pVvbuoPq#p4KJ9{Qp$kqcI!BcO1LD=ASx zYu&|YLhBFHnXAlF=U0~YXd(Vb{GBRd@KzKsO>yhkL?~M7@YyROVUH37k(} zHecD^AadESweftSLsYqpvCl^pWU$1r&FjVaV4mD=V*CBJ_i4JwkI9J_J}MQ=FHfkR znELEVG@lc;KAz!Xs=7106t>^mcsp~oGyQXF`gH|{ofMkq3BSvzPbU*QN6>yjOjqg3 zLh5-Rllat3k(Ll;TLdBKOc91LLAYONTB0@H*^1m0%JAZ7*JvHC4RWbdFLBJ&^|_3( zPo3>5s+lSwr@FE~^}sm}q{ORDLJp7wIid~7*S5x^(n*(HWw@Eu%4 za>-eTfTFc*%$p`9egqS@#fEELo8eKDv#4V`P8UUQ#mKI3g<=1$G<8;a^N8IO8L2(*Hxm?~udmckhO%3U01QREtL}B9nx9G3m z%eIC;EiOEIF7;aN=eA%Id++}gX}@O^&HvlI6OCM=@8B`JzjbJG zQ=d+E>sybf0?fo^A|1|n{x;k7JdaHoMeL%k_cz`74i9h4>sTP;YCpt>`bH`c=Hx};X? zVR!fot#|lZFtPi!4FxultvuQ;dAIz|1r2C>fgv=qU!B|WZsOgCFUyNzs7t$R6$0%! z6#g3dzI-#;mLX3e^YU`~2=^Ocw4VR6N?XHbndE_>$q%U_b?oIdp8aL(LPF~;q159) z9)36GTr0VmdOn1cM&{|BRbP2HQs0#|rrxQo@a&)`1!UMv!jaYJx80#Y9}Eaep9Mis zQ;~Tz_?x@QVV@}In4yQ@tKf+F;QXN*HwL#r8z_#LA8zR8Jd5|EK%4q%c*bT1Tx~+y zpT4_7gi;LIup-ve^G{X3g-oxfIv$S9?fT3;t4l+FZIZT@h|t|<&z9=zH)<+RR|-mh z<=Z?}9Q^|rWcV|g^f>+_mXtAV2ASW|Ms_0M66BXjkDucT25CvsC(G7K3V5YRjOtum z@kp)h!aE<9_nq@R&v=lfFRgSd4~U38s2RznqMNZ0=2LGD8Q(%vRR8=?aJ{a*%xi5h zRW)1wtY~Cn`(vczkuW2Ob*e2wD1vfM;*3HtOA!9}bI(Czd&d`*j%qa*h>;(~+9ova zkC!S0IaSufZTpQ@f!#nAzc*i9w&vW?eSGz(H{HAX=n!=#h$X+AD=^BY?6)tN8v`k( zTaNshED4!rrK~N#PAXQILTiq5e@|;Ye@fSJ;UT~6oOj4YWM^3#@h3>#4EX{}&q7UE zX5v~lRl+yVFTi%`rq^=u+75}nZlwD7)Q^wZ{h(Ce&Ddy-JQ&?cn8%^T>5fxJ>9cEeZP+(~5Ye1a zbwP_DlN=X5SKc7ulKM#E&Vw4fkNj61t$zH1lC#88zas}8e}bc5z;C9A2hO+mQFA59 z8*6!iajGxiBD2DrU0EE|@|P%egfrV`#JC+5V{q1}aLd?kMjhIqY=+T$w<&jW#@7d3 zN;hhIo9oKX5YJ;{c-ncf;_vDARi)3b*_AD;T#}3O_-6Xu>>!ViV*O4?v&Zx@Bmf%= zPCxJN@oUKMurmA{?IV`7fvT1y9+I=F(KKPC^p^K=oPMF`pZpH}#^h`t;A2iQuMzF0 z&3*DDSK)%2o$c8GJ2K`iz#mOfE<`&0VHieP=cvtf!)uajI)F?qJ@-ER9sxh}+cYQ( zLNU)5HjG!KvD`swO!`FZVfZG;*L!O5ZEBmLtw+V}s|nwA;hwH6!*|z&1w=r%uS>Re z3AWii=$}i@wVtr=tvtT(Oj6^cwH(pW$75fC($={S5^-tqe# znQph;U8lzUMy1JC=HlmzY`%)_NNCiB(C_*tPz&TME7jw1HjVpbtXa3Hej(wfDeX_? zN9;W=Uez_hu`()NPv~j!9CX)z5^Sa43l`Bo@?q5vA93Ie6k78(-DveKMd{kNp%&b1 zhOFAoVuI=%r;jz&?S1WkVt6jB)3|1CbvbHoI!@rZn#qUtTi@)M%z&Zb4<#P$=d|T% zCc*~`?vm3z3+{P~G6qtZF66$I_4YYlge93}HFb!&xB?@o7rUFT_OulyVg+k6CB773 zm={#YPm+;2H1Y+-N-_-BBw{VQtFvwd>Xmt&G+J?pqPW|{ld*SJ1^QF|$R2H&$0S)C zCEN7)qR(qm5qda1ymq}Lj5c4us|@ZcgvfgU1xQf=RjvNW5X%M_ZEea5cw z-W`?BRJRZu66{$Z2db`OWD#);KfWp(lDnwyW7kbn^ePPgK}Tq;*^QEAp0O~y|I@cjXI9{TP-_ZoV4wJmW2naY%Pi&##e-E&|pGXHZW1(=T3+vnBaJYfHQhQFC#V zI7s?{NQ6pNw$~9z{Ob3GK1Z*yKe!zgKsP*qC#DSVGD`HULVMGxcUnRbojUETp!T1o z(@7Y0iD)KjrsYl>9Zfv)vjl>a&`@(F#W1|-ib>1`!yN`&629cpz0^bTlFuo5G##H= zyN5D+F?Z`vscXI+Vt&(G}ssLTNa0M+p`QZ z#1<1hHOOzisb?3na0QnHN0hNiv>=pZvoaG!6cik1`oH*k%dn{0wgFc_ML>z3D9rCMO{cYn_EYn?P6LkI6N9= za(`qplSXl+*AJIvEdDur0_INdRApxwNAzTYIYMF%FDNB5a<)v`Vyk9E9Wg=!UQFUy zKFMXFxmLNg={Y3RbUi5?OGm1!MEKw&7?QZX?7H1~zZ{uh8Jo@NImIe@y}?Kfa>8va zp{e43!P11XAp?3Y3R=ibRTE|{pWqFcf9I+RCC2l*k_Hl}n_6&<+`+|iksd>m#R>z( zt)ep0qPJ$`dtBD!?>5qi_8WPxtZz%-6FKND>b%|w6c`Ivx}ZGAXP*zhwT|lzuNA54 z@}0RJ%sQ{~XiavtQu4VdpslpXxl4S9Um+xHeRIo!%ggqt=yt!#*9lu^VA1_LykO(8 zC1{r-ETtM}cARS+eqkX`plP6AY;Z)!C1_5Udh-hdqgX=#Uq(a?djy@v@z`1VxJ@$k zo4(rM<+nL#)j&eOwLR@JWYA6^e}Y5#(SdcLmt6mhMfw$L^PHY$Xjf`yJOlm6VmkNt zt;|W>9Yu+Idn(PT{0$?#aFiVZ+S*o$Y!n81cou=00b-C@{hoSW!kN`6Bdl%^Bi8z( z?xC6L)yWI&jp=Gn4w-v&5~KfXEGyEayQ# z&pF3#NXvO~WX52j-m{Tnig^BOOaHkkQ2$8g(RF1YU|yDqfc|UxM?@tra$i1F`7UaX*cF2&isxaQk6xfpor0hK11P4XR9=YJ7+&n35XOe zXpB27lOvf7OqNa;jqbOnps)q~$)7WeTqpjFqGsvQb*kTI%vQ*&c42sBa`0ma?L!hJ zN6pgdTOs}&sa1Kv^8`EY#=&G@h>0+ zQgJ^^dg2<|YjvYI46w+6oG8WEPOH|DCn%-wb2`(PW{ZAAA!ETGY(*A-js2y*Kk&fa z;eAD+ybKh#RXqz;v1|=iTumHvi-&hkZNFJZSN?vZqP+>><6jzyDvErw!^}L(Bv)!e=)Z$zriqSrZv4iN8FP^O z&z$&0a#SstM30BlGB`9X(~1SymTt5y-l5&v(1bMJ@z8O&DU!|DXtV{-U!8O&;$Q0@ z9|j+s{6I8~K3Bj&=K84^_dXxQpj&8I%i9bugGv&-z4*ylLdNfY)hNtr&F2LPlCGGj zPe^_l<|!iVEzC;;%W6*cyZB_Ez)UX5 z>J^q`n+gX@1t#)=P)4IWG08>U!~iW7WiMS;^Md=FEnoVIBIx)JIXa4px`vMS_~eH$ zW2V4;04n_*2NP5n1jHoNs%>cr-mn@SAq_u zx6t(~(*?<}eT-bho5eTlH=40Zv+r?qtrlI+j1Je&&^KAlDCzR+I=693-BjQc!lyf_XTnn)|k`zd3aocs+9E*UAO4HYUU+lN9W17r$qR=HO z<2*^te~b69Go*Q{!^^hf<*7JQWxYXtdytZ@*^R>IkBuo+_k*3=0IwN* zh%T~R=~&-uvvstLu4I|E1Q$5G@Dm1n=e@`%x6O(0R{gU6o=E$zZVorZ{Uq z)&vRUi5j4bJ1qSC`dHuk$|jcmz?UeLmyN>g9-Z@8MJs6Wv&C31YgzytrmT(lhcyj@ z(grfvQ>lgE@Jatt;iMVHo5Ia3HJtGMya9BFilqx!%pHl6#+@C zbSrGfMre?prKngYe0v!8hC97&R_hlv;_$4p`DEn;uHM(V=Zu~Kb_Qmg@aruYNo|at zZe@0b+Ml&|TBO`tOG5jchVR`_Xd)8yPEdd#NW8)MN#xN$SlJei>J83*S${=YbvJ47 z2X(cUx$T)_Py08?)85&XlpSjk*vDD$=O1nk7=$4v! zzvK_KsDSVcfDA3XzkE?K9d>o)`uOS7eEyY{l~T~1yAl{+U@O7a<8>6T*LtG!AMm0o zle>L{LKOP84<%m1`)w)SDB#=ACC-{d$N=1+{8qu9y)O=oF3uO;eHgEQe3EXvlz}mJ zxC$qBkdl-ouz-@Yu{F*0h!Sb<)|wi0MNUl6Lse?jiCGvXK3>c?KeRSrTZM`-U#}^J z^WtM}DzEh?Uct!kSFRI}D$!5gX_Qt{&T7*B%nza7wfj~;gITz^$~AY{ZQ=@U?}y%= znKKZKkCt76LtneiWb(U8qYp4WBpu;qXn2|7_-^epw;-pRQy6A6I@b|E+Ss^0XO$4Q zhv>Pi?%PC=p^U$9Tx6|$cL;9TEyIo+1X8zP>9gLP9`7b{!*>&q* z9BpI#gvapsDPiv<^^UI?KC3%@oaIdD7B=ElV1Pk47D}mS59?WdA_gq!#H+YCLp%+o zpuPF1-8NP8@WYkI;i`AsLD2m-tn{y_3|e~)hTBHN zw%96|4(f1rW_o8HKB;Fh-$L=jWUhFxo9oiJ=y1OKOR`1xM*`R_NV_>mLi^LFjNhbb zCt6fLaNy6qpLA&N*I_^or9^M*u9GM=b794Nb&D|vdPd2h8ZoH7r3A-OMBI+d6*(tB zd^#c8zK0nwe9v)uVzItkJJ6C8;tDSI{P*e22a>YeR7b4TxJg7^Zo}?&TUw(Q*_Y;) zy`~y2EZ79DPR+BjvT}by{aC0%#;8*GfT#GreRfnSwGaz4h2bFvcb@h6`gF6P9zfFS zJ}_=!-BINEo(FSWN5 zlh9K4-A9$roj;G?}!r7~2*oLte3w?~-b0K;brd53K_A)asc#G0B;DQv> zDc(DD{YHZai|Z@gXfL|d8L}_mjfh{a|XXI8G)MehZntO{z9{Xf7E z3-JA9_WQj93tJ%@dogn~!?$dWXO@-zn(ekONM0(+0;#b<5=*!5_;x|Tql;i=tF4l9 zq~T*`h9tN0+Mhd^Y%7mcz!GPlxRq}`Fv!*s$3_+IKuPGr`f3CtwLA->LPp?z@z7D4 zVmW2w>ZFEiXT{Tx;W{5ixgjS?!sOej45d1qkn6S<-~2}74_-65&+FBGOfF@%Tq>xU zpKqh23?;{mA_mC?QW5Twl%2UNAZU28*Uza(DQF8?xv(xGCLv73DkRa;8}rJ~8lhA(e5Dgf8qUhjOQ9 zvAEqET(KEii@^qp=1B8;o5y1+W##x&7~fB#Q{pnTHR`SW<;rN_{cYoT#l=WQV`gtx)lH|HolNPf6JDc0Xh|H69#b1msJicwuzSy$Na(FobF0LGACtPyLr`JdIDT$cW_Ch0z5(G5@x!)?tHTQwC-hAc(Z4Wm zs;cUcN;f#DJjUnBWe^$ALaEC--{X9KZ)(I^tGzv}3f%}*b<^ZV>zeuz`cyJzm%Amb z`2Mbr=|6d1RarUeT?a$^K#9gfvOPfdU}@ZSfix|{y$6v+ye#MCoc#;zL6ziSD=6FX z+VM-5$q(YT;#K*)vN`M}TtD1%KD}~Hxg=hUG3IAG>8+#kA$)PkK``zM+XAA`vLsDw z?Fx%W;#a8_FM7_N@Yz^q(UoFDP9~rm8o%0zcx%FIcn+RO%1;yabA3k@wa&2#e`t3|?mkNbUxkxK@RQj$*@t#y+~Jt$6bI9v{+SgiQb>yQ+Zf>@(-D7Nk6L=X|_)FNU%c(E5G{Ca#@bgemjg2T~_^-DlCUc@rdRHpSHHY@|}D9Ofhd` z${9i|7Wg^hU>*7$`0jQ4ywCTXRkI!=Y<;8CU>@GE!OOgA8?wpn>&~i zOLnrCIL|Cp&L+w}?$#{(P1G6miZbo^|5#oujd8Adr{LsTvu*5&Ub$+&s2@hSs6LPF zvNB20Eq}f~WRH7re`MwdHC*lHP$)g>92r%E4qjno8n^h&_^%F`Zem|I&o3(7TX&@| zb|;n?$2D(}0Dx zl-&;}XgmqsauW69Vu*}khVz0XcTwtY<>d&p`I5=75Y!%1bpqljYPsy)3@@rBimD{n z0tRU<8p(zOi?IqwRVK+n8q*^eu|#5DkvUD ztrdyAY&Y0@#|x9$Pch~XAxR_h2?wh|K>J2gR~T3aC>__p&hcFjTsY*Rm}fEVFdhK2 z(H!)t8SiGiCO=ctNbjB zBlYqhU6wKP>J*0p(>8*{i;N33wIVO&FnO^EuTd2X8|=!m!U>3cxsauo)f;0Q#t;go zYMDiTyvsq_bsQG}7A_M=Sj(Wx_uGk}3Kdo(OaZkuzZD^k=J!z4v7a4^xu{)uPd zP>Wi2?j}LCj`Xlec=%8*>QM5#g(m>N9CzIJRN~&Xi+4^N8AzOQ5|<5hc*j7Vdpg#V!P1xPf zi^5cw`Qri$$A9qt96RnMv$9ss*p7Qw*j)&~()}iqIp2sgi>~utJ?B?)5zCL2TNnwGM~u_ZSd|3S z5F>{^{G-pWwSpdr&b;)NjxjU2cY=;`bysI~_xk5Z1w=na2lSyCD#t^EUq>r*6;AP% z@7R9OpBGuB<6`-bAKv06GlVXDX@r)oDqgnz9fw+p6;I?bS zg3G+e0{tnWKXCVd=K0ao6kvkxo>t%~woTT1A+Zxr^4BiVF&WxYPvgnZwPkJM>h0!r zv<(*Cpz`4a59&0M$avuuc?I%fz#`+BE|3XwDk=xBH-w`lkdodNFqGPzSWJ0x3lA2T zi19R`_NEi~gvWbLE_7ZV7PeX!6{WS#>JEt923uXhI!SAJOLa`4uEz+L{NJrioTg

_rOBtWy!wkm#^nU5Q0g=sI->PZGgH6gTVT9+z>T5aMcK{m@2j+W$>U9{ex6Z!$v_Iypko5#! zDEH?(qUz64@2B(L-1gkY4|NW64vdme?c~~3J_?pM`hZk z1G601_wyGLbz=G{rDtcQa(xkun={4Q`RwZFzg$ zaP8~NS79krt}XX<_NZn@U8#?4hwjbTC9?OON~tBrL@IOhdrI)*nn^sH94QBg-cFYW zhLzX%8)iKW9X(+sD!pgwz4tK9_PSH@ebqFUIH{Zwn~*;s!VC>~1ZWQ-%Vj*=-`qBO zuEu<+z@4D$ri)nn01c%uSp}QCT$e$@WJvGl*RzVSP|e|DT(|?_oxGpPy_m&A1wYNxGvpNm`t1TQn~ z9qA=-gPI5n#(|`{2BLGNjwu(q5~<{;h(uLFLfl-Up6oWvH-Wzx)VMR6wfzQ5puwz) z*;WbRcr9E{E2!}WVQg4U;b%HZpmM!Z5XH?A5PbFjoQKBi*O%uDveT_)j~q< zH@lKQq!G)u?NS@LdtPKhoH<5R8!K*D8c$upj|&t`u$5_VHF@Odj->Z)GX7_iHL}l(&LjO`+mDUzP~0h zPaVsK7~vKVa^&=3SEw^Ms4?sU=%5cDAr9rIiUJ>JKBewyY>bF>Yt8^j|7-!$-Z-yb z*R19&D~Vm5nO@FpTCY!PGpaX(Y&wJ`l@j6ovgh(~WxZul2CuEMib@wsvSrkML}ZS` z{KhC!#1y)eXH+l9OT-|wv_@tH+6C-StH7&lY7i3w2jOzIjej3kMbeB?(-p-+&aXj! zC`=-+05ls#jETrUwnEpP=(m|)a~avT85|6)V}WUHn4p0?_?X=}v+I`;$=+3Adw-gD{d%J3Y?~qrJjm*XY_W=*9)d{5 zU(Eh>06-_TAbDzBd~{c4OxZzgC9#kpYy2SSH(un+zdvix(KK&2$oFcPG8Zms4E1Bd zknGv^5SojNWwRS*G88a~Fp`s?mdlDnHK(MX=zpI!7X(E2sV=j(9I!(Tqz46^RdCjd%AtX}xO zUwc|3%R%9Kxs$OGew&=R&zHHRQNx$yLK69OpZMc^4#JC(3t}amnjT$E&aYWBfKtsz zGP3?t(MDuSz0|TmAp`Qqq&z1ym$~3uZqz8Osb_5Njy_hs7u^@R;Zw9ShOT3BR#}>Y zL^TqZ4PWp^;E7!-$6#>-AEi?%0p_IN4jb9hwg+OPc>wvh4}RPWqBW_b5iSgdYwSMZ z8Xi;bj((|^shkxI#8x+V2wKD`LGK53mEx+I1w58Ac4QW?5__ACKtL7lxmuKE{rNe= zr@C(f#h=CFzJ4{QRid++sZ>5q<#Ea50-oPkDQD-nGND+tyPNZUZI9oBq}lgU=P+8p2qIxy5t*Wc z-`$)vK$t}5~XvNkjZ29DYW9)Ko? za&&nqq^yhv05286<=T{LxGr-T0VJR+1Zt^W($fxtsk#O-20Dbgo;=&=X;O z5qR)SrW&~0o1_%7_HG5wjdoR0(b#x(4J<e5;tnI?!kWFqNY@5NqfCr z-4Y1(>O02GTyBCuBU(E5`OvVF&N!*|CzKphC+ z^?KgQ87U06-c_@+1KZ8xiWczk4X}vMElqw;v2>Iax);-YW#W1C@;7u@Z)i9Tj_&X9 zdihf$sp|2S{`=$pb6ivVK$-DN`PG%ou<}4pZwE5TnLby8jF8}kn{~V}nV$7gX;>rAkJawDi zE_Er6KxrxQa~XZMmdLXFt*D}`BCshs`CXUgJub)!TEGqzRtSp&wc5rk`AP)=OG~;y zQHAU|(Tf+KfxS3GL&Ki~1JXr2&U^R(Ca}zYT^z`gLj&Hve?TZ!826LiSuQlH72%B- zuXF@IU=WjSnuD1PAm6@ydvv}t-hL0e6aY#ti0+`5Dqaf?GNK(2%I{{QuOC0X(Veef zT;AAt4){}3I57~Sd*Jv19E{yo*$i{_&UgX&Aj9KCYO!uMllFzRpd{3!l{46<@f?x; z*I6B%Kj*th#F$K$R@4yKtDQdu^C6m`t5pk|&$&&RcXcz=GSR=}dFHaHo?9#>#xy*m z>a9f+-?q3&!o;%G3;tk@W?#7~uesMsZ2+up*NG!VKl^Fe_bpKi=Ok&dGSqfTxDE`6b#NLwdpKOS*+f8kgX>*is8^ z@?7JWRL2ihc^Wmv$ozx7y@Jxx5y(S>eSM1SfO;6m?_g^y==RoADb8tgAXV_=M|e#w zExY3t;o7>oyqFMeG{zMj&G527^=@xLy&f!>|LOx02o9oO%n^8(di*%nt zT9%38a3OhlLQTz=WiE$IMFLbsR{3-7->Q0KIWRw!Hk}!rocVK+zq+2;9URqm5V8NL zrx2mu)X>XaW=$-XIlj&D-{uq^Qz_X zJZ@j4q^3rtrGe%R`owF$XCh3;h(tln<;*^BIA*LYM$|zoEbJ|MIftn*%=^*ckf}UpxxXr&S)mi(tG$#{uzlQUsgYf@un?jCK33V;ct!Ml0#sf1BYI&B8 zvHPI{kaPj_4Kc8Q5;Qc92|2<3k=ZlusZap2w7EaLpK8*Om zh}xgT7WMTjJh1T&n9E2xIq?zEi50C7;Nf48kVJ-sJ%6ayassw6eM?Fhl#4ZkfhuG@ z;H~S{_dwYP&DWY?Z9{`W&sU0kdQ#F4=Rkq-tJ|C1lBqfess#|#%5tg{u0NTht5B_C z2!N#mJNp?Pmk0R^!^0RrvJm88z5zHfZ$O@!$8W9j+o+c7J$rBTL#?gmfjnw#kY}E! zRFIRDE&$fyxW(l+PGxy)1`{@$ko z--dQU40#@O3l8Fs5fhNQ!_|Zr%aI*c_pOEZow@rTMVtJ;EU0JO@7fRU}?Cf10Uq?d6>w7sxm!>Dve`=8)bPKc~YJg?~ z$-6S5b_gF`jwwy4{xSw`m>WQHC6rK11mLF+dgliihSXo3x}wu{J#@vk4)S{K4tzsgl|RFuRa`a=^pM`I?#<2~eWsr@k?Y zxdHs*uj%Me@ffrf?>aj=enKEm7Zw(#sx0EwU3P#HBR97^{ zGI@60HAr05Coo0qdU*v|G{r+`LD{jEt-}g~Ug7ryhuTRb` zuLs@_h!x&ko?eZqE_>cfHVVAK4xTkOIN`ZL$}rskEr(eTHU`)gNlmeUX|<>4kOt{* z5!H>YI%y*B5k0cRmOk|*&ZEOI?H(Ocli(ewJlSkvldkfTv!L-P4Wrnusk?&mRyk3p zFu6{6;1eRJXx@?Kfb6NEKwgN_tA9sGrEQkWKLOHqVGT*Z8Xis}*>!8ReFI=;|JN%6 z5R>y|e!=uW1BxBV1Q^is@EE=Ufh=HnDRp5awY$evEYW^NO(|3BI`Ov9#n$noh&}uW z7DHSAEQ#~QMRz~b>gBzce8O;x!)6Y^5eDQQs4rjc+1)tO?(JD(ywpVLibw_85#r8d zN$?^l)Td|d5jr~FI6WmLoSvT33!>yKNJ30ZaZ!!vd_8EY?zHjO4fr*6i{$FSDar?9 zaZLOE=~51^2O1@3lYsoWMyB%%`4#;aWA#`Ow-?dsfUzOFS|)_cS5RXj-jzlUUBg zMctME_xqT5rs`t3zx7j&zMS>7qyh|hWmNYaiM|cC2SeI8&lpZ)YER!efGjNw)orxE zx~t-Vi0zQO^+Cke)4?E}7Un&j;wu=Kfq@sFRere%Ad=hsh1lY6)_cM9g%y?2`+!jf z0e~m7^>Eiw>s}s^ziR*kBSvBuofET|hJ!KTz^jG8xjkAou?Aq2J9+>?0)i_`hCA_c zF}dNc?vWDr`qoyuZs`d~Vrszc+{>&~sKR)1zcHH<>%R{6^Y6Jl2hz0!!l$sv z-m=*Z{S%&epHr0d=d$@>ZA{x%SY-!MCZ$*6G6Rf|ljgiW z_h}oh(gK`3_*OtsGf^GfuJ|5wq8%7PRI&%>Y>q5>UMi&FhvTNb?@Ky%z1lZ5K>hDA z1vnl)5BEz?AVL`vD+mg-C;^2&+c9ITm)y-?!&BXHbT znoO`xYyG!a;XhX)_e4ypC`qg*&(abF`6OI8V`bnq^+`u|UqdzQ*~@e6IrBOqoVJI# zh|guN$@02|;{3Z5@}s>VTh|U@{Z)+D-=LgfNNf{kU(4T2Ek4;uh%CEW{hGs2cC3z7 zMwv}6m3%#Mm=_OBUSQ(?Co5*i_v8KkpVzxKX!ZNd z!%g08PoAE~#a(kAAXasU87eR|L$B&51H%hOQQx$dY9O0yH?0UmhT)%p9osZE}3qroZB^kpCHW@wLtw)y( zN&S~4n_<@X_#tt`VpCjWY&eHJv8 z;U%&wc!dQ7mgYMSuW%P(_RsK`!!*v{Oo1=yQ{uK@w~Z1UM`naordfCH8_RnWu~*lw z`OWlHI8^L+pS8qh%Ja}Z?uunoW})3y7Ib$s?N(I>GZuIVpMJrpKv}eoBSPTAnCVtv zqxfH4H}EE7gh@d_&A?Vbt5Z0O0gNGfsU_qsM{c?IO4r`rr|F#P?PS6tdcw)knU<$bPG-w#1Ow@6$+>^e+58wV!+TP1pb zdHzgW^#2dh-}w+RkL%=^!(Bt&7Ds7f#X2=-XG+9}Ms|mSxRs-5=CiW*AeUfZOooTK9i_IPBHiPedgihv>Q=rQ|a&*fn zc8_QlrXNcLtwfsR-~rZ2d{`{tquTJOGHfe2t*J6k0qbflwFA=M zFz!6L*KKljNi)-&F}jR7B6fIs;QY)!s68DqoE?~`aD>X3gaOdLRU<+cY(BxynM5sZ zzup$S2GzFq%Oz)1=Ku7Zswe%XL=xs|`q-WQ+_%E6b8F)};^hx*N%_RPJM~Lp3$V$Q zSauOons<@iB%jsKQc(U0yHFmLZY?W`PY)mbvi`%e_kX{%(36Aso1f&BdH=T2$g`2S z06`54w#7P!_&-)aLlYAMiP+DNFVW55IWlwClI@(kYEIUfRW#jEVjf4JR^HkK1o2S{tW=lrTNJ=9YC2=5cxUOcoB!Wtnt)PZm(c&a z-jSk9&7-d7?NBk2t=_-pZ9+ykQ(n)@u?F(ic^#h86VHXAy&`Nkw12-lL3*`c^VVvb zn4g~*m@Ei3xr0>ePB>iM>RMY{iJhIRyZieUdYPDzX57KI*P8@NB>$N}1SVY^3cv{n z$N($p)}Fkioz{#n;P)zpxJR82$rd!w(DAbYo~?{|iklG+?D ztybwH6hrk}q~>{d!aPROr3l!TdatR0Tm#F&eiq_IGFF6suS#gCYbS2Xr&!**q()7z z2q7V$PO$oAxM)Bb^0ixctt)nvMx^WoKtEue8#cFEal-Ooz9pBnCJHUI24D6^(fRDXhSw)i$nfX$iUAtc7yz z9r@LP0$A?t!}{-!>Z?#GzweHMu?pXh$>oalJhG(B(V|fq%P$T6Qs|3sb%Hx#RC2ZM zBv-+1I^>S2S>loWB`7$%MT=tB9f*51(LAGWh+FCH)_@X*{3F0wG-B1hx8!WIeNMAE z&qyxIMQnOLYOrh9*)b2T(KmGae{?8Nx!|}n2ta*XZgiz++-Z321 zy+D>Ej%Py~Zb6Yv;$&;h}NKDVf*@xZDlYa_~Otmg$HRjMMdELA!Iqbt@J8`3hmEt~t3n%kEDm z-O*^A0=nL$U0!2KPbZO6l5=NM=F{(DPDR_TbW@!zTwBgx;;nuQjsCmM#t!}l8>gy# zBLdV1jN*{^^_v<>{~cU?@}O3i2}GFP zT!AHe(h~po2?EDTFF9y;Qvps=uae9Tf4Z-k;XwJ z)i``vqyKG4%JYu&=}0<@$=4^6$GgcdJ4ko}9%}$RkcM_K`O8fJL$J(QT>?YnSv^JJjQ(ik7oez+Whs1$DgEO?BdB=k;BE4`AYVqN`(vtd zv#q1UP_>h25kxz8qmY3rRYqkOu&K8J+TD7$pGwK_$sXh|A!I@)6u*Y_iu%O&H$@vO zkJ7*GRANUj@CJLCC%r&+ZAe&0F zQsJ!}9fEwZ?{B`ii@IO|%QnCqI#VtEDRfYA_J(Z;8to;%I3jYBTf9G75eIXpyX%I* z%>S`>E9SD#-(2BjF*@Ai{7F7gD|nd*-8O#+0_6j9YsA6Un#k(+X#cN($1v*a) z1FStb2ayQmUov%H;3CzFAFPe$9G4=_?#1dR_RjACAKqg?k;kPVqi$|rF8V>+8@WTE zeqVE$n+H*2YG&#+IhV$haS0tbDf8C?Esr)cF%?_XsEyYQH}gQJeQxg(v?s1PPCjZ& z^V?T~)}DHAdD;2j%_Lh!Sq!MG0+eTzo*C8b)W=6A=1_6|bhJbFgHo4D6|e4Ehbphy zYwm(OF4NUmD~iuL7c_T0{7OqL6CyWXh#sv4AOgF1f;UlCF!P7t$e(r!Ot+Q(QbGOI zg9zb#^11f!8J0FW#`{{t4={Q`--%0IN(I?WJorqTi<9$vdwYD7Ysf7v9|f8_za4_b z$C@k8ioa-yP8J(auG|MUhVmX=2LRsVC9gp9i~LjzRI11R&`f6q8>P4=vwTcaop4 z@vH9`W>o+7hA7%Ge=Q&9W$7%G>2YVjyPfk~+e8T79ML70yG;VH#!6Ib0ROHs>byL> zGU}UqRAT-m>8_t)vkYfuRWvL-`OzC!ZRQi5Fli+YB*1;HcwU}*#;_&=mnV=}CDD-J zKQ{GTDQ;gVts2~`D&)=14k!L%a8jH(mw@gl)or> zczRVcegTE@H=q8&nM~zr!^Kr7itTwwZo^Ps~L0;3;sPH_^&f|?CFk$ zN>!nXM;24Ex7(bU71AH%IOcH`{x15HDzgV~{zSftR|zcn{e%DdO(92u=g)T{A4NX$ ztk?wOGwMD9;={|^+tl{-j@+-r#l>ZHbQop`!=D1GrB6~){zXM}jZIBJ0GS@r00bNl z7n-IjOwfTMAs|j!^3r=oK3U~JW#Yg8!2cXOK1rm*y>+G)t1KuekW*BA^R-Kc)_&2F zJ@n1}=g*JcP*R3e51R@Z8*lU+1EObru$q$6CavQFL7uKbChMO(sK0vJpe^y~_$HDk zI8QR@RMuSBxZA5n2tY^v**`7!i8M01T{JPFYexxv48c7g`z^F7`)YBuUJC(A0>e3=m8L&(9$?%0_a}n`Lqo9~xlIfWvEOIPwfFX-Zf{RCn)|lC zj>y|)dL~RDs{5lXus}t{)G6%<`5<_Hck=!2@)MpaKE>*4MvjE6>Zdn8FU$Duw?Nd^ zi0MNXvI(GP#S5S4_N`Tw3er29 zI@j=1B>N+**cBTaJIJ9SrLnP5R#UU^j6TikGL3$4T&3ZymbtW7lbo3oJqR?B%zbit z+F8#vptZSLZ5t^-d@Sqma<+yqFfzL3XUX<%+1(cURJ09>iwOfh3i!SGrf1%Ogl=Dd z(1E(|7z4NsL;(baQbVWbzE$Ruk8V5W78GFpz8TOguHMq)&Op1(%2}p^8`;-)cv&%T zXa8=u#rAO!5!1b~Zt6k*=q9X)c;og75&yPdA7kQGzDwY##KbAL>E^b#`VyD|MNs0| z9|6@4DZncHk=@;lOg37n z7|HAuVrAxLV8p%Icr+6eQ8P;%OUu{cOg~LoLxkKzJAG2ZSUEWxg50Fet8$C--|ML} z6YlKlvMQ3lCd1?kbpB4uq3~uI&-kS`WEjcVfRB*QIO@zMzX)U2;+KT1O17wy80jy2 z<_=T@<84(Zwph;Ebq!8aE!}*UPhI6f$0rve+b_*&dcQMGhVItQtxc*n4}UM33QO8r z%pE*csvk=!sIdp@gpt7T&RkUL!zr%z8=hPZXPwC`KjtAqAS8@EPzrnKoVW#)4-Q|d z*4-mVMMJ3q-@OvMcBXA|Kw62V|EsSW9)CkmFa2gkp=)d+7MeH*Mk}6K13{t3LsEja zWHl}HcM6Tpw$URNf-E|1Gjywv%tok37mdoNZI-HwW^&xkcg~)f(Z%SD!WTRJR@6yt65Y#Q<}1T{Ms9x@{3la@s9W@-f$V z2I29Gf1I692ZTf_9|Oe>R6NLd-JjiDoCFTsSfFhrVH)n;5ga2*=vD_vXFGq;O;_y@ zdD_-ljoh<4@%npq3!hd!`OeMTv(wR5Wl&$_^yjZ(^Hb$)1naoFUoOIW?o__w!f^}$ zK>F|xpCLhBhx0x^n&sL5`uAaI36qhNmjS~@w&*J<4XVom%e77N7i?YQCBKE}wFDaI*zIe?0X?UidJ|ZYE5){07oU#%k9*$ALo@Hg+!9QhIKC5j z9B*uj4Yi|`vDkP=V>%JKpaZ3Va+Ry?0+>*fX1|ufAfFlvtXU4RQ=6FxO%1TnpzG5? z8LqNTq=O)LSKhH%?JloT6V~LZdqg_2G_B7)zs`eB<1WyNS@6KGTy7eH?lwNa z;i;&8OP}&?FfmijN(5<|xDe^$Guu151h>KGVc~ID&{$WAIp|8 zVC-3FvcE#)5}MQva^scM376u+rH??CTkI~z=3Q`OI+i;cK~Wf>%&G5?e2SfO8&)Eq z9lYKfZ*YxBvbx*x5kFgso^;tXNv4R15wqO``l%%^>@8Pfdr7qHTbTn~@8u}&UD*s}!^!HK59I$@vHx>WpU+sAu0Emr(RU_pUH6L-$KCL_T#hc8m=oGo)X_C>;i5mX)g?ChE>GlF50=zhP zS|Me3nKj?CF52&NOdl6WaT4ASQ+N535(jTT{n<-`5c4G#E)god=f(c?4Y=hd#toI| zk}MNV)}m6}4~T7!yc4@6)Un|K*wNF3U!w0W_aJs$aEtl@m^i;8jbGPr5+n;;ztFK3 zhyX}J-?_9AhPy=7RVWNr1Li0EK*43U9L+Ea!M*~N12{a3gui>~AoZd3B)ua7Ryh8s z)eiMZ2gbSfj869ZDV`4JLzscIb-Yv(E4ItL6M}WazIzAc0%LzOy+yRLD!JTijkgTP}4>B85$qVJ}X9S*Zaz4^O3%g3~6$+j6;N z^gEg&LqTgD1p0hy)zA)3HHl4pVxEnd<5dzbv5vLu`>8yAua6QA-Ce}ale~5?=Icgo zo>)}N7|LO@ccF4ctVRb16C_g-?Vt6zzBlK+i)O29(YD!7*DZw%CcUu<>MAdZ);kJs zFZ{0kcIKFLVXnwB`f)=qv;c$20d=C7&#A7Z#gp8Z<5s3_%^sWLU4MnSbs;h3bqC)q zh5;(zhSt(1d{y7onGpyHn)8BYEh&6IcY}0;NJ@uvOLv3PAl(hp-EkK)bIzG@ z{^#B|_jxfNHahP8>}RcCeB-ycb#^A2DCs9iSSp_Q`>(5%>oplGD^F%NFOXJ`PfUbn z*Vp4z%OH)m_2&%?iVs8~VvT+qHf9d4%KwTth^m`OM?*{N=Q{z7VFww)97()6Y`F&5 zH5mOS6=jS~5>ir;FpFP!>vxF}vh!EbK|iEC9I{o?`tW|JPllevD=MZ4+rEd*{Z_7P zD^Qj0Nx_`7HqPT0*8bcy+YW|es;VRMb4KrzoynwUIR!W)+_41t0_NQtZwDBHzw|N+ zCazZAAgej@>x258o~Tr%KY<6+Zrxx)A#5MwtHs^Zo%i&&n6ZTw?&!(b*Y9=+`>HkD zncRD6`|HUtye)~Vv{&F|8M5DueO|1Pe^vZ6fX~;&*M0))x4=E3D3W&0V|pBs>AZ-n zSA6!|e`Z8fq1I|i~!HOT)&5yl@+EVVEzemq#P8?xnHi4?AlsP zE6_N#+}b{gh*%glZD^ZqfW5tQ)9+7Uf}<-EB&5L4#IxU8U4jw5wmJ2WR=GH=!|*Ke zuC-jVm(SLowL>v2JheW+fh$geRamdv+Squa%plOYz=doe?g&6({gvAtP~@k$i6pNE zn|+F1|Ddy&!w}{4K>+El5mnsl4y6}}1pzdcw&?<5^-vz@ycW_~qSQ+ViaH+;k9;lVXsFX`uT03bgQ+1K|i#OVCU8d*3^I~>DlJ~bQs$~X`2%) zf^MaXc*4L0+i!P_ikgxXS1{G5xPy*{RtC=S1?rJt(fvL%F7oK;D+Alz9zw4dFAvt4 zY;7NcJ*ur1=_kI$#Jnh%Q8{5BMe_plfZjVvo)AuZNsiz3_Db3aw?^#=1clr@Hh%)9 zZqoa?6%sw?U$dt^88$_4lJcoM8_Q#zg~+XSsWnUIL39)7IM)99dRu(7 z9&7s}YJywj=iU}KF8CC1}9hxC+mC2Sez z$UpSrzYcG=&{cau>Jhrv6PrLw2@{>^o{cWuUc>V(Hob_!vbLCFj^^FbdL*m}DdUEr zh*PoPcD#UY%TH(CtD2ER4zkssoBZ8G>y^EZ%0!0&L|gNP6dK6)ADaxwKkQFMJgrHE zLxLAGR-qJflL+;~oKnix+i_YXR&_CLqdEx&wro!mW$|c#%#&LO2noY0*`}I z*B>>tHYc89Y&`I2{(7ELp85=79!A&MudhclGM12BF80eZvfulxdGmuAcwIyyR_C$$$bv&5c%3=a>l zoJYR92~3@1H|&1}1?3!k)Z9z}j={hse~S}Buc-mHDV+r&q=WUM9k=DAAjvZ3f^26p zU*pKlwaqXmC-H~jGq~U|QRA^gmh%CwN^y-E_vB`en@8nY0>20M?d>g?EKZ)11*@m8 zZ*#aL$YinDmBGoU^s=%EYAMzvRvVKrnaUg z-Gs&4!tr(;PP(>j;;FDYvb=KAoA!cgEjntN^_aauivPwLK7`)KgqMPp~xfg~g;iE(?&E3azuT3>(lhXoOl=hnnPqExe+6ONCshxMUO z0G7IzrPxp^pZqe0y-d#@yFFgSo+L`S&*_V(R&C|{Kv`oeyqR4ReeaomazGZs{-(K!4pi@C4vyK$won#FZ;X zK(Pq*YKVklv2XR~=xArM#Xw&lLRXg&sfs2e`9&He`J<{^{yjcP-9seQEsIJRXX+tU zvy_Q#Po6TZp>*(TyAIj!^VN7e?_(k&S?>)^8YO>m==NV>r&)4_RW}fxjq2EX@wBe} zt}LzZ?ds|x;^)`;B`^MS;>X>?GN%;;|@%F&m!sd#$h9m2>F>2>qh&TkZN&e&Sffx2{`v3Efzo5BrLMoc`^6ys- z2#*$yjri)$6Sq(YbtD=8Tj{-JItnW9GCNyH9J-I;@ZG(7tnBPUX^C({{5Epa(;Xj% zJIG!=?eV&Pf=;0Y8`~?kTR1uSI;-3l;4nBi{c?qSKo%OXq@#_;mk6n@{!&Qz?o(7zzu`*m5dPYsu0vgjVul+F&pw*4a;Cn_Wr!uoe&++u z{#9szPX9)U4B-LOrpKODP$`FF71ur6E>kS%ac#LfT_GM89@)bEO>m~sw&ix?PkDf* zk|9ZNMYaAqg7m-G&cgUT7U+W6Gfk8Ix56I1yW<1p^{_;{Iv?I)Smu$f)= zF}xoiiRci*$)i=0*1kRjF^t|Em8}F&e`2n+($rEMNA3sqP9X7TOr|s5eVW=Qr|Ur`Z5!y( z?k}_%YoG4eDJZI6#Q5_K|Mnh#{g{W&tWJBmr}EjjFZOUqiB3R3fKXIaRIficfmca8 z0TLHCHmGk8efA_`S6tX5#kh~jg|~3OhLAmr{E}_^q=8z~G$JJ>dURW(-su8!CoD{( zoE#)6yXZ74kFggH=Ko=3@6D&bVHwJ|ZJ|C?lP}laSXv3FFMx+S!wtIy^75i$R3oLtIoA$S_PTM%`M80zNers#QJuL zeoSc_q_(ip(RV-v61u9Ogfl#>BW7v&EF|=7YqaYnjBt|*5<&lK{VcjUU$>g8I{ULz zlq*K^=x6sHnKSO56v`lG3G0?dAOjck-u49Umwqj zy;1B<{P)6n{7p%EK>>9+eKEbLjp8%YaEDA#YKL<(DD4Zt{+$;3BkKL*I~-eh4vL0Y zQ5U!^7C4LwY=Ar)S0?CYee+LI^F4-qW^HHZ3s%P#f^8>161`5a0>RP0zGZoZ`I5A@nJ%A@qFM(En?}uo#AkC@RvqyW4|9!~I*lFu#6{ z>0mFDO-hq`+gtj5XhZd>$)O`V?hChOVcKQ8Vf@VK)@l}Td1fj$0Mihfsu)RaRseDEMzi2<<1KQ9MF z+wA)s;3CMb+%o+DHr`d;HIDM%HeS&|gO*o>)1|R%E59qE2FyHM&39eveO$=gVYn&o zLLGW4p{(gl#6~|ntIky^!tRvGn+)eZtu?A;4AG&sLfN6ttyVqrdp_-FKxCwuyuA&d zJwBMvhw3>m5!Pq}r3a$PaJnGYFb@{D6jKBycB0qE=ox75J2Bl`KY1*iafFB-MHl+gN6294`*|DpcCjB%}gQlODDu5 z1!DLsv5z}eZT)VBI_CDTG|Xe25j1XL^mZ$!6CC=i{cgCa~* zRo2A*;}L=vGaO3Wxj6}-0$E17Nh0{D%-}RdiK?1a2eDDlt&)hbBOryQll1)t=HYTD z%h`B2P~zR=q91!24dG8Eu(}hetao+1u5#bjbIDzfB4!dTCBd1v;k^SB)_J(VZ~eJC z4o_N0EgT?$1q8MGIh0WKZ(42(BS>_;GQN42#O%&YEHM5agowA{%*Db^EQ)APmBB9L zX&6)uuXc0Vxk-(RqL~;d|HX#DUp_Ch06nS_?R!i(ky%nH6Fk+{?S@i0`TX_jxs%-c zOuyOCEiUIX*~urc{N1Yu`$|6GQ)5yH2uPVYhHVh91NBYRqsXUz`S~0+@o#qE0?xMrS zrtnF_@M%0Hw!Y0pX7s$(8Job-Wml)MkHi{5Zg9*N%Kql9W43bL;+)+D1GRaO245(EQaLjz^JqOR6g6(RoBf57Jsyrh=<@aS}}B1ErK#TJ2Bs8 z$^KOUq2~1sVxCA*JmXO|8Z+FGoLq#9ZGyShzG!9phCH@UUv_cklb;Ds{tNGn=OUFi z{(CTsoO-^vFNkb7uz1%lzMLgqyZCuDeZIxr&)BQ0SI%f}J@~{1T+l!OSD>)!N#%3v ztm^FP3H6|li;u?)2~B!aR{t7gjp9Rp{WL&Z=u!z@aS*b<*^OsQFE^$rXmLSiGmv~- z%rg|>Nb{?DBf|P3`^_F+r00F7Z&X@jWOkLWjiSzf8eRVJ;~2lOd6gv4s{ixiep*qE zG43L+Yr+^@l}u}8!Wd$47TX12Pz)wv`JAAan98ks<>_T*8nj95cSu`Xe;}gI66BLoA`?ll8NV82jC?>d*$U00{c=DRxWX|LBD_BPcO0n&=!FR%0)uN4cbfaBxqmR#&jlOB`4 zq~B?hjBbh0O!dQZZdUP~x9fTDT`uT`XslYFx|fk6HLu^4ZJ%Xdu3gAj|L%nnQO*!2 z_=5OnOCkEMIVnj=VeMf#FblMZ@hhU>(SDpZ7gJUJB5|smuP}~PJm6jF>j)FB{ zuOFiqT)!8~eq)crAZr|xQ`EdRO1?Aw+#T*hV-h;{$FoZ=euy{NRo16Fp;Q+`ZE|F~ zEiMsQ*P9g9;N0ih2_xb+GZ&ke^OO!ae)%=$exC~#Lv*BFwpDlTpL6xzj~+$hE^pZ| zzXZ~}JiGsbIt5bD(q(jq)Gt~2aoI}ltS?Rq%WYOSRe0Y`|K7BV;CJ8O^&H+^ywUU6 zlEZM^mqrcMa9H^9;|=MVk%7VT;c^G3?HXK|Se8oPvyEdcP!$-EZwD##CT>aNG`#13 z6&?qZ?LftuseA$NUVW(Ac)c8dxqHHJG}4mVg*z(+F==M~vy#z3gC+BzJ;qE^r#H9< z7h$nge6%^uV>M8HbIlBcI5OJ3ei;q#ZWuv8X3r zJSzX8=;}E(d3va}cBMk2*H-%eXf;4j9$>H~`wQS7W<6izzI93T#v)jN9zN*tTAX(Q z=6Vqk{N$03?Y@i4p`Akct56U7sS}(I?!FH`4XaPni>2FpublMeYG=!hL%)Up{`tAX zCa5p^6tCAsOBSpcu~hO~(DeWxQB(^hmQ7W0fvBt&FGL5=ye87|Gqzohp;&`&xCe*R zw={`FPWz)iY|QKTh6eMQPiiF>O>#03Noi0)i8MH9{4TYd#O29gH$WeyR8yNc!SKW5|Q2Y!KCn8q4l`ww9-6Wl6T zWV*A}7DZEw!TG~^l|h4YA7^~I$|(8rcr%h%5s((%wjl26tnxt(MsK{{$?&5OBGG_M ztg~xnKy0=(xa)n2Coh!C@_jro#bbD0_8IGXQJfWzu|LFf@?Trcx?9;I;0xx4mF*l% z2(7bAqOCAonZPAk%4b?}Zg(YRs|!ZfDo?Pn-7OBXj`F1sN;vMhM|Ta461uz;Sg|X; zsDWvC{y@S`qQnjPuX4fk?H@{~kjTYAKR;hRI*PN0>m4FM252jQsVN2s$H&Jiz<~Ht5KzLsk7;)PjD?boTc4gXdbx0^E>fFEUL<8>~!KTZ~saUtF?xhTnN+3UAy4X z8{4}ZhJOD2jf|Y0(KT0=+_e!VVy!_?r8s(oZtcl6V_vM~30fINmeNcU1NkCOQRm}b zQbj|MsWy~fRVZH4ccnuCH1MC-mSlcG!8Kko-t>lj1pD$K) zWMQ`LsyEn|>lySjdaTEySQNAL=6CX_lg3 z<7(5UK1EvWBSbI2^yuCse zPr>n=5&P8oSy1ay8h>lW5PxV$2>b^FgAA+1=BYAW;Jtn-(oj@{Xw`g0{)l*I67yZ3 z{-Vdvkgqgw^?1&T!$U<7mcsL1WVWvlpF0Hs0I*)Xiw!jU7ZE8C9{oFC295A)ZM56|({{zEmbnVo% z+x0WXm|sKN*x2MbBD^+`CwO{|=+k8`rf8DExahy0 zu0!x}7_n{@cJg{UEriwYx-+%de=f6g5VJ5WvA+tJn+7L3IUsA0+`Qh~f9j^qkU(9a z^LbFd#qQvTU2rldWL2yyE7p!~u1#x38b{FTbY<+#14umy8)FhXzf+LffBz!X4`uF(<`kwI|X)fTWKXf1g0=+~j4G@X~d zlD_s~X!)gqN;|JC@$&NXeZ#{wta-I@^bw+4C~$hIb>cQkh8W`Fh^M%CfmOQ2x}N)+1a_V^OeKm!3pG52N7m8@5?drOD2vn`5;fiR|NzcLj!!)>FrQGiqac5m77 zSfjDw!f)hN*T8c|4y#15rK*_?uRoK8n#4sABS*jOkJHoE=- zqvNq2zh-$@fODq^{|8mD2!5(Y9k5(HqU@{x51@%Y>ks6iv-fV(FZPCk=@HV(L<#_V z6!s5v>mLas^Sqmn76+#osjS?)t{KKr#*z~B9=G}juQgQ(%-Lkh%By0l3q{omc#gn>M2I+3g{ z+P6jsJXJ93uxLvg8v&BxNNSq#(Kc1SB#18!@~9a6LvtC-_jZSMm{$P&C|0V~WDQs+ zyVQn}QjTr20-d5_Z{JYdc9_W4a?O@xy!bC=5YW)jD>yR^)g^OQxO2ic$sRu@$qSf%r0FXfwpSrY}mBw zdw>56S=dkLcT!SPsA$+UpZCKZV1Q;Ila>N9g5Hu+ng}OtYWb6J zu*hCxYxw@MYn=IJ-YGAXr>6y1x2aZa*FCvx7RSe5f1;Y+JiM7H8-&muw&kDP0gJM=6V$yegouSgy@zn=Jk_C+BVM}n zB!N1FX}8|knPIZcHggNWVyo z!wNZXn>s2kj@*(P%keGa+#aoQUa_E!63(};tC%^tLAa1174LYY^;(JsqHpee$A-S_ zJnCqX{$T&lCF?f9+eSLAM*_y4NZ9z1NK6k+M zdc6sol|q7Jjz7G$4_mD5gtey`)p%mm+10h&>J52V%MQ~m_L7%4;5D6QVACM(pr)_R zgrhe-Ctmkw4ZumalRH20$r8_y8iM#fbB6#lzg<^OV5rTU6^pxceE0Teoktl#(QfjO zgQzITF4xJDdA-N}bTg+p^~X|*poBzFExL-<-&W3bfQ1YrR-`ZdxP$6Zz5k`@S(q&1%MLX#q#;AUu zsX+%i?=}2s21`nbH*dH$>-O%lRg@ArWszakzh;z!-G`mC(z0l?T?EaJqnh!Rl_ zU~YersnS3N46wm}#S+Y{;^-SiQy!lG%`G6J>@$$?#xtCZ>rsXu_=n*kkLpiR@gvvu zk81`u@(E@+eP4-?bqoW}00x#Bt`56udUcI|*C>zCG-s>w_+G- zb+djwOA*aj`H=js<|`@#JsDFs3#~eB)j!F=e=IogV&vtA0t=MTqMWZ78!!l_G+|{D zJ7NeT>JhPJsV)Z!+s#Ytwhb+zIOBc3Cdw2AMtPLCb$PMSaXp)a@pAXO_Nqmz$G?egI|kjE@lHxZ9Pk>dldmk zxxK@)iBIF{soBLXAfR0YZeeQ`mE77(a`-r;GfU;;M+tSzFX z0`Vdo3J;FHRV~t_ef0e>#*hD&L}aG^X+qcF*3Qr znwlvp|5zT6FJ^o{eOHO%wJKssr{zF5-~wUIMp$=-Xev+PyA&T(XxG!w8B~94ak(r8 zf1o=A#H%j*M91KQ7U^YQ`Sv$rJb_vSP-H47Dz;5bfTB2?F=^oN@bI;(D>qnOkE7|z zx6WLRtJFRi8ipK2L_|xB5g0t3eq8)6tuQ-8C1??m*HkL|x+U5Hs*&^$R zlDTE$bWJ(!r1t-?xZ9MmH+)%Ef<+y=x7Tje@Xrlj??I*UXED*wz$O-aaIYhWAnR4p zJXMg!Plp6rC%hS0j|l6fV&*?rM>2K`=Zg7Nol1O#ZfN#!-y zY#0WA&|^ybHQy?51HKRMjPw-J%%zMGPv}qz%G{Su#aBU_Jh!-z2*%)=_t{)b3}F;T zTX5fUFjsD;!>N99ATUKZb%(KkV}y_e1nE_)jpY}6)6VOdk5ZPgkcfA64~RhWii{sR z(zF}Zu=l=5*5sE{&0nIKIGPKNA;OLaR)}S!ItgbhzRyFpzOAv{|A|m zY-)zV3CGvaOaaVlfSN_1j}J2x?9Iy72;S680SeA`;OQx^vs*(}o&+)&&BH`b)Az*7 z%Zo}0NS@&m1`K0jV*!yXaZ>n|$rLORVz31gD_-M84r&AYSxrTiVxkD$Gtq~j$)mMP z)mkFn7tNZRyxe=*9M!^w&MJPgtLr5k;^|}gnw*?0^3DrPrK`MSjKJd}9th>DWdB*9EO|WHG z{+~1l^kR?hz3HHS^Gri7rf94!3%JheEt~->pHL`x>#uh4Xf=;8SC{KI!?t(?JzS z_2lU|pR)W)9w@2L&cs0bczNaUatF-RE9ZZ&J%_~wGj3eC7?X7b`cCkoQPS&SpQZ=~1!VW-0x+V@X^(HYF&H z71;lqY6RYbe_p1@FfeE0_7X25Uf^|ogn(ppwua;7)nIfqXSJ*&gCTzppfMj*{CNb> zX2Lx`6IM`Qn3{Di1tHDz}o)v6yBZ=KN0 zc_dHlJ#eVh)%<84JsuprVY==Nf3_)-x=PkqvE6y3yfRMFy&BU2p1H$Qv0upUZRXV_ z44;a%X>(*kMbitQ8d~lUpSfUi5dI$5M#cxt%a>~O-(+fPYCbQXfH16p{_+L-QT46@ zRPTDT)px{NDk>2xdQDg~47MW&nVH0ok~Z267=T*HtI~EcN3OI+Y6q*tj$I%kikdib z1IZ6hou+nz?^^LrRCJ@%=}sYyZb7Mkc(~*)1=yU&{NGl4BC|3xg({sa=gA@%3JVI* z%(%VSYX%T4`Z>o)eUk>|RHwNFbpE^A^nfY#ceXXA+>NnpD{*la$lcqg<$5EtPq-Pr zHZQv663)ZyL_sX<`lG6CBxrvfsmhZIi zNH^{y?)PF)#0DA|Qi1VYUnSQ`&bEr#*NB7|5VCK%9KG(bKcDtizjr2f>;^z?{vU-9 zrBeIb+Ecu6^#CU@NShOF!Xt1E>2mYkUm)Ut&`|u}o-znc9s9hXaA#@11kk71L9sCkLAfxsbtX}t-yzMm^2e`f zd}wk#6LNOO1ZuUBTv;ceKGi+hSX^FNAx#NoVP=L;AISp(n1EAzvu~d@n6&v*b9!FA zFu?Op=_V-A(##llX$R^n$5L&`;=p)&%X6SbX`j&^0`B&jEf)np5M(`ikD=r8KC+T+^ErKIt)u{TNEVS6VWNRy6E zcBm(g@wo?Vas4^HIIlv?C#>G}~C2ERBzMCBeWpEpf4I5D8DaxA6y zoMDadynxUOJo3oAZ9^8>?KHle$XV$lL{_;VJg2<(v}62K1;KE8CUB`W<8-h=;!*e9Bc)#kKauT5Z z7&KR+UaT>*^|_Z0!{>(cg`w*E=vhlXhATr&5<%hapJtcH`?-e(gT*kSOOELr$9c9- z(9QYcUjLyaK$BCAxTk~Zy83>LSl~(T;B)WEd!~)G(LPjF*oalMIgBa8|4(|G%;V<2 z#8(Oo|4DqM8rrG+U*fA^XEbooZ3!dRc9-p;4h#;i#WKNM!@y8>VQwJhpb7Jr;au7D z+Vb?0!JxNEpVKGR(=^JgwCnAgBPeMKeZrrAWrD#97kf0vuC9Oh+SWEL%H1P&^woQ& z0RC6<=Mgz=*sKg32-K+WT$NJE74E6WbtZTzpHeFUU!o@YEi%~7hqVU$_Bq0F_!FQ6 zDvyj$QUY^eK1^Y68nMp?B_Ym)41jUR=F&W`QV^?xVsDD+E!OXKURbz1Jz4Bi^r4vZ z*;IZjs?ugSSF=Qdm6$&Vjc?SG5RN>B5ePL7XFfA-$7|2zN% zpgm#qjk?`9`NiyFWS}L^)15oc*P7S4&U;Jb*^>bxwoM%8^l9PBgO~L0K3~}ox83)z z-8bBq!>oFIK3Y_jDiah*#CohQo#}y0mr%POKPLG3&$Mo@SfIy{?~woo2jD3BJ^EL1 zL`6kC&cYncIxl%_YvraX-)8q#F8z6yy&A;w`?2x#ANk2Y zKD3Jpyic!M{dbK4-a%7Odbgz>OqB!OGu?D#S|owE@2GD$1q`wml1+)GZm!?jS5Ko! z9_yXqO-8XoK&GM3`KH7;qC=n_+CfNPYmm}p{2a%6`!Q6Y{VAXl=}jx01%96e_UE0* z^R(69jTLO)Mn-)ydgqE}@k&pOwk>)!ezkn0?`W-)gUPEC%g>EV(;m&^u(bijM$)qd zz59U*XMvH(?!b`DG3RZ5-KanlqqA5tptWRBYahDd{*Bu_zL|UjtJN4J7Eq%`!$^0Y zw!LR6Ie42%x5Ix<1Qm9PULWZtatbLvfX4Ko`xBMcI8W>`7!x-yZB#SW|DHmZsQAu=`&$~SCEm*Pq)ih z%&zUDKpsa}2$@FTJQ-AdjD6Aw9>TB0B16R{=^=u)2*aOwxjy0W<7|yNC}Fb2o12e%t^BRlL6d}f0-!$ zC4bX=_B;+Ifer(YO2R*-n66-_ASyZDXZzZ8$`nsNm*KUCDm^Q`=CGVHq`oK9^ zhPH2SzlSj^N4nTdO$n=dSiZy}*?_5ce!WJ>dU^>jp{bG6SUhH{ilWcViZqx9kx?x& zSePA}J#MPYh!wNYRk7E%c3)9nAAMu6PD#1or~R`}&dA0;IvjG>{3}B=48rzT!hQW7 z&sNzt2dg#L2tRh?gVtQd@$OqD4-5Mog7D`smv!3?t4oC}N8>LiKQlxXAX?DZ5q|F; zEbdvxS%CBw%-F)l2$A!GRoJ^hv$Fh2%-&n`#@6dqNfOF)FCM;kHO!B?W_rZ`3JWT>g@U+U`;gP}+(*b0A9-;D;rym?Oenv^q>W3hq8(xOC%LuAviH z9hf{2mWvk?324Z$%44BMpt0^a%)r7TK=g8Q>pVpkzr7w}y2?Qf+Q#=o^}WduS9Vg^ zAbgyHc7K{Hkm2=kKUHHzczwPXip`>@Th6NY{nG*#m+ccVfJCRiBHUf{LOf``!36dc zV)km}%&ZQ1?SqfGX`VQMo2b3oNCLZn2t!?6Ju2xo?co-d&+WW(I767pc=%Ol7;qod6+m?Y8yLMdUg9#vwmN77h1=46@64;Ql63vFL>yR&3XcG}9 z-3v8FtFhXTsxf&UCGDXPhl8(3Nuk!)*Y*BG4{!~ADynOM3Qr9W%q#&jGq#sEZW-m} zsORUVSmDpV|DXzpk59rn*xiMTm4uGYhae*(cXo3N^#o9dkFT#hu(5PWq2ST`qtxb{k$W{#<~YI{l_rt!1%wwhkNs#!IK#|IY{*M z5yaD4S>?h&oQsFgHmVo-@d?B3+!x{%Ev^0GUm7TQyS`^TPVK-XWLky)6tXEQRuRt1 z3LhT6H~rmokh806Y+jDGsw&mzI|FM_^Yp>>34Pa%i>8 zeoYhm=tfLI`Y!X@!#9X8K#Ol!9V5aorK%R|DjBFIM@#b zm_6_*hzfZsDWN8(;LFL&Ljsi=kU?Z-HfvaD54yymKl~g${#yMEMwkz@hvi-mO!mK4 zLK++2$!lsa&{JH-$Ki;qdw|Iy)YpA4&(}?F!8n&ku+8~@0ozD7sA*_?r7#bokHY3> zMFj-TUI8n7aHf8seDW7~297qnSbNm0IyMwcgZ4Xt!?Je6*=IPCggn?PG%^L!ze#3sf_y)Cl=$+ zWc>SoHQ9MaJw;6%sCoxR&@C+Mvzgd|1!-o{qR>UqAA$4N!zjQv_T?P2$h(z zeS-nRd%~AVc+0b^C|L#xSL=k`yikjZt4!CKpi~m6hH)`wY96E2QM#BAz91PERML2U zSm8q7B0!&tWP|*s=jz=xeSFK1fNB`00m9!uki7a-N|iF{$wA*jq+b?KXMK9+>&K6; zNK)}9(8SH2TkdS%&RmpO0dMx;uIGX&>q<2{TfV@e-Ek5vobi*pLp7MKr_L%*Vq4ke z+_#|=ZTCqxBBH;TrSo~ua2v76CK(dR^)C@A^a*69Oi>YKEw{_*F=Dw~e|BTUROj{4 zc^#ChB{o_thPzZ-g{S}I72-b)T+aI7A~4rKRsz4p%16(^;9C!mlu^^ou~fK70-xrl z+l=?>!vC*99V*ikWB&c~gJ4gjH#Ta};wPHYrq_311OQ7rM8EAkaJxqAKkta-AUZ+2Ri#zl z*LGB=WF?zD>V}k3YwA94x0%A4R`Zb;j+prZqv}zcnJ3>NHjL0V?M}boP(I%`a6fW91zaiBb3Hw=ep~B zvbvfqX`vsvMvaWVolgIl_3JTg@lN32(31@MRu273JG`UgfGP#yYswXllI#JUrDXo} z3A?3s?Lxg^Mhd+}8kL3B`CL`PdFgm9kB0B@;zH|PC`SfNMY;Lv3qNX-K?UEh%2qv@ zbdt&&*nzNVjkqL2?iq?`1>x({Qx`wgZf|^@HBM{JgReTiUUkiLjNZmVOFS67)Ne1`Ze3>AiGP%Yw z8K+lfeJ0eo754pp8Nabs5B(cY>jmfEm$-v@6uMD*^}9$IeZE~*q%9Uxv~TBoepXv- z-yjz#b zNl7(40pn5We@Lz~NAv>1dodhMpZ6k@N^CCw7qN5oeCw3dI>00J03=9O}3v3Tc4eG94xxiZp4>n%+M_*Zw!6^{@TW7mTc=!8;Cr` zIyN6p$IWe&J43~|Yo>UAajkw(E}H!JAJ>zMK3^{STc?b<%C&=QmKry5qBRi1Quis-gQ>o0}cl6q907QH!$yF=C;3gsX=+N+k@ji0`TX&o2* zrSWu{kT*=dJG=uNE+nSca=p<|zE&>3Wk+1DopbbBqTj;#{7k+UO;ga!HJ~DKW*Fm^l%b&1ox$!s2B~3BQ6^Jxh#z|*>R;bm~O1cw;aM;!hoq%!#=GsVSA-o>5Ksda` zBeV9d(^o;KHf&Q5pFv64MhXnAN(YkYiP6~1s7ODHE-3kEn3cK)M9uIB~4 zp-XuJE|7+FN787C0X#8c|Mm^(MBkgcV?FjHP~U@GNpoJ9mxr=*?Ft4|naOKt5Lp!V zEO$(Q@2CBA&h+L+MZ_K8mZJ%#QOOJxIepKr4_Y3YUo4VegW8l>SKD!^6{6gd+i||$ zLC?gZ5r{A}g#SmF-s$jTr*{R6RD2wgAW^x_bo@?RlWL;pf}*`!$$^<%`ys<(F<38^ z*=5l#<>Ax@BNY0&9S=<7716NlGjnM{Kk1vaE;*@TODcc=6gTu+=@zgTcqGdxUgKezI@L4ZA10;rUJ$wa8M{T zLHypI!V>;tcS86X!(i8J3r*6XIvz%e)<>*gJExJG8> zO2N)B`=QoINxw}F-_+9!@`88P^|Si{SKs0B+LIUTDK|nU*>>0N@K3*{^^v`-(K}+K zJ8yDANWGSv_H6%Q#{rDoxrc{tqc*bLrk_r)`BYAY?Tm^QvYp=c)Y~Ah_H&=8^?RP! z9r^hrj-9DoZK#<`#3y@`sZXdPo>mjR35SJnp?jB0bF_Z(i&B8= z0gKa%1ygD*7ml^A+h>u#jmOHv=PR1aoJfBv%X4}DQPSxhCa3+`@6DiyVk29Zb2E)< zR;tg5lx@^9`m!TJ_CO<-|FDw0*Ca3yJh@eqUF&g#UE2Odrjfoknto>A5b~GZD*>0x zjwXN<{q3@^1BZ$PID0XDX z$g&Ez2pq&O)C8klAWTYeA%H+TfUJggmKXmrIP5K)v{c6Nuqjg!TY8aaRK z(eoG;xtpI^@lsHn_l>B1@T!KlvSf&!aRjpm;(T*Q^mVcAxj!%!lgwv1WNLZ?RLy455BwOzZJYSaHq63zstANezh0o2^Tv^ z>9NR7dKX8IukO3xD_c6x5H;i>T+jN>clZcd&(Zmb;e&&ZL}KZc2U#3@(v%l{Cdw-U zWO-lV#l~XNbM>2Po{8n~E6k`VhTuddp=1*Hn$@(E)OJbm3m&GH&r=LsOx1=D)Vz%< zGQ06v$F;I$#tRe@QC^GCi0!8kwzp5St;8k6PjMpMx5g;=D!)YBR=A{A7j;gUo9tnR zHuR{2S!;j4@WC+2M=eAN#@`1V#rTQ&^FP}GX8KhjLY1+Zxv}n&j%X+9ALpaYrIFDu z?1UcFAA*7n+U<9&zx=dsbf1L8n(si6sg{(!=76YjLlIj%XK0*j2t+fNeEvXGy7YzV zZi#_VD96^vEA3YT=D6%LjdTcolzo!o6QpG?)d{(zU+gfG3l9|b$o2s#$5uR!gWhmo z&WSbfi|&x#mKb`t>g}2IZHChCvisc6H)VUVFR8T4zD;c;0>dIBzTEMN$j-CDHHj4F z|H5MWp2%K=%L`Exq6C{B-gfJx)xF!yjfJp!)Xf*Es~Ej~g;}r>n5}Y_Byk`7i*7$;>t@r=`#IIK7oxqYP>7(e$3A+)*L?i*^#OUCi877`vVp`c#j z?<{Ie!^HMhB`h!~a8KIr-Y9KbPKOA`j@J2$W_&sI{MvZIK0(ML2`R+1?C+&3lmL?l z%nlXvpN0!aKZGKuVchK}L~=%LEh_0T)w{*=(VV`ejIv5P08)t=sGR4@juqO~!0?{SYiG)b&pm+|RP zUt-fJ@rC_5SO~x2zeVQf0ohQQ#Q8g-bTyJ?JD4fb(5BFcoK_rramAu_ONKyh66$o3 z5mbg$&j|T+iKe)h#Vb(5xXwUb{xU78?8L>z1sdCxYz`-!r4olEq`EPp6EpiRuGyc~ zMc^$Zud7<1&V_JqGKa3LUKQNSA_1FZ^gdzE*$xynj7ZU+-MVv}E~+745z@B49osv` z+^YurWZ4cOHLp@EF%)8~{=$YtvCdqpDTEb@*&t-sZIG~!Tll#+u_`rEuR?QF=6tti zfWHo zhk}$KA<{7*DF_HicS}o2Go&;qt(3G#cQbUuNH;@w*9nsj1&zZNU|%*;?Xe z;5*%|F??fbV>bru!<5{ZKpsOwf9oQij~hpFz@_Pkh_J5wj!ML?UZwKrBe?keN_vjY zcHK3#5~pi!`e>E7KYq$ircpI=$;^sTBD^LYA5rB=WW!$|>8DkFA33*KGl6M5v?kT9 z&-Zi+{vS-$ZMB*2m+V7iIDUXB=l&@Tz`~8FEq=Xs?~k+EFBK$SX}hoL&s$z&v!LDP zj}uAeIs3<7h~n$Cw&;j%KJ?~Ss#4uOj;>Gtt;2%U$|r~p=cT3oL_94kZq<9SJvf+( zwUNq(J9D!^&r?xsWJ~J+B2!(Q82cuLIG=}COg>{dS6sY?ooL)r&*-woK7K1LK;+O7 zoZV7%+?QOoQuM@={y|(k!SiVbzDecJ9sUtLPaO{J*`xKYuFCIGuN~s|M`{ zmC%?BLQeA1{12!?9>vN^Mq=zEwufG#m8>20qlBc~e$PUlKuhgYwM3UQSc4Vz&V6lF zT0{51DnUe4!Lmx~3_-)+SvMnNV#xLYqe|n`^?nMGFB~Wo9AY+CZJiBr z-Tv@CQ=GQ7)!ACs#_?YhE5CW!|DT#S&I#a|nu{qCS;v^jzm=MK#?q9@fY;xBI(*;e zlR@!!P|CMt6r=L1BnX*GNj>$r7UXN>yFsman}jK*4?h9}$B7H6UvfDr*!GeISHwoY z&E$-cFrdWugJ6KuFJFoyim~wqu&;myb`a)e@@|fx^YcSG*HtGhUFl(cf7U$re5zva z6~)}Xcm1^zS1}se*QsubRn=zYzyfc-j4wY8akEb-r}Yo_-MC(#m7iTO?#-KGy z5dPL>2YDaP*|z;GFXwT0@YQ%%{1Z;yVR4_+Q~d>@6J-uBM-nxKTyi<`2p)o#C<_-( zxj-=GpS-=Vx)1hB%%R@Ll!!;nP2ZR)+JgLLn6u7@j647!jAD%}DV*KC9 zZmQba*j83TIl*((iP3nr|1fb3p8hvUEN?D-8MZi1<%pB)>|jHkKN273t0B_T=*Fv9 zlvtu?!u@jRX7eS@mGx6H7@VN_!hxy_a%~&5%&xV_$t7L8aMWgV35gEfYK_h%mJmQl z79*w?x2N+dC!MrCjBwYjQb=!)A7A!2oQgYn7)uWBAb(#yWE08`sHQCu^OTI_Q5lg< zD5ZIK#MPZ&+vv#jiQzhYedFGHkAj^oYyN8?1rxw}H-B(G75iuOBcQUxn10p@<(Kpm z|H|w`m65rW#Fg)wZqyRcd)P{%;+yK=8_~9o#d8ygpY>v2ahgI{=b^6ZCnaL{bII8I zQ++%6!Mar~gQq_icGs7qHg|PDLBB|iuOx&vxmgtSi_0Z!1{{K0F zl&uI=Hsc~oETMf9Gg7~TD)`Ivj8rT%>h0!IIySW^20lLi-%oE$D{5*&fC@Pc?FPCX z2O!jh*C^H5elV{MRr*BgwfN?NpK8vBA{)7;{Q)YBt zWWJ7R&ae3qQ{F@(Ym%Bb5M1Cz97*?mSe--XkIpoF3-v^kD#n74c!r&&p*^iiD1z(R zyE#LUeo&30SOf*r#2*u&wLQn@fev?}0;aTGHMoB&zc~I`vd8brwv~_b(MqDGS`F*6 z^OJ3EI9=GWbKDf>wqo)3!RO*C$`3F_eGme=-jys;twLDbw6FkzBwA_7_%0_X2+u!l z!0zQhCz0)MGj^R=83K;>d=AFymGN@K@FR+GS)m;#=#XSo+N=>pth=F62>EoL1n0mJ zHT>RYXykM9_aax6Lv*<^S26JN?aw-st0G zkCPmMW94QbN<3nN8Y`qGXO^|Mx=)*B%HzXj+Kh=rRZ_n(w7^zr>$o!6!p!0X^)2OX0%NFE=6=QVTknk*vi& zk!F=4_A&r%bf>fi2BSukdi(z2dD6o&v8nYY`%`>|q~=@AYS4ock2HZ6{4Pc)PbASv z--B&&ZVX{Ztxq(x-K)!sc;Zs|*;|Z}D^5aB&cBSVzFw4-01Et9pVF2oi6ixLZtp7! zsSzZzQ_r;ldoHK)B)<7>Ud=dPz3r+m#fo{0$b7$_pk=f#4dZ&6I`X;QOR|;0HMpJX zh90@-Hpk=ctO*EZ!eR3=`2x);Ge7no)hIorg5|^}I*;T!`QY^I;S@KwBD_$_dk5-}C1fNqK zw)U-iN9l(NNy!ZRbwQdwzMz;c_9e@tsb!9cO##>Do@#z7Sh)gS1l4lWq5V!emew{O z8Jikiv8W1fg$(=TJD?x3jqTXJ&Hh|>x`esVbdRKCeF#PBa|%~^2DAKDeNNjo2oL=P zyqEFAFS;`0XFWV8ZBsx(m@N-bDU#%5L2NkrzcO#nvDch(?J9bp(C~*|JGz0)%NvQ2 zJoehG#h?q}VEoj;D@Tsrj_(ZqZmA_^H9>T3kX$pla4>9=VYvsZVn5_D_BT$5C7Sux zD2XOkP9fu#ZjbQn?_dhQ{1xX3Zg+|tI)rU_5&LuFEA|RLy`Lt=@2e)!T<@`vv&|B7 zdk5Y$)!9DD+ zUTlk8iGH1Cz6kPmfgV(Te0Gw`a^kf@e>7`AqG{qIAXVgIn8wPXUqiu@u`$z%Q0BN& zdYtL7tVi+s`Ny3%EVQ8+VEJpskNg4^?NGN%^ps1~N&ViN9=l?&6Xz1j zVAj=eHFw%1z=QV5D*3xI$@sYy$*PL|Xg2Igitoq+^^}`Z#A~tc{kz75JYJk(3vJ|x zydgo`zCe;mMA`>f#7|gK26~uQ^6aEt1n9R=#1>e->i%(*rYT$p&2!;pusBHfu$w=R zpN>1Nm@t}u5$(19w%AV;Q&@ib5-1bPoRyi6yL|8A)D5@_N+h`4QCLp}Os&Sl2MLl#ko2c}+2<-wbDr!lq5_D~ zTtC-Zju0}JQBn6gDpo%VN*^0|IU^jE>R#*k{qnquGPFCBLn2{M$PZm}OjYwfvI$*7 zHQr&Xi*9jVN`S5l{coi&`y5z`o~m9Uxdz$A$y1t%$soLMFphdb643a zYR}Jun@){gOqpq;Z<35Tpt57+jw>)0$Kr22oUQaKzSXp|8%oOgwKTJk;tut@FBqz| z>Ig0ExGd(~T11U90Q#+wrp+R^8NF=RIce|f*{I%Z>(lXPBPTt~8*EHlK2-yKk5X7c z&!6jEU)fguXLUcDea$ZM#@AcAt!Ce0ErD1RO~21F_RLb=#m{M0NjA%aIH$BZPa;>lRrY2=C@yJ@!-7 zS33`XvRpfh?k0i4Q<{gT>kcwh{c5Uy2=e9faJA$x8R;8pIc}gF{w~4=5Sbq3L3#Ij zVZKC(1sjgqh4&NRQRTSKM}ARnKr1&le-Ulwx)z4)DWIbb z(E3af!K=P!vI;a*U4-fh`9?8|>6%{opb=5Om!4y&cAX>=J`j5=?`OWQl) z$`WAEUZmw%fhjVzY`JP(y$JqQ$%oXX7wP23?8|v+rynq#+Dtd>4CD|(aAQ|6xL$;n zM~a6S^doi}{NWm4qY(aUFstqXBf06t8qZ(K@rpx70<#Tz75^N3X==ita00Qgrkeq@ zp^iVI8*a+RZbf3?q}2<}Co>}}X}fI~PB_wz5HS+%RX}fXVB% zaddm}5291vMK5<#ebNTx(oa|5I zQrH|5N04P@t3Rw&kLzA_EFs2Akw;uBrQDtivzra~E{PB~Yw;^uKUp_ty(F$pod`PD zA>t9E1B5y=L&?W*O4Z|9^9&z*7kea;*czoMC@)cp$S zw8)yNlF!Em5meQm52g40S~9C9Ar5EVYXEtpNjxmB=%-Oz8{S!3SZ3!#g{#bwnp+Ko zt*EvnavpTvQ`6F?Tw)$Awl@<-n#PWaR3=VUe{V(B zg8RX#A*e%Ua|gRqUB7CKGLCOcYkUKD@VUm_yk_UQ?^8rvzRo zS^+ROwS;Fx22SZHE1*GGBbyRa(wohqwW?-dGB(y*?izINJ#bB`{vT;F|JK~1!T%hy z3DhCgVh519d2hm%)g1$MtOx8qZlyDW4I|<-&59&kvO&=RMBWZ6 zh7;WJ73$ppPq2tvu z^`ubjXaD1u0wCgdo?;9bANgMbnIRb|X<8gb*~LLYHRq!Tr)nGLSL07}@|ATPyah6) zIZvjA?z=SzHtIcoGkJa(?6Ua~U9ZP|w3B>%YU^k=8Hx_oK-0z=TiEK22^HyyyYKMz zvnImsyL;eO$j*J#;jDc*93Nr(43sIkW#L;Bv{*9+nhZ;6z_gvtXk369wcc-|Ms;@m zRhPL|)bl^xKiC4hJo=v-*nfQ<)i9kdHBg9@FI^}DX4`EfyYW9JvDt?+uQJyUG%O9P zDP}U~d1mP6{BM zaW)^qjT?w>tuYvuw=h!98{{?L78LRPyhjcWe#9D(uRn2WkG176V;+UA+F9=Y=&;FA zoX)5oyNm-3yxayaUe0B4X z$E5(_1u+kIO>Aj}dEUVa84rE+?c&!?$H4m^D-OD5NOXl`L^bJHpwH>8W()|-ZgaTO zMN369n_H0$?p=Io6zoPfiP`^z>oRMo*w3P8vDIIwlMk^Q&zPh|uZ6uvZdf|#y=jTu zmA{r9g|K|fBosa7lummc4b11iyH@jm{KH#-y@J zx4Le|ym2`9+-5$BQcjN*Ndk`|IRh}BES#>q^S{3zs&bb6Q`y2ttQ>gE6%N%Yd9|u` z>|zQ2*AWZ=Z98*;Q?Jf}R!v>q32|%!@VW4OZ!TrNeBqCai~E+6!b7Yl9i8#twYf@>b+R+l=->eDie3zMkT zCZ&>pIRsK7`-g%ih(${@7-d1tZ4jZ;y*%np_qJNZxNj*EhW`{mbw!8uq5dXqyd_yD z*!RPMBVC$aw?4fOU!Kg%S#ca=80**CFg+?Y zC!JL6#f_15<#PXh;a#y>kvHRYsvMNGdD3g3XxM=u+_`uuFWb?opQ7K$C_F&lqt-TG z_bn}%?xMd5I9?M3jf*WF=`?|hb<*oHi-gX{# z4T9-ojcXoXGmddZyx&v5cUu*+mzl;}2|4lHa zjs6E58kxA%tv*|wR-%;4Dzlg`BaecL^v$G4on|WlLf39Jt%RVC^vsoQFqwh2Df%6= zxnCoxk%bM<^4C!cF=l)s1DkJ6E^hH%s3g1Iz1WtRVYys-TnJ$8B0C3SrjR#`2HOil z>67+j%YB9o*MBY$@qZML9S!@yvf8;toTc?O?R;<#kt|xf^tj#BjwVp)v4`(Up$597 z)@=6YK_8#|S>aM>zGU3Qy&Cup7n2upWvfdA3dxy$C}QUfHBM9W0}j+eItz%J_#pp)wA>a@wp z$QW2z<=10rgk7-YUJuLTK?fBhC zcE&wC1lZwq0BeJ*Vo;+2JcH4UHU?LxK^&LI9{}izwEySac)DRf1W-(8t3lHKIyySW z8u?v48XX-4%zV3=J+A7Q8w*bHw&{Lc&xIkBa+LjWX^*=>#oNS%G@edAu z$fL;&1rNTeYin=64-B2&0nB4#3Fti6i8%D@37|E|3U}Ba8^-_ARFLOmk%6zRaL@k8?2?z6 z9nM=Qq>bpnSF}-^(!tgP$Ah+t727wM7E<$LOZ9~8mcna;$r&AuoeIaVol|ZY=^Apd zXd>K~gKjLJ_3Azg;0zb!K$+jq)=w<`@b5Wb_#2=>*jYLMHj8aGMu1K`P>FBg>v-3z zYZ@F(+r*63yBb-Y+D^4&4w+bVNT--FFlB|hZi^Mn?JBdBbU{aLj6w7B1&PX*;FSEe zL7Br-kg{ruv!N#o2e(XyxAVfetfTDx?yAIx^oJphjG3zkSQ!r?OTg;<`9&KPa-+aJ;mWr|{+B!?QHJ$5tAw_8ihNfx$(^>S&snzUMZVwymK52i5J1=xz6)SBO`FpG z!T`5`3ZQ^~&l3W`09^N`l)83zi#yaj0G-$PMQiX-lfHvOFxQ-ga6M+s3}fhSJ9um@Y0O@DI688)HNwbuF%h(>-- z)w#8!F2M8E$(eNwLKPYcQ#W;uU_&FQs?w+3Q&OLD;n)-Qh`WfazHMSi=15j} zNVqSS8d5~28;4r=G^2Lc9t$Pc=-7}y#HWa)tlBu?CEUyF(%T3Q3$IEvOWPBd-g0PL z0Ifyhq1#Te5+#cE30=oOH(!q8%v5e@*y%V05rfjx&R^Om_r9sCu7(jnOkxr63f84?1{9tyiP~FibV~wV6>R|a+@_XCjM_ceEc3|jv z2F#gm9hpT>dUV-}7oZ z12t#U^$r`S>-u(#IEy16M3OiEMgh#aQpz#OJmEI$i5}EKWmF5h+R_)N0r3jqS^t3MS2zTccC+(McO__zzYG6ynJ*9nnAkB= z%FG5H>4Q3dnCDH})+-Qa={(qHpW<}g#3wIOZJZ!yc{Es7WeebqBJ;t1q`>p{JLx;8 znez=Ta3yP=1EV4*cfoI{Np%lI3n|l5S9ypw@*}QmA^_OVBR}c)!($djGt<$$@QuwY z?X16|EeqV)0B)A;49_c`qkU#D&9%CN#q`+Gbh1)Qb#e8GEYBGfSMEB;(8WH=FW}50 z4iGc3>(OO>f!uu z9+b6LTrF9DvEl6`wfqAO-Aj0RtJJO3%MPZzH~sUCPlMenza^cJDF^UhWiVcm)g_rq zsfYHpk2$;3zeBR@!T$eWj7k6!dwhN#+;5I7GXhR7uNFGMmBOZm>gwuhd#;8Z;QSoV zT4g>L7N!FH4pZJ(|E6%{p2$(jGzK)47}2tL?(QYknRn{RzfJDXA|lRB(+rIm?dzo8 zg+Br^vF-phl0S+#Sr^BFp++A{*rnm+ms+F%7=zg#b^#_ zjpbYsxu~>a9?@JmVx1PouNA=HKuQzHa-MfcAe7TvTe^FnK$@#IS1{Y zvS{JfWrK&*b!#G*I>~FyaamnCS39cQBY9~hXw%8*9|G>V20G?mKkdtY8;&ryo|Dd< zzxvx;Nxx6(Z7YFai62bhr`!-161UHNJKHeTg&N>^;al@0a!V{4%R%Q^k|ogUdQSHZ zw93>Zu-sb(940nXDC)gf%I>YT_I~?Q53K)wV9zYAxwErcse1kprvPTMDDdUsL(V_W z$Onj6d+o0V{4%7fYF(sE+%hEW(?dgcs^it~^*G92B~4e_YL!_;CffhZ1GB$k-&@jG zQ&j3ERdc$p`a$C1tT}BhWfIyGCiHCi*YEmYkRxQ8_sC5KyxHo<58fcLBbTw5{%hU} z5!IwjwrPzdYMWgd?q+Opkk|Qd+yo#Eh-*Kdot>>50iL<3qlE_bS|~L6{)4|Z_Jrig zfgK&Dx5u5C1N@17eSL{;Iy#>63JO}aAg1~7cg0oZ+@Z<^@xIgp3LkV-V>*h*``!zG z1#B`Y|2kS)a&A@33;e3C{)o96`Hm)Da4Ig2_{XgpD?5Aq#k+U!oQbzoeHVaCAx}R! zEv=YFeZdo|N)z9Ltnnnf>V8cv!1n9q7f8D93-y$Lk|-Nn&L1~Qwn0tI_>!S3byEK6&?z)VYXUZ?g8nd7&0Cx0q0LSfS#`f7??1yvttI(rq3}nGCBU{Tu$k2 zo%k&MzWJx^9&jZzK!_+Wm`HlZ>p4cYV9=0CV@1<@Z(HmQj%cC;SVAWCK^qthD1nQG zXg*mRS=-wSp|9Y3qUcR2in;cuR5%vt&conB-{HOAewC63w))8@GcM&`2%Bxon0BeG zrE+qlX2LViEt_V+tqL{Qy$&C9zbh2>%m;n(=*6FLwiQ7r zdv1fH#q&fi3#!tMqSrKC8o(V7xQQMpc3ic7#e7)8%=ZVZw{Q{5<8iADt|r|o_*OPt zfDVnVP3Uv>jcznbH>21@ALBM!tCwHyupz1+SHf+*RXT6D@B?E@=yvACJ6&-22mGg8 z3gP%QFMc$Getxogy9)g0#>vb^h}xAeiy{AL8f z$ujT2&ElkP>7dB9QL&FFRb_XoOpDwWN|5MA#4qf7-Aj5D@kZ;#skFIRCFa^qeP`v1 zM|z;`NZJcXBvsxN@;t-kW+g}G9U-x3*9!=jjRPLFU^{G2R9~#*G zcH{UEV^QnOvDHjJa)r-*g0y+NWOQ~sTC7_*r_@|FaF)1+$Xarmm|Euf;miZm&L#VUS=6sfuLSsUN=x2Z8Y>&T*hmi?36ZU+9V%a9nYBoHIYJ0rac!YpEL3lWPfcH zn0_kDG6T{EhvmjjvqK7`zugvvd40mn@Z|1F>2Jx#W&@XXV7W|94C9s^e3i=pW5O@b z10t`lN%N#v3RK8`Kj7XQyQGVyT*J)Lv%R=|dEO^h@w7<%hR}8`%0Bn!5R$;u+HY}9 z9>m(}tvMkavkSvqt%EbOqBH!%bvWt4sfSBG|t)>^FcZ}J=B*zg`;|KdU;M5sdZhAV3o{oN+u{R1R z0}lnmil71FO))9pAduzn(sQs%RZqD0YjgJ=pFj` zymotvpNe`bGQ9>}ty;0C9@%#s5IZ~RtXlk~q!Ysmi6VurjO9$=X3hfK5r<` z_ysP1{X0hs8!0Q~g}WavP*zk_Y?&X@^KL2wmW^%We<2E_FpBG-_a(99?j#}&glvY^tNCire9Ks|VvxsiyHMPUc>Sdi4k84xUU_qm31i z%a_z2=ABfGuWa3?8~g?y1*4A(%1^8OxGBjT=Sd=yK_Nu6lWl%0m1Paf(OK*TYbS;_ z#t>tZ$XaBNDT~nFUIbqmJle9#zb|o;0D%wkc_kWufmus_N=Kk~%#z5$5km_%Z>gDdgg59CRg|v`rkG`HvQX{^lCR3AM=!6 zqe%HZD7M?cc{p*?Uk-H3Vu?ra`|&<`RM{}KwrKZ6OZj(Tt%|#4DGRrQ`~#HY+3G({ zho-!?Wy4>$S$-;xHwdGTEz0afzdJXmyhm^;Lhb)*rfw%13uY90A5RpogMYz8r5Jyo zJWXUNv={a>FDXj@nxpMA(G1tj7l|@Tb{^S>mxGngkd`usn@G!*p!-ICVOZXU0mwjS zdV(L7_mJL&7A9?5Da8v%H?>7>1a+UK_Y755uQu3M@-z*8*701|gc4<+8vv^^!+O-& z8c(*oq$+NM_v^-$!7uuidQ1ftU9oQoCM5cMOTu1mY}phr86S!@_3#pB zwds}ln9Fu)Qkmcl3y*ojY2$>qk&bZq8iEiC^;RnhaBi+?wUTxF=5`=E`G;g2x@+s& z;-@ux*_++X%ROX-=R>YPXEqZha3Wta9|GNmmz(#LR|TvEp1Paf0G@EOq45b#kqQs{ z%8bgC8AlB#uA+-ISn}z)x6+C)sSwSz56@VB-@gb9Arlv4S=pd`ZWBTnLrD*9N3>c2 zD_Ww0-2+sSb2?oX}>w(qs;h$xvEjRqQmAhCZXY*LBU;V zbEVQ!Ugdn=0VC3a!xRk>ijV1J(*%8g+(g|`GY<>nG{8eY)yI!)e$1$u_m_%;-2SBN z%!%W2#Xh}X8WM&?DS9G-yJ@`FKV~;gwEex~A&@~|T3gaB{#)dhFC+||**M&ZE--X4 zTJVEZ4ChsRL>boxi=U`8i>zoY2>IZP&#@bFDI#DtK5E)Eb6dK|pFdp-%Y0#%$He#F z7Q~oESLEN9nYorLrdiHCu_K_TX^+tAH64&6x~SABpr~Smft|NIYr zqdPz5pDjxbD>M>=`Viio>Kf+d2O>i1-Ei5}a~c?$oqG zvebSp+gheCvJ_FUf!Yg-`VqXR}C^}{FS0v7jAtTbSJvK36eKZTiWu~M7P||>oGC+8EV(|ROs@}X4S0x zcjlhr*q`4{yaW&-`>i&-?xfvwyu)) zq5iXS9vK4r0y%E*$(!JGlHZ6Ytx0fx9^Y8$noIqfxnWp{s4COz`Dr`bG#e{vcW?XG z*WNlg=j)oqUKey`si8*ge_pY%hA?_XBR@32C%3{lTN1oY{V@1BC>ZOmpjbV~S=Vg? zEC0Z%WD$iNNE?`JKkojXgT2o>PYdWm;D`0%7<>7Oq<-{hseo5Q@^fU_Q-u6NYN$%* z*WlL{AtD%ujnElPf*f>L`@o*zS9Lvc{#ugW+uhz7CpGK6Ich1ilPA2xc|%v)x6B9h zep}B44;)4&AZ)upCB8Hxuh9No3zi5sP90g}(On3VdDi^eUG{#qxW^MYPO(ZOPcic4 zCH$!Y$J0vEe1Abax~QP(;LE8D$M5v7z%f-2WkU3w4u;6Fdjs3ZUl z@wdt?`FJq2UIU?90$ir7f7`nsp0F2NYl}T+8}Zp^F*N1$*QuBQN?p32UgUsC4LSee z1{-zq`Cj!v*)K-WpM$UBVQe_l%VA@hYandsLQZXqxj6RD0fw(Gspb$J`%UH*WbL$d z^jwEm1)kXwHsf_Snmavhh`R%^wIJEN~O{N-fExWwIFq} zoZzY5cqQmeg>d<}x0!t_FY=47SGzf@`SMh-5l=d$BK)0hCb#Hm56!t_9_hIp;YmwH z>rcZ1eaNsPkK<3T1p?*v(A3G+CRkC1*#V5k_Ot%S@PbGEr?Z91Qz-W9>zN!q57z2l zP2){OZ-vIzJ*Cn6qT+tcnlzZg!LEVGM}aG;5zxq-&vl_pxCLKUiUeS73C5?(vpqD|6QO}WDI=mH@RGnBz`)B1hfe7nwo7gy0y zmo?z3={hzHtge!J267@>@aw7no(13w2<-Z_P7^L+*a35XsTPD#bWzJv6ni;sK|7BYdAlL+gyPezhU!9b^p5VpS7Jh^aihw(;6%G(0g%7MqxfStH>`K)(`td zvNcNT%AL~e z`&{f%z{sg@4HXGF&D-Yd*0J;NkDQ}JYt&Rk z#T8#*sa!l$pZ0gz`(6Jc7tH&UbQErnqPKU7(!BA%G{c$1(Mn~iq@{1pw#zJQwtYI#a=Fh-&KV$%1NP-6RqN!RI=wR{ z7XHn6<02vGq3r5(_pUp&=`TI_6F*u3;^dR!)W~0HD&GXRNbNGjh~>Ue!5I70N-qL= z5YOiX5gnif!C$86bzK-QhzgV(4w?eON~GDk@wYvo$+nH%n#y+{>RU;~#vm`^{fa+4 z?DGbGUZJx78-3h+_nh5*{K+9|^I6zzsmZI|^aQLh7TxNd(yuMx6Mdz7UP_;@!})4< zqXM=Z?Y@`TjxzdA7o-U8;Q7GoX23-FK7JCOOr*8C6zC@hUs0gRNRCn2hl`xGHgWJRmVc_e;Bb#wAR{fwDRjTl=Y)r zh%QDoX~<#rWK?N4>@{Mtf8c}kWY7*ohT-2Z<9!v&wI*T7qj_$}G41C1&v*>0lWUv` z?L8r?7b7Rc`a?i4ss?m2v_-|YL}-4C)1Qb`ZQpB61wAs$L=nnG)o7&%bO^tM84dVe z6=?ZMPKbMwV~*r9?6#C07a$n3-LQhGY&B?)5fQqx=e9~*pi+KSoqpKJ(l#7HyS-}S zed$(P9-`IuthxEK^zg6mc;i+SSY%;4U?4zcL1_WW&ze>{B9lu=B!dy+Y7A~AGVO<% zu(MJcYG>6@yzlcyPwAI76)Ae-H{dA?+06ZxQJL(vGJN6>A(6hkgUj5 zNi7@rF5CZz^o1Nq%jW4Sx$=yW9BULe>L1ii*pd)tKJco#!Irg#t^gRo*1?qz| zwa>dR{&If$qkpve0t1Wpd#er^mlDckU%OW06~)FzTB_#4;5@}MFX0t4Aqc}5!P>D< z<}m3+6`Nx6p~9taRXqlLBx9-P-pTmm(DmE6Z5*fTznO^b5TTUD_YWH;wF2Ws@caGG zt59#m4Sq4-gFM=|PyFE=1D*iMC78Lr&DVGSe35XrCx?ab4ln<#b)K$ulu`U%I3nVbT>z&`%1M{D;MqGg(vrf87z(=N7 zl@O0WU|sml_NtqIDg`{rg+eu%Pk!0Cp;M=&fJSJmMp@D{@MLD+;K9c2*KbY_+3}}Z zM5KrKER(>>zSLi9;Bk}E3GP}CmC@dJ4xBS*SL z9`o`FC3V4XgT}u9Zag%8NkdAl5WT^sTg1wd*=jv*wofUBAD)$SM7m|POWE#9NlEe8 z&2TS((a7z^CIJBJ8m&`h+3yT%_1%E5z<0*6)C-go2PY4(@M&1*wcyWvP*@#n}aYS#^XN5*gi9oUXH29raBXku&~TJf**VASM-`A0WUR+mYGdp>ZiBb zdfc48$_kp~7MK$03w(oGB8ySYa{=FLS5F7SQ;@lVFYdoyd7bUZ?@k^M{Gv!_FAtU% z57jzC=YAQm<7{Z<;&_RQK2pz5OTX^_{Q~P@%$ua%U;||j;zid5dyBRw>6u?8|0c_b z`?e6~Kz=Di9|Zb5{ubR8yA@O_0gr*z6~X0c%hXT^P8fq==O^=>s_@PnFrM-DYYK| zi?Fv2sA}!DhZT@6rKLgXMnJkj0qO1r>F(|hX{C|w?(UG1?(US>zy|hj;W_8M_nhP*?Qr0z+<5AdJrstYw+WLdt{%}0^uw!Pn6d!3&Lgc~!D)`+`<%TX1xI4=3h+uQQ9_D?BPF_oaV11mMy#MT(? zhnDLOA3vf>T~xN-I}`m?{Z8Z-(aq+xNWppPvC~|>9nU3urqHbXUD&>5mF^jr#-~#?>=TPE3iP;O$r+*DX&c z)kXu!iCg{IC@+2bUNDgHQF6aFug9Gw<->3t8tKg8hvK>;VYJ1Wgy8!td=-FMg1l*2 zN=V>TL+^$ztC{@5!s&d*WGq@Rack-DIfo&m`{ih#x3Ju8$8qnEVh{@b0 zIs;LRrZ1kWbPS-C6a{_R$JJL1M5ujXW@)ElAlOwE6(IyQ^)|dpq!qA-`%Kt2yrwgWw9&^jsD?gwmF%U7=>wx7OatQn z*$t;m_CvuT4Q7KO7%}vZgbjwoZEXsM%N%Tuy*oRP(|KMQ@nYT<8~0P6r*IANHFUnO z?5*TOTg2zK>|xzF2(4Coj;_81nNO}IxZHaYtL9nv7SRvk&)0H@wOxO2`Xz5fDs%s> zRRsiMny9I)H(N3nAxdQEG2R| z7u4-i*SxT1hn1_l+102@>xJJGpgSqKet?)03oX2sJ<>~3fR>M!5uuwpBS47nHdvN1 zyDK5lhj+e^MAWB3;dd4Jv;F*2K;>1h#2~%m<0_UH^cW%g&UeeZEJM=LEe;mDvic0l zze*hkg*|wrC97>8baP6FAS^Bo?o4li_Y(H<6Z4A*t&7c>(HXo=w@rg|4?s|dUvo1z z;6iNVbU!&Mj|_+ofW$5!1U}f`-yhkueLGR(41C(&y|AEeyb3xy^8unBj|`>?%OMygOu6 z!?x_vv`|^DYa*VgYvQ-{KtMqFTmR9voYgcj%MUu}vj{9ukFoLWa* zf0^eHZsP8otU9|}vF|^_eK}C~_^!2)Eq@A}4FHypaptv=ujLWQfA+$Fol6&A>BQWNcRhS=opYMzJ0wq%+F#nU1tJ#X z#t79ehJ&s-ylAvV_XBssC)dM9uWph<3w)}&@|i6?SbGj$G37N%vtaalgJ$V6tLj}? zX1F?wMGxD0O+Qnv6MaQ%oc8S;WT&~+TFrb-ER}FtoCr;^p3B{9GJ?(9AK6=fiWUS> z`gGO;2Y%JVJC0AjBF}f~Id$Ox>dU#v+dL=Po&$Qg>W!v>7ux+ns@p-&WRN`%5qKP< zDHqr&T*b*xR8SE1zb{qCySjxjyAN(pI(fo|?|c&C;NYFC_Y6T`qyoKnTs9h(tFCv( z^>gp%T@na-WJFKOTq?J4U+ZK{>TK76;Iqa-cC#G8%IGhdGjYGpjN1~ zli4d6#5l{}YRjKgTjlWe4}9#jVJ|BxzF5QsMXwAs(H*J2dwFiZ+8gDt4Q9A}8{wYU zzOX0n5gj0M{;=u)-1;G^Er%#5@?MH+mDh8nC#HP1B!{f(1IU*nyuwvJi zXfK((`Qla}*x{?m0fN4LtJZ#xH>)AM^ef1yH4ssdrA# z+-#c;@I}qNJExs^aSSKZl{yBS)v9R_hU#XU9JS2kc1QBgWxo8|(*n}*i1BvlM+K6Y z_d6(3y|N+3=sf%PEO>7vqP4_6b)Gd7M2sPfb9J0%ohKI^Ng7`9-!&IlAdDYiEv?laQtv-5XtV*+EcLRvNO48cn7fS4{MJ*}{<6 ztC$w4V_1r#c2~TJm|beqnDSVz)Ca~7oNu6nD$>u1B!4qd;|CRczTJmGup~SRI$5UN z1(vR<_eMs!2a{JLD4u;hJ{@kMF1ZrC(kJ&s_)(a}Sco7#TvitJyss*f%Wb&kV;INN z`{~qsv+6LQ@}5!Sm;g1NS9Ba4D$+kb+VfiFG*`L|>)sUS-q}6gy}~dijP=cPylf&~ z9Ytb|wdBDoKGh5uo1RpVT=eG#oc3bd17pIE?hxSLT12sxLu$J(A&{@@;y< zr}AcX<3txm?B=PKJN%E&=r6F6?l>)_}@$P@aUzb$||qbSfU(&IR? z1{d;J@A4hP#&BA-<)*f<=I46y)iH7a8|E_#B2)dW{__lzjYh^El+%yMx31ViJ?4y6 z605AQLWi<1%;j7jrC&0m8Cs_V$?QI=Fl?r*GP_URt^^?5T#Ys-IHzS^M{23sL6V#1 zA=6&3yf1ra*=D!&E_H6%@7xM|&9Kx$_&=jSoCK!s%jRSs)GyV8Om?nR+E5Ot2Ze~1 z)>H3zS5oi8)Nk4QEM0MT-*6~zKd_+@|F{#PN2o0e|5!VAp${%|NW+vW!M{BywZ()yAMglRpZ&PnJD7(5Nht*9vf@|1WYq69GM=49O%8lJ7TnpJ{ed%Te#rLSz3`a%ilEfVc0r=l0LPV@A zfxWjmh+WM4p6MPx>`bb_vz^PG&ha#s0$DY5*W^0L{>SyfLxI=)RwYMYF92->QmjyDi~brPhBY3=O>& z-@X^`-lw2?Rp@q7n{tn8HPGv!LM_%Ftkd@b*ZXikTDLa@=R8f*7Vq`dvV-!?h&6ML zwJ?7`82Z(Tze~;?f*2cx-o#z3skg7E)SU~j*d5!HIIm>_->S-;#h$&6wN78#w2)`x zOI0SPmHAWeEAZpZm~g_Xy;+*!0mx5%R~5qHgH67w9`#YHmWrzZ6GK~zJfmSF=d$&~ z{^Hi61QpYjhDf-0y!+#g^sbdsjmdMORQtNC+*ZC>bvT|j{VF?@>1^sy{PRnPt8W!Q z2ygoR^!Db~epDzghVO)tBI$IUIpqa~CT#XVR(iR0Qf>ehR`rdAi-yqyvQewLGbyjh z`XWbHW+WKZKu48ym6+m6Y2k-ro4FAw;i55b)Qco`inzb@4_0=-$iiG*X(!~B#B8z) zjnLJz&^%pKR#wN@r+;E)8l-PXdD@*fO?v=)jiIHmJ-++KpnuX?3ho-o`ys+LoIEzw z{=vw?N}{PeNq=Qb+=dHszkA!C`ohI_Khm4`d$`+ic!mD)^KA$l{2m8F-o?6AcMHHp zu~QI=lEvsK#oNN*^Si!8^TK>vZ|w~+Pi7U^nvM`mzssYOS)zpo2ezOD%RN|pDKTWL zfP{gGH1b=+2`P~xQYx^T;+oI8hsi6a72mDvU{r1#dVVN>lvRo+1@C!R8g{+v2|ucg zl>Hi)>A{}QhVJ3*`cwnVJol)QZ;6g*X=yH${8ai9G%EJ7x8*Y=zolGa%C7NO+d_1? zwzkhS4)MN+tG;)CJdUz~xIXG7TZYWG%VhLgQX_?&L8JdcJz`4sUyUPt13C338zEdz|6N zM|(ydoYu9!z6YIR61Y091g?MS=7#{G= z3E3QatkDWySG%f}xYcJ*w2~G)9;Wmb_j;rzix@1CqUv%kZ~s|f-)g0uLA$@@6fKYKkuybFjqoIHFo zP?hUV5Avn{ibIKMAz-=lz@ z25F20(!;PN{`kT(MQ~;r`ACRj?W!NHONED=hY=B}eca#(Nzdk^c5q5{Tc8USf8PUK zagZCy-OrCM?!g5lWZC$l7XwQ&I9($TvwnpUCnBE;xmampezm70|GG_pS8jbdJ!ZTd z58P+duTvT!c5GbSzeu)S@&=LX8k=|Yj+WqSALY+iTn(BAzzNqcTR_JyFd>vuQtqgd zano*OX38}(^nGaEp7FUzJoG^!Wf}_;r|XNh&js#Z^Ke*FGu))c$z7ZeZ!Tx*?fl2x zy$OC~YPIE^=Z;r4lG*cbg7)Y)_diW%$VIh6ej`*m$hH;p=($;mWMcF7VTq z;al#O1a8c#(W@;n$TsYsm*%baGyk5co=}nxIOWp}-*iLq2vRXwrEGGm;nQ>3iVU9k zAs0Vst9!8xd;K%=Q2#{bdGh5oIsEvZ?Y%b=?wrgNU1R3Mn#tLW7Fh-Hc)zG_f+ktE zaqiDIEmt6o zze8781!EFRBPk63ZUCpge@WVymdTDm!U^C3V^cWFAMW?<;`-qo&Kk6)dUd37Pu~rr zKlY)Sc@Mp*x-P!T3#sF$OAkEfZO!xrWQ}e8l9{g&Rxn`0$TA=QdH(LJv15sOLK z`StB;)gv+rLUo zptfCZR?*7-1|(1Iw~RDN3*hU}*1{-aQIOq2w8cic_TOKh4~Mv0bLqD|;O+1CnuX)* z=pvo#tcS%W0nUU+sHe)K6((Q3pWx1H+C0+>{NxrUsKytZAI6kvL(75?dBa$ubdUW) zT|7Dg#n|Kvts5`LSE6qPPF6GY4+z@wL%!C2(fod->YIY0-4ph{HY((6bUfJ}t%xo} zv8A#xc6H#6?0bJnuiwWpJ!*c?U(L73)Cc2eUOZJtmyAe2rHqJZHPWvE0|$z^Xmtk- z-ZrXtZ-=U^9~WWM{MU|Z|zF*5clZcmDOb0Jut%F=$q0}+?J zK9DP4RvpoCMB};k^rKt}l|2MZe;TQ2X_b-+I4>?PgsrT~QoqLSxGnwXGyM4n2R+hb zzx9(fRN=tqqDH+#nrQC$a2C8(C|OxqKxDU1LIM_mnvK_4YSfrcK!LCE419s`Cjc57 zZ};{-T5TuZ+1aT&*71G_yu5Un5Bi!2U8%Q^@pJei%qG( zSY=R+8u$uxX9B&u8iv#z|5EU*PN9hQ7kayLA(#Pn1vFZqq!Td(&2MndeTdFj-|o}K zdbZ6fi2iLxnGX8Oa|~sn9A^o#r$K8gqp?|39cKOlvPkOCMT@&QOH6bi9ag+pH+S1yli(PPPf%9iJmjd!mEIbLfzVZI>sHkEh*!9m2Xs;YES8RnYu&6@%CshY1`4XfE; z%XG*Pk7XhDV0;xzYmTgOqXj%C?>f6OgMAfD#EZz%g9LOCx!@)YSkXVgb5%7HV6T-Ky0UZV``dQfA zfP@EP2_1WvbF6&pmY}nE)k$bspe8=%+L%tmS~e{O)uE;_8Q#!Stu$lBR#Hr3m3ED;3_20=SU|G2n zh;Yxx4$V!UjZ68Oy|w4z@l^Mf+_3%8{iMd;$X^hT#v$9z%(dklBa=Cm_8`HY44Oc5 zu=L(SJ&roXW6+0NmRi9Kcj0xTeZLOW+`01!er8bh=~=&EW54}e;8=${<5J-Db;1XJ zbl+vT==GaIq4zG_**44U?<(+s+(-dY(Z(i`A1UGCND`8g+f%9UW;ZGRVn6bGx2 zM@7@%AIq(1cN~m>pnFW5Swot3iydR*>8wSOD^(4_PnQfzO0TDKX**FFT)#27+rs>s z`dZ!ca*rrd0>I^PAzJBQ9kmJ zk;JXlG~>fa ze?K^2Uq;9%{#aUClG1uplt1Ew=qSg;S}&he7BPZhuE(Xg>|?N)NUlwfhh?zr4I;-- zKD$O!IaH(upMN^;5 zMWuH9exI(Do>dmZtLeCQq!*kARYDl=aidVgIyIE2w`zYF*2;iaSA1W zXnv+4^WwZ?g|2s%D<=r(4QSXTfa{YT1rV z666wDZgJtyCRS8b1tp}hT4>Y+CCuQx_z1_`1S!S!0@LGSFFg16e*hYjARx!@$s#~l zj%;cOc%>3Gkm2L(fpiw541G0tG_-z8P-HiK>q(cEOq<_hbo-m(PEb_r#iBSb=_104 zCy`kAsOJ;a3GkZhu8T}+jCF_LJ;g?A!AsX_R+WNqk*hQzZN-iGWOsYUn+W%psHFtc zh@FVWr6+!i4JvCiuX=S}5}mQHz#Y6kK#HyA=b&9twdxDIgxy9h5u6|%uC!<@{7jfV zT^E_4LIca|lDVvF@INEb|7+(cW5l|9wKo}+RkcL2tCWB>RHa?UjnRx@belrO_;b1h zXQo8WAK;LH2rNDD_3_gvqP)C3U~>>SFz|sB!L9YVdTC@T3yYneo?g^)bF}Vao#~## zkXJ(C_wQ2sl%i@gon511oSBI6-&4gVCPXkP-{cJG#@GuxF&sfZY*)p^#y-a{g{Gk$ zicN7q&esQ#(w{sVx-zoUj&XeL<>ggnDZEQs7e3#le4;@`M;Cwb4ezP`Dne!GAAIAl z4mCoskaauP5$`E* z{1Kd1UEX9^b1wS|*+zVfd3|V}Ju-P!Kc-NV6!M&P93s&Mn8g13aQOJ^)uWi)0<$6E z9NliVW{jy6g4WkKM6ClkKoM7<#`rxq7x3Z`f;|u4{*y@nqK8#JwN}_}uBtZLg{N+8 zNN?1yW>)}OWQ+M%k%WM{ftrN{RXjRxpc4v@-&#!Y^5vFQv`}XoE+#R5XsTtbU3xwD z>!xIvMmhpcI~Z;iudsjtep}Ovv5?i)7oWw^Hahw;ws@|`uHM^j1XwJNyM`Rw$;WNA z1p>9*(Cv?rrI8U}`D58e4)aP55AZjU&7FZaPE-aOlCG-jxfnagm94NW5K(wE_Gs4@ z0tS<9S9Nl`A?lqwHAjsn|7NkLS+y}Kf~&r4tPbutQhc!dT!Ezy$-I;hYk4$A7VTm1C zrDOflO?Iz0FOIc0PT-V0{k?m!XAqUAF+sOpEeg;Vu-Rk3Zm2=&{yu9$s#*Hag(-Vy zuz9T8bfS@w#}BrX)rE@38lU2jQaUwc7H}DXhC_{40E7$77Rk0+rltj{Ammfh-8db* z;Le=8?%`p{#KK#qZ|~R&%pf}0X0cM#ROp2>);yh^eQ0MZt+Un#;EJRqeY0qwihYpr z$azv|YMKAWs~ty&P|}2~#b={dY${oll`xISneSvQxKmN$gn3E{#`7eJFA=Pu;lhP_ zO4LHr)DD`|m%94ad>K&93e&rA?`!NR%jO!|DK>U@gMnE~PBtC&8|37G*>pk};z%O6 zHeBBn{^H{QwS@fsW5Il-?Nv~2Det=|tBUcttoO8dqM!S1cGH}*v$LUqxZ5hN&!4Fg z5fRaeiK7Ac+YNvx-?P(rHu>e}M3a`}_l%){oHW)~uU;9tH?b@&FUKYrk#!urO8MlG zXFlD@YgU7k(zEtxzI*Tj#N7>2wlXz{9#BA39wI7FlXp|*hT7K5z zG=+WTX@FGbHz^WERVjxXBKm{N(~5DHfYj0{mmhB%R%_S+Pjqw#D$bDU)rY{Z6;8Y8 z$jv`rGkw&8e_qxsQ%wRjmL zHT6^Qt%s-QQCa1Nhrt<5wwP-$n*1YyItXf3E-q*;TLH zr9}pfUY2B}rbZku)<5OaNduw7@7*q`fbEAI`fhk=$WW~W2wnWLXk=_WnAVd3}T_IoE9yoRXDY0-xw4J#gbr-vZ`|m`r`AYI>w=td~{7k#vPYDg7>Ge|2#Y|NQ)%ik?0Y zNTdX;ez$d>#op?al$VtB++7`-S3QR3!>ZQo`}vK$yK!hlNx;IQ;)(Mu8bUNu!LF#8 zBms>}H(DwcKa0o064H@}!H1)~0UbqSxI0hPEIw=|Jx#$81lTNkZoZy2F&d5O!Kgi6duS03Jgy|Mpd ze}Dhi!n?q{u_d%W<%pkE-)9Q9%i+#^y6s$zk0%~{U5XFb%XcTkxp)55EX^-AfKc9e zX&{CXH0#}eTczYvv`EKwYs~PRHEu3r_W88&b$QZlYh&(PV5P0%DCh_#sqW(!~A!*Cg^^W2-O6+vu+?A%q}Q#DJL+ zbY6ES5z#;*qQsQ$l_GZhA33$faJZT%$w>lQ5 z3ASAe;SnsJn=DGa*EqC%D|XZ!mioj8ggkkeoHebaHjFaNUgLfA#Oy;y-6ciMb$Bj)RU0J9qV_8x| zP_{HO5jr&0*D&S={%-Z(>pI}ImA&v)$;R6f3l`IeV$C!Vt*PG0x0VzySYGO(qQ%Ar z!YQ(9@+!9UI70eFxnPKYLSS_^8lR@2eHXcfGYg5}BB$bV8qdXY0ui8N{@OwQd|iI_ zPWr?LPgYw#q$tcTe&>6qtP3oxR=PZU$H?R>V`FTpq4%VRT3T90PLEYpEV#(9KqfW` zJ^d%+!}_{9F%J)(8g+U*JG-r>urS2*AdEk!3!N zq_7VBpce_pjvA_hw_xmD?+%sVMp9HhNO*WXUS))|wTnaD|01^()%(#^V17n<-h{NO z`a;jjD(`5wX0igE$HRM3QClk-=nscDW+C_NYDHDB%0l9l~FZI#ww5o&93|1oZc;_4^3`qbv}oFy|sWO zhst(?9lmENU5nv)$qqFfPN2;x z(HcjWCX4dgEEnqR)>ZVdEG93f`j4iA0CXJH7ARRxye!P zkma<)AK)yi0;>=ofEF08l6`Bn=_k}mU{^l7Fh|hPFjvF&g)}w_7!9L~5S9A{LUi|9 zyJO8~@zR&!hTL`;pyNxAW##pu-B)!nIUPGI$*fby>;1u&-LXd7Xh<^rhU$%jH{`pC zmNr1$&NTK(bYa53qKeu0*xGft6rP9;&uaM&aGay9zT$Ru%VA-CSwgmTYS=fCgX@$U>i(RjX~9;)RA=j zw#krV!gkQtyR9uli`6zQ;|!d*0UGbiJvob&7B%CqIKyOzE$~t}c!#}jhJd_UV3nU& zsmD-z5G5wlXeIGm3Ors!qp?H=8k%%HF zQkC>D<+Bja(5u=*gSxT=Be~O=yw(zoLzv3Q@wqlp?g_D}(2o}6EVtneuAZT&aO{tB z1)kv-FMHyU0uIb+4|;WjXgiOxY`v8F4Mfvr%svQqM&hMn|KAc20k~RKja(v1XRl}! zaWh`jp;olM2;_jmooV@c#=ZsezHMoclwkWz-!>Obcx=NJrG& zb`6XNU4iNW-9#{;o0#JIXE8+9l-=_awI?$qPrq#RcReL$LM7((i_b#6HQP$p8>3)+ zmuz!D`u>-<4oCR^ur~ksKG}yTtRN03)+ZI3oaGO4dw#8f$oR(9Ka1brU;o?Fw5$tg zuCpeZo*5e#P|^D3reUx=Y9pQUq2;`zM8ST|ovfxxb@;>RVLVGXHZ6_5{_6TVaTw6m z0WK>()zz#cKYqjlUX4jV;`unNmO{qIWktlqHZH~>zOC-jSyfet;Oks+Dk}I=jrzWH zUUx(9C&NfPyDtxY{rx#LHJI1e*QV1&So#JAM&J5Q6q4WDW)D6#J01oB3;OVJNlA&} za_=Q$qD%%~Bmnp~{z#abN&(YDH8tZEY>`*{oUZ zz~Er);p=7@4GoQy7=;qn>Gov0go{^;p}L;77C1k>_4Kmn!Z({Hdv1XfD$X4?d5ODq zSH47t|5Wb&9#}Rruz^Ho&BKBC0a?qgbZ2X;m2a^a_3lYum@9XTq2|AQH#vNmL1>-J z_0G^?_G`!bNX~HPPkU%3+%*|hChsfMBe4&Za5WX>LZFjJD(b=D=x7X}UJY1UvS?^f z?e6R(uv~2FoR~m<@gm{u*DpW7SqJY_bjItY05Jgpax0MpKHA)TV|G=Qe9GeB$SvRs z{3K64A@t^8hgj1FMIeal*%Do!a=tk{Z39~c1O$*UGRoB9_(I6S9}S{;DWK0pwFCrw zklUU{->2{!r! z4&NPxy>yujjLYLvF>=G0D5@C~85!9k{nTx%J&I}p(ysNxLnIj)0GA9owBZE0t#(P- zaPMtHmIjCi?o*#7Qp?-`=^H=t2m1%>Tlf_J3YsG4Fyd&_VnV|Q0A&Di{@am_FCsjD zEQ;>#*ykxDgR^(FT~Rqf!ghr`GU8*t|c1EUJH1hF^=`Z&Z_=kUE z9YVp148r6I@c=qCy+-<0y5s1xL=33E5~02ggCkNyS=s1%c|=sG)jw>(Z)Jnf`` z(~4A3o{{qJEJWq!=fCaNmilMCDKeWAib46r2F+EQMAL<5I#N zH^;GKG$CWiahKak@9uJ6wZVo|+xx*0&x0{Um8exa8n}6+`9A6Hjb~MzY)10~7%i(| z$0Nt82l-;yqiBYBG*QCfsOZ__^v=nNHY-yWwJMC0jj7Qbw^xGxcXog zN$iG62i8e8AN`eB#dCyrAn3O8R!#|l>j`hI4a|~JyzU-i)WtE9{QleZSQSU!H-HP5zyF(=X4sSbYPiq6*w?Dn&cQ7nh%5tz2M*w$D7IkYP8Ek zpUwWCvZ@71YUi{BJca`8Z8f-@g&zkv6W}%AC=K8Abd4+#d_J#~AWopFA17gDM%~VR zTQE-B|GjQ@&TRc?KXUFEe|+-CRm=P(Fi)`UhJ=KK*BzIV5*i`$u|{`aHh2O=fmzprFFuOC$YMmnmr*?hc* z2!xODFhXXap%UP2zGd*kcpH*Z==1-o5ipELqL4=LWp^bs9=*dZ%ua(pAwKZklc8Kc zCbSzamVyEC1M`iJxDN;QW0Mg2uk-0sTH|UjL zv~K<4jb(ahV|dc$CMb#Au3w1fVGlQ=9QDY0TtLe6RKepty%haF`-0zRk&^hoAPzFg z`-vR!?IysHmXnc|RUn^MP+6G|D0O`F-wXMpxOHccnKmn*hZ=SY%A&4(dset_As_)BzCp(x9?@#vEE z>MtD^_8JtrX_hc)vW@bN{=@Q@VLkx_P4dZ&kiL$Qe=%+jtq1_|QD?b0^-Aj$FheWLF57dKEbVwKvN*cE z(5Zz22kP%3w)M+2KL$pMnoXmO&WjZ@{OySjXIcqcfFVmm&exO@3Wm4ER2EiIS|?uPoydqx9k z?0DUNt?L%K77B6^BLQhQPMvll*!azbX;_fb1|})ImoV1cxlLqf=jI7br}}H2rxEH` zy&rhbSh3ryQP1tbNPFDSI(!%~m7gtpfhmL2M!efYqZ9AT(u9WmQrl^@-dYy$|3&eS z8E<9~u4~yd{0Sb$y*63oJ9m7U?(Tu>r;f+XzV%k`P{rQ-3fQG_{GZl}k>8up-&f}( z;BWR1Y#oAIo2a(72jMSi^QH%=;dyT9(}{Rtb0`^oUXztq_<@Fho|}@yU{)f0W497^ zc)d1ZOOiKAgydbTgaUFu>w>r55~Z=M?Q0tG1}R~rH)7S66o_gNl?yo z%7@1G(%^XfkZML)J~l$o6mcOC2>D-*Sr~tCp3uhv|j$geAPqejunBKG#NnfPmx56WjnmNeKyAdo)oU!hj@@%=1OX7D_ z=&tyyeIufMd^>GTsOPX9-TcVD2X(s%RVc+tjN*og08n6_v1h`mY%R%F*6y=+mF@Wj z_!_OeRkOvdnZ+kLnmg&<9Nttpf>xNZAF4iY_0!&8Lo9@fItjDL#RmAy8q`Vmhh1;f z8ews^woxoniZ5$LPV5K0jW^sY)0XM?I8`lyxVC>Evzi~8b&-#`aG{}2g-%gh4I8}$ z8Z;{-9eoIK~M(J!34-B`9bmcvSkd2*w`xUKY&QXS|-9G ztBy*`;g{u!5n+`l?ciAIsyi^gwJMwZ_2##QNar4sO2w3<|4`dK4n`+Oz8Vp1vm?9@ zP2!8)tA>pLK&e`mIwNl!M_YiTGGPnD@$lb!^-hVqIqx)t2~8U z^Pw=iWeZ12N^D9Emb8va;~~!CkQcO-W=hAOsbTM^iV0FDr0W#7jr60NTmH+^PAocoW zIUJxv-vBC^tEu}GR%?E?0t=2WW}@ATH_L&|qR34johsfb;4mr$a`6X04+`3N#DevV zZJHWM$Ro4cq_AM&6kV%WkScmNh2LRAg!41;pS{S_`?9aVz6Nnx-n)zDOZ-L zyAzcD@EB;*pID(-EF#<9y4mfL32JBB3(IW>`P3H%!y*Hf!+gd!ENeOr15r0<-JHKM z!NA9lG~N!9*6ThS-&9~S3bXxsxd+`)9F9*nMX_69C-Ch=n92ByDL<^|()3-B;^}7P zM>cRWOCH+N)bzhD*;Ix0XcnMbV6w6%rlG8q;$XZ88-o3riy`QIXMQBbTJSco4yEgE zteX}@*B1_rvzg$|-&gbKKR&pOib8SKZsF9ByUJ^$EGhPw%tInOZ-Tu+u0PeZ(>*$` zqQ$b{LWKa^kh7a?vuy$N!C!+k_5>~uH&Bw)btbXZIUL~KpP{X4Gu~^%?5{FIZBj&Z z#*DMum@?f#=$h*u&c*}aBES`&dtm?du@(CP<$?`xYXUMUs)?i_qbAoB6-DKuaFIL$ zagiyg63GFTVH!!=xjFUDs-1Z>SlptiUJ4cDR*jgLB#ES@|9@JrAwg}wSd^@9|s$q z+M&-I6`4H`F4E;{lqj{Y-Shm4WfvzGOzI9NNYR;sXUIf|V~at9ckZXhf#8!v`h2g4 zCcO?H-I3&TrWFr+s32s7gt!8n!)E7G)OtbBb=;*FrG2R4!xPR zfk3R~lGEz@rO88vrK>I4J;;q@6@kYoE@!*v6h>9r`1pC~@f{zR(uoGTr~KwrfH4N! z(fe$Jyv<|B;WPIo+wU3FVxL0=rJGpuUjhM7Z8{uChYXl7E`uyDnaw$!Ubjqmj|(6Z zV8ZHz)Ad+uhTyEu2kF-;U7-7l(vruhA0b0*wl&?}3ujOsY@Yx4hE(C^OcO?M|B_-% zp~M=lIQ4_YGCc<%yK17Ek8NK|I<_64QqGuqk26upSgTxI`tgW=>0=|E{MFe@hFZ?zOv38`T} z=j%wBOQRYd6LC!`Gj7eC#m}5x7@#I62a+^)=32q0fi*c9SInTaDl9#nHXv^~RcOSU@|KyS7 zS#tm?Z$+4?B8N@B-aEQh{Pk#B7sa{QvI2do>98mCNXYg4-b+Btds5`;_Puv zZ|YEf7CU?U?SEYt2VR%QTQD%?5HT{sgZKS(>pS2o_m@;52$DD5--wt5de^FhV7Ee_~EhK3??bgX{!HumSF zZQ8X6_)+7Dq9KrdGy=uLGGvpRl?9@ebfPm;-N{4~(sB_?pc&?OxE5_4=)Y}9tJs#|UFqF@q3se8KrkBCh)y=$jI>M}~`el3PfGV$0 zz0E_Jk88P5(+S{3hAoon>aV5KxBz1TI3N_3z}VQBWiVGPCsq*R;P_k7#}RLMwZUxf zP0nNwskOgi0Y&%TD}g#x=u^Jbcp)2mm0|<*Yu*#}8NT-ToB5Q_B`S<<*FE+PVwuq) zv2QQrI~*ssyM$L7CPtY5lu(@fs<;M z@DU7eS7m3*#DbmjdH%zP4>4B`n@srcCR=H^8~;#?BTnbyOWN3=ajrHyXQV#i%A4^C z2}P2#tQ?nk7tf#wr}Qlo+)|frdD#i5m1!|gJeiCQNu=1y6PrAlXNcsG(j~y_67CAZ zq8A2d!v|>t1&YJ7)Bp&zwX-wyFIHhs9ndTH0cgYYD>jaklM}#7L0&Q`I_2rc3$eof z-(yfZVG(IJUO%MYq*9BCI-<8vdiTZhS2W?l{ELx$sfFgo8LV$Q+qp-K9yP&BEEHWQ z*ia5`Jy36&XZrm}{h=G+VFCRN{BM|pIa%`RP#0ou5X<|yg`5hJ;0Qmd@4NZM^m}eI zmnq<4Akyl;9!+M~Z^aG9La7KoaE7GyI}LI|gRQl94*tDB{IOz`y{r}lxhooFT*`$T zN(c&O0h((B)DzNOKyeuN?G0iP5{bjPVaMG_q&1b2RPib_hPjC`-G zw7T@HKBEZR5)pVn+5UJv{e<8qyiJ!_X>??9H&?X z5*ijJ@t)g!+s)R3fdSR7RoBQU^zxEm$(P<92qYY}AsA#ggYa${GVUJWBp;7R9cZIL2M$q1$9?PovUhM4X_)r)kX8NG)f(q3!z3%7S&J*JHc<@<^_p_nNYPmuVfz1;{NlN$lU92H5 z^+>{~$@rgD-rFR4`=-%fzAFMhqjO2!zoq@Uo4En0B$ZJ2cpFvNixhc?dFME)j5Be~ zy?<@%8k(W$w`QXN;~&pYBJp2#LwZ$i z*Gzz7NvuN!=-}t}k|;E^$W+6U!GV#=unj8I+lZbBVXPRo2UFB|a~S|cCmf7AnECjG z#z_O~5&)<_5vyzMRN(?%FV`6Teii!z1X}hdn~HYiCLF;VJUmw*m?~ZnjDYaj#?i5( z&Js@7(lWPX7>ML+s~VNqpT*_g-r4zn#4iVXN=cC}rmWnCyn(YA#wCXhrlX=#zD_8O zzj!KCo<}$JRFO?MyLBU#c#P4q9WJ^U?{Zt!@N04;q#KsMS}tFYSkmB`hup;x(k zr!v}@T>zt$YgDD(*im7&P6pCalc$L;&aU`SR&D24#EBj4RG)d~z!DZ7zRmU-ab#%~ z{*TS9mf0Q>2>`DDTvhheF;e#GEf@0=3mR>movkNF9{$fqu#7C$F{9x1|6P0Nf8yjq`=d~a%CEPG77zd+9@A7a)A6&Mg0+!B z_{Kc}=61TT|2G^uI(j*)@y%0+SLC0Py2z8}BBf`*vyjC|?HB2faqoWJAKJ=ow(#~? zGZ-KYTv2Da|4{k-d%bFUu9SEvr=92D#)SWeDEJ?F3~^t+WX>KM*|fs5;5@(2mX;C~ z6}4m7+T9&)jGTF%fVKS;tDsN`j=^?*wtdIK$vD6j`7>XJoRw9ftXzw@+Od=_+^wGd z*eFevGQ={V@0z}jqnat{c*xsgtX=LRQI^~isd9#8RrOjk z>fLGL0wiFNklh25=L9!2(G#$U+7oDif$8p=AlSzH3>1%w_}VCXE=Gfk$*+z5Grah} z&uH}@iLL#3Tg~jMi~qfRH4?M-E6_~lBW}Y{{i8nuwl#%nM{8(W4N6s2^8|S;3(Z!! zcqe2)pPiupmM+1~UQ*JOVA-&BV2ROhosf|5B{p_YQ4x)ctLq@$BOo{E1%{H|R$mkI zxS)fUXYte7U)cOq&g5al(z+*LD)1Ih4dV`A*RCs=G|F@bT@TgyMuD6XyR){YQdLvV)#hsIqJJh%jRCune|gIloR!6CT2)401e?(Xh#ch33h-uFA_ z{p;^4s_3qQhTUt=wboqE7{d$u?h4UAFy+HSGU0btns3$2sx`L4T3Uqt{rwxZTp90< zt~kEcR)4&fJyiG!hQ)72E#}wK*U|WsMz^uKnPFq9%cZH3+4LJ;y$?Y`5R0sLnZW`;32?Ja0V=62FLOWaGCVdo?-9W;C;nHfYpd{K#l^{%d>S3+SApLK z&h1zBayWABt4D?ENB(t@{=C4xW59ZCYHB+0FtfQDyY1& zsOFeyVAoJj%Po>qo!&O+`&n(Lo=c~2$JFZxY;o+ycOA+qD}_Zx-~5b@HYSC*2z@-H zdh^HlsD@?X>8gvQ7F6$`U%O-{CE$$A=G zegerO(014)qNPD4mnnVy({`wFy`Hei~FkgO4NR)TTsYkh@|HXMXt3 ztWp^;c8>SO`-RAQJ>i<@nDU(i=w=rpVn#iH zK@=vd4utnN#+}WaM9j-iKQ1nE+>=GLk4~&Nk=?^InvS?T8pC)GN*dRJQ>)N_?F|0B z08>eZ=Avv&=~@VM>$ip$mhlWxf2&yJff)1yh~+&o|o{=e`dV%5r=;I4G~6 z0wcvsW%SUD{YQ@QRTdxctYNAwlb=o+xC7Q-9ka7|fY`3Aq5?RoW(T<4$oTj`YzB?i z@$t8?zAvAio`8TAAt2us2quzOR}a42hf=Vyy^D&9syl44rS6sXm5ZMT&^_;VR=m7| zB6%mnmr`^nc4&t&^H~4Amc=~A5?tKeLv*tYd%^+q(=6-0#Bvs+fi>~ll{t#GEcV3* z(K35$@3RWUdTqUDeXerno;TN?<|8J*b8`z-FZ#{*1|N}+Z2Xcq>XvuOs!}}Q2q!b2 zM(qgi4{fR^{r*Qq>~?BkgqjfK?KS*SpY3WJCc|B`S|-duZ(qL92i5T04`mUxiJ%t0?grl-6;%tMz^f zuX-;u%5BAz-piC|m^g~))p3$fumTm|y84so^?1L;9iPd2tz2h-_o;9hck z1{2cf#+Eisb3w(|rBgl8IO$iTp_R!PS2qrP4vio_!eL_F2b(m#tA1QS`H_cb@J+Do zQPku1Bj;w4nyvY3u~O|1al-?U!}EmkLV_lu*yGNSh&B|C(GCxoePovcs@r16b5K-r=NEAL0VVQ~#?4T3A*R@(E~I zGVT(w=9wbPed;E8RQ)fiK={nw%g2Kv`NUI#L>An?&$z zU@8R_`E9H9Ms}JI09pak#+cVA`18*DOTrk9p0Atc;CffQ00Ob7$V%TtAHma>Y%sRI zIP3h)wUw&E4?n-c=%VPhM`)`I!NT&XD-1H^4YoP6^SQ%sF@i}&OvTsTtg+YCWF~l9 zjNu7K-M=);B<-+Bs@2Upvz3~EX;_8s>A#HS0u+U7O_p`|(}iz}eY6RYjP*1X1NAiQoWoq_zW=l= z6gt`aDB;iPV~yq)D8rn|N$h*PSW7B*B=!23SRdY@R%ol_O+pRz+>Gcl-pyGesoIpl zQA@w=JYM9*z96%G_V~JMgp~S;YWRBEbt|;{ds9|akTmV9B7SsSLKqu3Qk&(sO*g|F zhTp-jOJl!2xm*-OzsYIR;hKk|jovv0+8miTU97rx;06bkSOBQ}^8ZsLC>Yk!g;Yf0 zK2p^X4U74g7ckPnRqc+$dHT$^wq>F-Tc{YAJ}#%e>|ojqM|$w0|IsE#=S;52pmY36 zc&Wo;F|^#eZ~sP&CUB_*e!{m1{c%FcWq!lvICNma270GVk3Wa!H1+9ms^rr*2pC#> zVsflvo*yT*_x$;0*z1K3l~?>^Q{PnT|rNHr^d*28YFT>)Py7j5- z@DX=zXgxA3hkd|P{BYZ}Z5Z&s9J5?p>J z)Sum5%IgT8D-o0*7y47H{!?I6BCg764@pZ)8=M2x0Nk`YGx|s5x9FaXnl(j~mCwIF z3u9nL|1PpuxB~^KSiA;-RA=Vr^{$U7M$L+1tg0kQ;w0ooK7IU1U}S=yC4GJt5_1{X z-$FMAXrDSalsR^lUhzG?LWkU=shL~qZ6DCihmbzkr4VdBfwu8e04=dB3O_=6zVE## zGJMq6X%%)rG@!hR1%FVg4;SAglb}tf#^?5EN3WUsejuPo!dN{F#m1Ek(l)Z3*N&D#NFS*us)Z=jQOjaprr+U96P#t zf_H!mLG$!Y3>6_T1|K*5$W7DzUfsVpX;m28AYl|d@Fn3rH1sp}MKmgfSb)!I1C zz7JA*JguK~XUQS^mC6uj;s}Q2K3@jgKCZoS`Fcj67H|38J|d8*iwjl6@yNnha@1bQ zSPz0r`0eT@ZhajrW2h&HF{ZqR&4d2fkc@JGLtkaRgMRgbxMfkMSRvT^h4YWrIs`+e z_g`QD+XPMoG=k!@>R*8()d$uTEux{3ntJqU`yl!UYd$fM>za@E<65J=Q6&5UCn>8N zmWfxs<#j!eHgy@K@3OsDQ&bPkyjJV!7aupt6Ib}NTG!PkOe>ri&A+W<2zLgQpgGr3 zKS1h0@Qhd#rmPxq`}*7EMEXIe?PhHle^Y}%dI{4|@il9ia(pS?eb4CCZSCmc@C&X& z;L{v(B;?R2W*%Bld@T-PTHv|0;`&9Xq=yzbe5kMPLAaav-72@tZTkV!E_^q(o?pWO zky&NRG)oIQ-OqOnZ?}gQXC|4u)ZM4HsdnJI;%o}8uE5^Bw8AS%mNMp%eTeY>2a4eE zi23=xf52fB$0Y0TZoE2}(uu17jCHf2-%ePj8D0#!f5~#+0?z^{uo{6)2?+^_I@NUW z3(xXo0B0P?90I&Lpq^If`h^Bw0P5_~wx zEdmz4qFP!Z6;`Q5Kw4c4;R{mA^5OP&LY@>^*x~;V1p~byQ!^K3d5e?h;B<8b{odkS zRlK9YqOPC^+5Nx>m-2*46^1X4-$1?CTEgMsNOVna7l6eXxtrCJ4_2Z^rx4Y}jvA5Vc|UbJH>!Oli!9*V8~9wz5z zjr_gmenn~2{?3N6=T1%m%#$M@?~~!s?h19JG8%EKFM;{Uk3t=Z_nt}|tHF2!VTq^N z?k95<G42lQv&Gf(GPvFhiLA=Uz7)T=z@DF zvg%%yRrs35d*kBoA;>fj-Z5sNt!5lC_UppA8TAl<)M-R_80Cnpf97KYrimw1n|CBn z2y_&`q?Wu^#`NjFMJ(zjG~Tgp5~wlMN|y9(fL+~IW6R|zdMRHPLOjm-mRC{CfEGX& z^K(Ag$q=`DN&GfB>$R$>5lBXSZ4MNPg_H46o;ztV*HLpGeS%6W)PDxX3k@2)X4%_I*YXY&0WuxmJ$JEBwH24_0tuELyDU)nJ9~3oK+^f(|T{ zPEY3vYp>F>W`j1UNFKzTJ;yHVXnu>HPm+(O4!<|}-Y7F!;Ky^;%;s!dN#$XoQ}Ja z)M6^*w?172k@3O&dj?@bzQ~McCy1wlZc) zt(Fc6cAHfC!RUj4Ce!PP0QZ4|oA@j)x)vRIPh#XXn3(6nBs>T%EXD&MShww*O7=Z! z>x|#ld-6d$-K==-2(d{Ojr46e6Y@wQ>wdeLBLZMrpaTif92R?P+t6})_O0qO|4KXL zfQcT!5l6%U#aR5wN4KU256Bu4W@fqibIu2&rT(&7=T&q!&oVKhOFN6lpb0SP#a4QAS)v8&g6DpG!B1bN1YQ8-waNXnEJXhyRE(n zU9Z;nx;LwGRK}K!pg1~5;36u9y+X>ypq}GyrYu`#Bche_^!c4aW!%?R?3)b5cn5=K z&u{nE%ZH5drT=JamQ*tpesa*q2KY?pedKsIv{x8%X5WrBvIp&>E^G5&BFYq9ASKV) zz1`f>IU%^Er=K#PkqaC-WMqPhu6NoXAN*s0WbUWAioWRp%n5EA<>l#kn<>9B5n71H zLiMwok|w*PlzH3B%4tz@e8)i=#A}>3?KxpNxxMela&R?qWIB{UjBPo>`5y~O7g#rm zJOpg$AB;&1P{ z5*!hm+izm7?^@Lw{h{r1?7UGfc*|r?wE^kTM3L@XuWYBcZ%ZxNRr)HAvjQ-yRCL);>N7k zY?3djaQM3)*$I|oao}VDrc&`sWK~5s)D6wSYgrd(#GlI0m|L?tTAbexB2|1P6~5xq za23!XQ6~q+L4KhXO3=pCH0*H7d~ZCj`~5t1UTnsbL81klosK%AX>~HuNhD_OyNMc7 zUbM274=^>|um!qN&eDY6kro;Pa0?4&`Ch0pf28Eau2=nBOsr%6!xd8&^1vulo!h<*PskMowKB-@}U(P zhUjlPqY;xh*WccQycZvFao3QA`zZ&BpOJNbUCIq=zYpik(dm9Zm+1FJ?mI(ZO~I%u zW{BH`-aDpqz4%*1}zIKv$+81b| z-V&@z%5xa1r-+FsKMQIJ%e1Nz9N(AJ5YY_epyiNPm%*^aDaN7r9|AGuGY5%yQA*C= zzdk2kB>j22-StG9mgndwLUs?v=x4SVJv&m>TinB{+AaFzIxd#Xqvl!sk5*6#IN+z< zyY1Ng4-KU01`=kg@8PP{|qX|6-}HarfDhsL5<*V?z( zMenG+!e<&E`@pOmZyG;0R{HJ@)kH05|Zk;$pyhl4} z8y_7*;q`w+{jj0L&kK#pzTO}X5fZW=h&SapLRYz`Tfb`{jRj1crB7oX|>%C zxHto+g*1s+XcKNeULljaI6ZPdXI<@xRmInomk0(cK6!MZo>CYIJH57nTs=O_rS4^dR;mJFD?`|OEpigLKa~;(>r0!wk zph#OaI4KD4Dkb?$DXpqnUz(-pD5o1+ZWNS>{p7j&13WR-D^-GYJt&n#c(H&p#rY^Y z_X-*7mE|b-v*oM)bZ__VG4n85npcSi_O-*`^6Rm!Ru(=Z6H16XU38(MH%os-vRzBJ z`#4OtbL9e0NIMZ#^@N#x{_WL&&gXw@Q`GdG5Dt=yH!Ey{a6B67J0KC99=`m>VqoU$ zeVV8FhuKRjA3mdIRdF13Ydq3QxXk%xuZrTl>kH?&`PxH$OHJ*PqtFtxt?!Azrl}wA z-6InY0^CUYl`!!jeQ|nuwZHMNkj*$gfyGCFTsaCLMc*jOf6#)*z++xRny`~i=K|umrdUv?MFRSH+&F}iIJ(|Vd!*-iSvUU!~pNXYLUF!FS1IaCj6G(tW4TG;ezU$DF9US$3pq2ppi#bB!9c}0Olfw8;c8uG~@70V-V zxGf&ZM6aUBB>J?!3GMWV?ef=KjIr4GYD_u+(K29WxW|WxB#QtovKCL=yK2RGEk+qC zKS$e_7r{Yu^I8>Gbjv!P0zCz}Dtc4GwS6z`mpu35QhWh>AJF~9&%;uBU9QkJSO2d; zUprg(<(-`qX%_46L%R)2_)+#PwYKeu(8{EqVQ8ep$n4sLI>k~&Fb-Cy4cQt5&u!F_ z5Kl%z+n+e$44s>4wrY#beWmp5L0XywtdslZC=xW>gcdxJ&2c}iFnUYAJmI3+)D2-# zL?|Ok5vVI#igt_dv8&@}d$bS;2TlkIgw8B;7Hpc6GeJ-W>EtrgokpL7sR0WqUIt#j zY4^;w(q3N5x%$>>smSvFt(UIawtFw^80}uPZ%$+w9m;WO7d&JXHbo#hKa*5cPAUIm z+8L5?+x_N5RnD_WSO7`6$Zrrq0pHJL4nvnuqe zF{=GFQ=5A&J9m1t4gqEYfY;WCPJ63P#3E-#NR1JZ{M<#~)*Q{)SjIUZ zf9A$_aX{iMf$+W~_GiAieN0qSjGn2*UG}&|T01XVA77fmp`q-J4{i~=xiZVl4lmm=>GW8L2zPd6rfn<>)e?0nfC~L{Phy~ z`Qs|}`)S0VIa2ca9}T^D)YL;x9`}Qq>FB4rco;9BV!LAR9yssmn866?d z%)qa1NnJYF7e9nHR0*QA%_HI{w%aQmn*}CcqV9H^2hyyNS3D=XG?&``n??6@uJewx_%x_jw#VefhG(Gadn#dd>nueB*B|J}}-%KCv zSMVV$&!V+Tfnk`Da;J3K!k)cxX z7&`c;gDJ*0nI1LQ>e&8vA@iU_-!1vcmg}csY!`9b%9Z}10`BeAZ0?(?JI+^B{^{o1 zw8^_H_=lsd%ms&pd&yAOggI4)nhr0KTH>p`!5^(pAD#m;uGl%tLHlijneKVb$VYOD z;HxCM`<;w~j*2Bmc8Di}HNnhQlOapL;WHZeS?#`gf+TeW;^Q>DD{*7SK`TxRt)BW! z=1W(*Hf>HOSVv%u{eG!(BVc zvKT(^))D^ElcjrL!048g`c+TARmM`L?q~2Vj)vXB-m)Y8u1cl)1(#NznkLXUi9r$7 zq^&WO;6hRz83uj6-z&yRSy}meA|CAkT^BOmsjJ!I6pFFvCh%iBa>%ckYMF$UjbjII zY`z*>FUUrDv8i4$q{5TJzWt)|W%>ei*TOTwJ$>tA8@*(;Io_qUewUfDs_ z@HWzGTYh_IXK|J3Tc00{sKB`+%1}wH;42#xOP9SJlqkQLKe%6dxo?s#2_O0z%9ky2 zf#END&t0dehp=*+IL6&=c_w%>ATCXd*k_PX6n>E9V2I84mUguko+q(2JY$myypHxj z3iFIM)m7!@ zlO!&&_i+@Tn<$6L*rD3UF5iyczq%KVYzektamJF}pQ6H_ob6NDAex}D2XS5FGL%|u z=D+T>*fRWox#E8pqLL3$^~+N|FV%x@S;}r0X8J}Z-De1WgEJn7SV4lW@(9$R6yTgtkg_tF-?tXF8Hz{V(&2KGy0(jiGfZd zcr3!j{CggzNV6FgAaFWQ5x0jwfV@qphhP9-w}|epG&xsXa%GzOYyzoG>E6f9E$*3>?%J`4UE2Icib#M1MO2ftN(scp_;+z=G zG={WnlNG@cQCfiqywsW7c#VSTgu%yt65~VD_4AiRqygBICK9q@*7G$ddGS_)Mcd@k zht}jLy0q3SeXjwjo9@`%GJG<+B4|ZZIWe?zQ;vK+2L4GPNwkG5mRo`AWOtvs&=r)Q zct17Hjh}=9AwFLkz;LU@Ijez$)LD(0TQO|)dp+kL)M|N>f0BPad-1p=R0}kq=;8?6 z8a`4~4D0SRObW^kFd|_vk-wM=Aio7g*6S7sIBBz?dYsTovQ3QXcazoyzeG!egxOWk zs$YHcxDa=^npnR8vgQOVJ!G=??7!&LN^T~wK*JTUlr5SayrFNm`>IC%sXlXv#z?#$ z7@(C;(9WD5y$k^$AV#51-e@Mbi-Z8GKPDYxL!I(J4mLbzs@y~uTc4yR$*KsnVsxX2 zxGf+?8Pc$?f2?~S>KUsvdR)FE0pr-%eEz6&nQka7@YBgFV4JhEeXdQTrSSGdFIWbn+PEYqc)KSMB}h@dF_s9RX9s2dsn#dxuW z$NNz=q*op!1oT(zXGHWM^7V+^pZm2Yh)YsNNF2a(Tpu3`Xa)I*0tKF65CSI@eyh@9 zZD#Xq5QPdI919k(Z`-aZy-$_rs6i8&=M~ah$|C6W#YPObVg`cGcjVFCwOs4jz8yb& z*T|IwJXM)jbm~bGREfo99UlK>6ktvdDEvDX@_8*amtO*wGJhqlk+7MeA3>hIknvbx zIs(ypE_NqQ|Ad}305pK%#m?BtnK{=XF*};cY6pJ-qLL@Tk^=_Ze`Z0=KW^OrSoDdA z426Xia?)EJX4pFT`gfytsrLZ}HUTRudNXr#LRn*^oSZmLPEHci(tc@aB(lj|-T?l* zy3rR6P^j|mnS~iZc(>+_)8vzs?#}N&2DB9#yG%Bue;M=uP|*PQ9~4Da)PJ{W`d@D? z5}#El?haFbOLjMUyff2}VAZT;tOqtW{-9B1_A*5_5FmHBxVhVUdc@;Kxn-{EZT?3h*AEbG7?;ko{}-wIgU0^vhc*iNeoJw2@n9$5{xUy1OUBHM0a#oBjvX*O zj(dK9Tq^xm`*mdU%nJUWK7yko*XZ=y>{_olSf1YJpWS5O5#60{s zLasopRLBIy4hUWHG}tCyHs*@PGA^qA|NVDB7@$u|3K8JZt8Z-V5715Pz`Xz%I0%c0 z!Oj6{4dp@=vcFlEKQV-V1AdJ2fP+I;dio1jS68#K%s2E54EjvCE62wXz!>^tsMgnq z0MJDz=jYL$K~^FuGdc$y6B9~T^_H_0zjEOmj+cnAts2t*Ndf+cT7EX-l7U}A#cdRYCJ8qtCO?Waq(X686`m^o7uleJdw*DNmt zfseVSrpC_N#wLQ*bT}RG^#ev2m)8T=;NT!S5fQ@xV0X4NTbXN_l$=cO`xqJ;YOL1) zf8zY@TPtu8Gp5X=l9K55JFhaEXX0gZ3ukp5-A$KY;Ek4o7{p}F-`dI2>=PwNMxi6I z+S~u`>goUV+89e2ur(9%GNG-A#?&)3^aZ5Su37*L9lM<~W)>M8O%b1jY1`cCXi57I z4D=Jsb*P|7=f6sW1ApG|54j;>;0kd9y2Jnaa6rMrUP}1fmv1|Gggcj6Kn=)mN4B45 z8!>NikDkz0(zNLMDBnkg29Y9=TfhDACGXz6u(*;hJA`&BbUF(xS*Vfi8Pl-0Bdk#1 zGO0W_{^P z3Ce$gPT7YB6FZ{fa>!F~Q$Xrgn))&9Cvp;2xrK=Qc0D_bRt)*HUT{R62aw;k~ zKy`A)#mvmyJ2V6wXc7W$NZ)qHKh)E6aHtRmN){dsK2lnz#*u6o&rvrUNm!SN?YdP> zmg>q`hYJ4jvMH$Z@$twGB{o^>7F$RT0#t4P`;kY<#LV0lMsOMwBKgtMvSRXm+wd@c zUmu>LI{9!)W5|51Oe9eB0ApDZaq)q+n@o&TCh~Kzhes1(8R(}@2fE+4WU z;Aa*;KQq(&^4SMh^@sh@0{899@B7fwfy=j;m>G)skufpvp;_aT=G9GJg-F2Z-iyDy zZ=wWDj=*gHh49B%4BZ3DYf)A3QU7EW0S|jpSbQU6&%CF~z|chr(n<0?sY`+eZ8h;b z!KOwNq#7?4jos2!`n0wOl<^0z%N(}th+t+C!~N-Mm)fN9Ka=6_Qd{SurCMAF@e}9P zC95)Gz9R7`&xM;Y9!F_1s$jL^3A`;41iA70xaTRXa_kyIOMvKEJ*iw*V|Y=Ds#S`H z!cD7Q=GPBjh-A;ORR>e6B#pjd_gfTs1``vJDm(s7DOiRTXiCNU0S z=VSO?6HGMcNVhLzK&)10!R&?gDWSmxYQ~q1?0KMUMzlmw$}Gk7tnNHhP>c)YCy)AmSz80<~eB^a8dp;s+8ZEBW`l2t#kU*Cfsv@U= zXwIhOkaWeuaeVjt#??UvWL%eum?Gz;@F7~j0M zCE=8YM1%GStIA@Z)H#uJ|Ak!rKE`AtoJL=$Iuc+b(I@)l4TDKmPXmPcyv#*j2>KBA z)Ev9oRoCt{Cm_Axs9st!S#qI+KlluL7`>NRnt*)-6h4>zl zM720IPLyMI*6#u=CYe=^bR2STg`Vdt;3_@;zF&5pD(tJ{2r{A~SQqAaGgIS<2>C5n z*0fcRu#LlbxH3Ldnbzxc)P&nPcQ}RHfs@)~^wtfOzx326GVnDv^mgQ#u+M#jjQZP>Uc2{}*o;*I`2eU2^;9 z7vjm<%rDc3mHLB%h%xHxxg}LmOid!TTIA9lS#f4)bI*JRMYII(3Bq+GM7(SAxL7UN zEN8K_dD;A`KlAuFTeqFEEa4k3&cH2tYPQ$cAX2WmrI)?An& z+b27_iUmH#)I{Fb>%2*1E`2=-j%qaY(QkP8myy=RZ`vk?-{DcI==UBl87Bx}96(D4 zSISv>Fx7qH(E@U55qje2+ZTLq`(JpH*MV7hrWD-#Ct1}_4on_0FXE;V&ufrHsiK)Y zIGUQ=uE%1&-dwtJX7_w=WE6e_jAnCX>v_6gay@q=_wC%=@KRL6U2=(%_2F(XahAkL zAZ|$&UHb50f(TKn*d;g)W2Uxw`LL^DhI)#wY zQQGVf_OH>D1a?mbp_ntpIhod<&aiECwjfxE%cB&*El*BNf$G>L7VWO#mlLGmO!y=4 zG?A(^N^4c=ruTDM|Dmc?H>hpUTStP&rS=x5?NK}iyu;_)+7^y>L(+#F zwkJRPk$tA|jMQj4rHn&kKH0RK`E-$dQ#qcMH+tLIdb>1QRp1TX-!K22#`;r^v8&Tn zuqZs^>;E-#F>s>v;1HH0TDKiqLp^T6j$BzloW6PvzwNad^{8jVw&*Pax$&i z%W?W6U=B%fA9s0wD_t6uW4)7{e6w6|3WJpJX!|sm{F>X?UYMbaMUc0l*9^yCnhVL6 z+{gxdDD$B3E{zh8EMv0j8V~f{dOX+B}?r_uT#_zBJCcnp=Muf$YvFl`ip7!71T?20gusNmt|K+;B)Y%JxG$$N?5XLx zU4SrfZD@v>ohzLPukr9|>#5*^cG56T?_2_O`>At~mF}edpn2})huM3>{zk*GtYFs3 zwU_+Cl-zH(y=Ft6iv&Y>m+h#b$=M|%O}}rosE2Y3G={UB(`+{H-hEPIYj0(DEO&pw zF6PmKXP8tNd3&wVbg?wNcCO+;^6N)Bh|=I_wSU+Z@0xnHFX&-kyy)hPH<^{|Gkdq> zIlIs=Q2FDq=jAJt!wJ-}{QepcIJrP~k^5%@k;y9L!>q{vwkW)`6Ow<9Z6YaavRij7S`p#T)ux znh6OBBO~R-zAIz(>d%T8mltrtYG1y-XSE?++2$e$N5$31^%<({ z?4B0+CiT|^$a3bK3|n@W5$FJEXduakym(lU=TEFm_^8HxI1+t4i_La_r#Ovg- zoNK`-k|n%h**!_C``*imlff5XmwE&mydT@g{Ii%pY7Cq9BOTyaYLAVoXm~qw!}00R z*6PkSaQGF!)l+V%PN2Nvub&Mrl-%v;AfadoCLNLXJ5c-n8MG58YHt2b4}xCqhIJQw z-ha~n=1Mi3=8I$Us6nrhrTPRCL(Di_&uhbm(C=xMS_?JE>j68%*@}kLxDcW3=rrcf zoMEYO7zHsZjk2uFS!t}1gnnV614wLxopR?-zFD^8%i6gJ3A0KxEvn{%(z^9{Qaa{J ztSrfM^_i*K3<)Z0b%eYlaOdtE?U~{nWx6-`;sKmL<0{qbfotw6tQxc|SnwE9vy3f0 z%R=&~xd`N+N$+!|XJ2qa=k>1cCG*;AN@L0&H(H+_W(3PFr@YSuvaBTGu0jK88XR$Y z9<=-{-El$#cJ?HPJW&rIR4OT>OC9fimBDvPTyrfw9mc%u;%B#jt!V-g6?XCaS$ifW zw3pcOBD;fMQPPPTpSL#Ml9vgRWbno*GnYXKv8VH(1vn-)zXJNEJcPzl3a9B$Xa#$l zwQ_Jzo|4qK+OB2wAn6qWnt^Qz*I^DsZneRhGoKwB*Dps*4g0?FW}l?x1|tTxZO77i zloZgjr&?^IDqksU#SYu-ZF%7qAk*Y*OBd<#V)`~6!(1WJ?rJP;-zFyLdUNXCLY`X) zXG-g9Fi95AU)y0NA0rNQI!j%z6*ySrTk~U|i|?gHP2rxd!ruz8otK8Gec5e&vQwLB zubx*Mq}wn4xVJqjrems#K{phrTI;Ua9~iy`DfW)WQ7eJx}d!08T2t@6#gOdhpibShf_-#o1xRd|yH4%434m z=TW0g3U*2*)Ta^Yeto@XVV}0gFX7WWOI52WBoJ$=wGA7R6|)?#FUr^~<29>+f&wnT zef5F$9kHaVdJxhrN+V}+7qB}kcYCBfK>gth-&}1yPI$NaSaax>*%*&WpPdnmu(+?-ri;Trb_&}|s2Coc zFn$xG96qF8Z>uoyDKk@w{Gy4HrZ9m5x27Cdh{H!{waRWu95-}8CzIIwy*tfdgFssk zq>Z#G0X7w6#0!kr)VsD;V>9Ir*9sSx0Yj52L$6{7GvLI?F6_z{v^mgb26|!yzqwp; zZ1AlZ_7?;@hnHr~GA`=`Nk86g0s_6)Du(k}{(cCB|UrJ42G%p59T|CD{eu_?_9aIW52=9D;RcI+F0 zkCmgg#=R0N9shI_TaN|^O&uKrz}}ZsRm*5Ijz|7Dmy{0!2d>UJ)f7UEn0Uvb{TC$f z_W22;-S?(fc{aTPobmml$9#3iMtyOWqvOT4uueCLEu{+IJN+=Hbuq&;-y5FQ6BFdI zAzv?6BO=+5A?l&^_~SRYE)si3+XdB1m!5g0wc5?A$iRDd4kEJ-`sa}=u=8OgH)w$#>Fj8mCRV!V09;40voRRn#Q|Sytwo? z8=YNmYRPHYmSf+QV~1X8#a_u_H3fiu5QeI|O4bF(Ooru<+UMksFEe18-GAax>hHD` zo?U#Axij$d4uqY`@>t0pC*6n-tD{|fF5vT&{`}#1-eCwy%}uch zPUsh;bZdoIn2zt9_d#6489$cyu7#%xza(Wci2oeUI^nu?5M|j=o#J$NIHAmm6+8U& zqgb!9`=Tx)9iv)`s>R_Hl0U3BJJd|K9%&`)jrvIo%Y3oUi?FU3-IC$m0P|*M7V;dwY8f zT-=~#@U!+28XB57&4bW=aL%vuqtJLUOx zuxF;hkzwibx~=XF-R~oYnFbR|6EE`WT2v8={1D@NXw_z>4(Fj6Pu$YT%Hju$*j3Fk z+sz)_ZNq%zVy=-k8-vsS=RKKi)+X+{&VdkyY}W@pnrW-aX^f!;(6R{0*T`jLX0+0b zVi&{m`PR%;q@Ey*$CD%c{O9PgOmSv>q^=v*huPHD)%6FEe9%ka%4tjy!KUw>ZrAB3O~?ZhHkBd z_qjChr;xViVh=Lla|{Z{sAWyiTY(iSE!a|jT1d<o*1Vk}G*c9*LO!Ay~-mA`bSd z8q%U~f)3`Kw6<$E>|Rdjm`;8Tob3`YWxk@1RQ*nj#CO>}Fw?Xhoyl`{x37K|Z*b^g zu{{MW?u(W(2(~c~)Mk+uk5-@5cn`lOSZ?~^;4}sE2gbSzJdkk=TKWI1r=x2?rE5M6 zt!lFXawvt~hZil-z;WTeOCdwEw-OX3kk3B~b$vQg6sI3P{mGl8+?LhUcb+V>vrGU%`X-vUoLM>dxG( z8Z?u=oKm*sk;`}si`|GUw&kH{$pMpn!8ZdO`$NvbCh7`Kg9vJr{c&=U@y?wKQ#ViI z*-O`j%*VIm8M!r2m`paCCI{0~(Z3dxR1L3~9*f2V5}Fl|?}?G%XhrWP4a-G}vKFP7 zYRujn>s$~p>t^pvx%Y_QC&~n1lgODn4CE14!ZeD`?$Mxgdq|xnR;!mlT;n1X6_v?Z z*ZGQ`bP@wevOSI4W)#~RpX?#=0imAR7fx?yi614!KtYEr7MCfWlIBieDyt-e{l=g7 zu}u*30TZWj*{;XgHOK2?UCQEJcZxWhKG^c6el};D?h5FGej#!x{^8Z~<1Kt%_caqH`)V8Ql7STq9 zjb$y^;8r@rZKX@MEJmg2&x~Jhe#vFqnq)n5g4dTD?%cyOdeCjMQ%`8RsXMj? z_g>u=a!0I+PC(fWb9!U3+}3ySPt}d>{D<-wa3TA4r?w%#AY;0Xe{_s2R> zt(=bdvyOl+O{Dbg?J!$x&W)S=&Q#Kjx=8EGur!dsQnD^MfFq)jPJ)lyve zb}>U40GA_qXdW2Y#-I!pR4Nv-(rtbSZq(hbQ^kJ z#nK{A3FBtBFF)zI2l18G+M^6=>oiHpp9@ zY&JCzqSAbyrlonL`Ia2=gg`c~=eXZ;1LZdjjKA9Kuwb?rN5XC1;rg<4BoDQD9nqQM z;@*jrz-Cj-QU6id2zG67>b;gg9jr~5wlDuFmg_{wn_n`-5%o!e-TjN98(RY?n9RTD zn@t{_+fG`DnS^GNRP$Yz=E+VPRxsl)i-d zczQ9|b;btx^=^tK+#KOnS>!&NEG$EsbbInCnP35HQ2J`35aU;ppSg1!7D+AxWqq#0 zhFlyssDC8a!3TN?`UwN&QxJbs6!!CC<}>=Mj_OO}>ZVihF<^^f~PQUMZ1Kr;L*~NeM)edLdy_wB_7#09KUTwuXToh$5!dR zrSaYAW~?$O@HO9kOYjHQhfug1DM{t_&fBtW@ znrv6ch-k5}3fse?6Zc#qe)t+8RMtCcbL9PGm@0g2A}gPmzcP77gS@}{ zGL{mN>ech?focR&tQ5$D6+)uHwS23fV7%>Zx|AkQe{QfTqTe= zm3Z;Cr@;Z)@i9DZ56iA3N^b6L^)*2ON_mstu892-({TIiio`-yp?X^%ooDvMm=)Tl z-C>r%+ijk+q%4|@Y25HfqO1xpDN7QX?Z~>F?EE!q`KL-w@C0A8hKd5G3lE9HtLr96 zu_dV@#`}nn_@$ovkv%V2wD#`kwOn_0z6RuR>|F&ktJlt7uULE|^b8$g>v1FNcY_FV zUqHigHE5YyNqpym}?3bP;a2 zGawriS-?yIui(zNeCu&-LUp#maCGn%H-m26Jt$)*BTx~|$Bd-PMQ^XF`(Pw6L({O4 z7c8v8xWo39#YB}xLSdj_naSf^J$M)KZV^i_dpwm6*<`eO$8Ty`x|?a;6voChoZYX`?%=?SE9Rbq$pom^GQUwbG^posZ|_|q_lKa*vY zY{dy73!bKmQ(#72CP#Bphq`$W?6cac-Ur*J+hbkT>>3A;12viL04ZMP{i!!MG>Wes z&oR{M^eOM~`M8>Vp6qio#p&R_YSM|mo!~(=<2DlLZdnwj8Jj2*T)Nx9x?w9~u+nBw zqEmJFKZLynP+aS}wHty55AK!_+%0Hu2$tZk!QCB#ySuwL7Tn#vad&rXwBhzzYp?yE zI{&?Ose(BvswkNA^LLDAr2oM>BiRhE0u)(x^&x6c<;XD<7QCl-*W2Z~neI$wzZem) zpgpSvZ|K4@wTF`(sFNDV2-y^%E}PQ)n)qCR(V%6gUB^FzB)By#w z{%1_D9J!=(G2D$a21Jjm8Q4cE3>~lYyQuFd3+tHGws-f7e6@7!$(0mrSF~{ikujBC z3x>n#K(Iq0$iwUL!D{}?!(W5&iTbA03dbm~=QrjZ-TO;z zSxr**a-?1DSJ)Gu=1~#29bG#2YQ4Slju>aL96Q~1*6A10fn+xtt?4tikNiC5!7I)L z0SCK`|L91bzF=eFZ0~ZM*;G=PZfIFW_V{`B1?zT?hZkdb9T8n~G~4qski$XB++8+*`wllJo>ujrZF>I&|~^xaK!4Tk!e7gF+JyccN&nyzkTxI{N`ec~Q4+ z+2dX1RZKlPX124_XA0_MA4Sb0Z*AS0OhK90l*!{j~b#ra-y$!5jPe-9n{NQ+Fnww=&qSK{*lqCr)EFWCpksX?5oDz zv?eNqyJJJtVlZ1EmGUXgu6Jq>8iDr@w1>#~SzFe_0p}@yJVN9M$v8N>yXk7@G9nv( zwzQkO&X9?5ZE_T@B|nPel--WISs#A@#SLCWXBqH|_x795XKrxv(#=%u0k3^6zf3~G z&aNAxl}0{z4B9Y-Nj+cd#{}acOE=gd zz(B-6cm@6M0(47Vb~F*uOmaxsR}&$wpj>a#SL7-};U3kZ?&K6s*&NTAZinwJn@z#1 zW<(ReL>IrP`VVX1{*#T`3((`b&C~5WfYeM!1G^Qk{E`Q7-C%P-3lI1d{N|MWJCTsv z{kn`u@7Kvb>dJ1u8oM>S@fpH2Dq|@b@o=}G{#lP11j4=T1H=_1SCGl^CPZe$u=rdu zXMXhC0hRC|BI!7KVAVhN`k*xZiN+?HC#;#WuTHcUlcEjNOi1n1{f3!Nii=WZMWNsX z1xz7LKV0)Rqz==i@-({`Psri|z%yYl@+uu`9CCd;ekb#+q1hUej`nhTH{hn9#CcLs zXPoY0lV6b^j}w|hEPVwkz^%JscV^^#WgzKP=q+E-vm%z-<$^+prOLHFSEcwN9vPe2 zmyQ!>=N#R{Hmx3RCU){ooeS=0PLrqrWx1(A5&uHY!36)_;J}Qc?&hlc}(_u?mXb7yJ!VyZx8G^*`06)MC z(@i0H>2xeez@Jkh9r2Znh#zLX831jMQaE3bPEj$tS)30+ey>7eZ+tZ$zSM8%Cw0TJ z4LtTti1LVKEC)7kr_c`&zOu}Z4(_$qnjZ$~vlVakH&9gbBX+}|XZSb*mK*$wX|>bt zovy#O9oT9QY>T@JC&M<}+sd5NPaGU^=VzRFfL;V;G_DCL`s6GYQ1gqG`CG5RU%yBL zUYHH*5XNK%`>jTy0VaKItqK-RLfyPlImzh)>>+{aV@auZry##A?IWQxb8<@#}c z!9#^lZ11GMjQ409xdQC32X8r$Sn8TtW#qlZ-!l?vMR8Q2_Pu09GW!fs1CpauDLVZS zuogVXi;~JX0ZPqH-nLLUD6z+#bz12hnk~*2j55W?}$fS#bm2^Z5kG9QA|V!oXuW& zl3kfg?6OgT&SPRjOyPTHA6$FYquxdLjT74oag?1lT=+TLAWIlx$2jbe&7XjJlh^z2 zP5SK@gbj}_F6?Bg^f~6GbDg>8_6>sD3vUv{xi7|jqziC#VWCx=7 z*{VH_c^!d1qXFbpI%?dye3IC{XAYc%6PG#=2+{P}W49WALn6^?wxhtiLf{2n8=7Xs zT+q6C?qH=lU0a7e^>V19^6AFnTY5vA0^qnuE+QLU*}db}BSIAR0q&8fwl6Wu_J!#g z=uc}f7Z#qYfBGt)PqO27WUJwDfJ${3N|(uATVQV4L0PMU-=G~EjNnjmyaYzUui$$^ znkOgL8s}z5uQZ0U$x1I42Y*-0Wk=*Q*G8AGrBg2F&v>+619RG>`qoacgQ~6_<%d8G zK+FZS60kitJ_^7yF)V9*qS!}%p8A-CY7qpgIXI46OKeDV3Cj{>Xn#kL$SH# zehx=Toobc$?ptpLr5gJ=tPDif)bj~vBN8uCOd@`3bppN;JAACu#JE>{`zzBCS+Xah zApJ9Xl^`2tRn#lG?pezxZL!omsce(P#&^m>gt#FlSOz<_SF1fPmyc*IWZ>wl$F!@% zw}98G+WSg_m4h!ZFBNNx!(Z;V;hX;hYI~JBpm-CvECbz@=jP@%xmsez8OZItY-tY- z3!o(`6DeRu=jU9)U4NM9?it2w#xVm{I}A5dK$c5!oOs?8La` zUpP;8%YzW(HNqT-h=<*h4yY;J2=GtOxqD~DNx|aH&t&yI!F~K}*WEyCfzzeq8}=HB z_Hq7C_+o<@yQ@mNXu6R$cXOY1v-MtV6b-ZNWn81Y4HGrC=8cN>d@bEKHd2=XYNeKt z?<13nIy4nV1`44{56b91R!p?S@F^q_BI&!A3}QH-%#J9&lx~0@qOjJ}V_vK}NhJ|j zoDc!xgTV4tE&OV4JMArmn@I0tXR$Pd>vbDVDn)~hV9zA6i|<+f);;KFr~RUl;s85% zm&{JE?v-~yOm$%A6C^kr6(G`AyeS)0yda-BJ*4wi@|lr8jVWQdd_`t z)~#l@B4oc~BB@hMwZe9?{~C3uin377NcF)c1}M?zlXR(x7h+JrkJ~X+ z-uS@$KhA#bPM>F%73PcrwpJPidI7Q+Awx0lHW}T3i-}Re#km`55_GwK{+Ut?CCQ$e z&nMN#dM%u;l$6BJs#U$9+NIyhlyxVJsti;++tIEbW3-;75%F~gpZxZ^IBPv77*p-+ zaM#@*B~ClZwF9MZ{yevK)~AZfIvzojB6mJ5hp!bhU9V3Th;Q64=xxYsMoAeWqoON}UpPu?EX!x-N}Ru%b)k){UY z$$`4#wDT*gH*9A49hn6Z7*;#njFL+K{3#p#W2vajC%COv5&df(<v<_#|2g;t?EicbJk;fe-kE#q_L&u{yNy$VhpWQTV52 zE0v_$!P9aRKrq{S7RGNw$kh7j6S+7bhSgQT=gV)~Nv;{@=Ir#ki#^Ky1?>l!36QoQ zckrYd*|MgW{WN@1m_Me4C&|rVZ#+TOab-C zBkkKx%O`^1!3VvAy#A1OA^^k412h*dIG5i?bCxy}mc$HUi5)*3$19SkM#q|dphnT) zAhF>Ex;4N#Fmkcxquf@PPr_r&KCj)(+g89(fz3gPd!B|Ae)r;6L$ZeB0V%a8ve+zj z14t4sr?VUvAVmN_x0Cp1hiZiAMECGAJve4Q^wq_DBU`wn?rco+miiSgyM}mI=86lt zGsyF}{i0#357Exp;kRn`)-uHsujx`=QXRl&bEwE1b+-aFa&TnnDAtZ(Lq0Piy#;(Z zz!}iSK^)vaI@{+@39%kHB1;aLnI?kN*B`wTc`!C#pE2XObgSq)14D?3>8#Hrrr{r?tc;H z6-4(s_fzM4#)?8+0z#ZF%_eI0v1>?f(3QIp6`Wfcy2m9Oec53*IiGs^!?zZaR#gc> zg2?F^)yjS1{8yo6Y&)*(f98EuYS$}-50vMd^ED+h96gK8zd~xA- z&Pbl1G3Ro{ZAH21dWd{ly1ig$8=zBmOgIr(u%?_I9mT*ATktKawzZ5Rzi9WzXh}c2 z)7?_O((_$?39!gJeUf)K%6mjVxpN>$P|7{Sq*=o>k4KGoEqNl%BmaBfoad38oXNyx z?_v!lW06Ysl?OU7@SDo_%GHSltUR*L>JqKlQMrZJE^G%HsdIVxDS@xLF{&X2>G(r( zGgxz>XtF{t99Bv6YqtTOrIjUL2C!#J&I%$w1F z|GMRx_(aA*h4~Y=PWN4i8zWZax{1JfMF00stkev-YC!~q>9k;a9U*l|geudfrmTbq zpl(C)!LaV1uRN;sO}Vj=5Bl@S>xK<_C-d9meGS`Wy9l^7hp{U)7tt`gOLhHCRSkN3 zd8w|`8)6etK1_c;3QNO`6qCu*|Gw3|3WobbMod|#&f)(mKg?+bZ?GESrq*N%DcU|T zae6-!EFXhQG%Ce8?Q_1_|N6b92R8g^pX8O^A{LD)Nn2ZiJQpdfQaSslVY&mD9ujh1 z6|l4T$DKnZ+_)E_3Tg6nEZMy7BXh*XA1)gLTA*iL?4Wok^H{^Y{FdDy7Pj?sjJ39o z20;hsm&Yr_o>wh01DNn-?3s^A5fPY(zdgM3N1z*r&YGY=N+WJzXu^yrwV)bJO{&))^yf1|+HPkC-rn>SJ`Oi+^L@q5GlZIFJGa6Q!xZEQ?&?YG|Fbp>KnfHH`(3POc%EqVUDl|ruU3egPzX~ zcx9t_RU}BA`@jy$HBF^K5jfRohLYKaXq2T8hyG)Dh2_NoM-pN7#e*uJB&j3IN*Jjpss?z*M%F>R^Vh)A;3|&I`%*--d)y)chJW zQhOcWw*@3cq8_Z*a-rSj2~ZtsdNrMV!3AQ6^FNL!dh7;p69TUScIj=;D$q}A$1Q?Z;>c3 z`1UidO8CC;EbA=SA87bWaS~RKu8BT7Se3~}4!iRq2$XE}IBMdqf|JFLDu%v4s>oWnR3zQYodssR zkB0lJ9dPFyWqBWNw9P70E>%dIXiv1~exa}9sq;JNelK$5f0;L>r+!p{ZtOOtWHOel zd5+KgB2som9wY<9Fz=(MVkSN&=61F0qB`I>>QSqCgP6klqvcE3V)$eSpwFMoB(6Zd z+`AIz-ppeo5nhY9euMCFoRJtHsG~*JMR0e1C(QQ+5f|0EudVbg$^Ul4-GtJ+gXSFL zbd$HbutCnLNq!~xA3FgFfRQ*$w8|Ph)#>9Car(yOX!-ETU0@nMOOE04SNXbRQ<~p^ zQ~LJ)Mkt)iVJ01?EeQ^}REUpvG&my{oxfxkX2022^ zvh*y3*@bL5$DxWmJ4dLOpWTh?ZHB=HSv$h@*~RGtI}>VVn2AZx zUwZCd<;K$a0(FcALezVdo`1;BDeoe^#(lU!hA&jr_#li%+LN1&%;me4Cx;V7pB^=A zQ`Mb&^Ya_H0gwBL4WPmNMC#sN|Jl8*{yp6Wail;6kzP`A=t*((=FlV*Lb8u?b2MaR zE&HP#8glqL^^5$x2kI07E7v{A)(qgard(L6kuR@`TO!JQoyEXSrX6BZs55w#Nm#=r z%7cin+50R-s&uQ)R%VQfql{$iIkuXe6EP^UAxH9q67%4-5oi10HKuA~##lhL+3@hK zLI~}vo*+)Fn9%xbO1m+qxTAew#RJMqt{tlG8TS{4(hn1BRC-I|7(d$aM|H0JYj1;- zJnaeR*G1A47OqCCFY7xl?G;olvsW82O)%?ySq=B_;6LYxWBUEJA^9b)zvd5T?&^sD zDY+!L!MF9hf6UICmo22zi3wF^)LiN-fuSqS35rlsn{bK}osknUbH^a~4!BiJR0v z^N6p$MQg7vS=YRLda1cI(<0nQn{(=aPsEKE>Ny*xO?<22iVh^*FqL zVI9*TR^eY@YU#S)($xd2AFZ$Tqt)Wx3MZPpxu=1kIN_67*OLq*ol*L^ppQZr?re?B zGI>H9*Ch>XwsD(xp-iWd*n%WIWELkMESCfwd*)!Hr3Vv*=^_sgm6BnXAx~b*Cy1g71f-QA$Qex zPHdE#V??B3?gm{%b}Nu(2EJQcgUchiGUnorZcJ8N7A+DB_i^vR+;u3|oYqH{FzC+k zuJ&ldOhB_riH7_-x&Og@4)&ED+AVzFy7kXu0=DAS;1K#VO+E3+IG%(8l0a$y61h>i`a>s| zf#r`x@i}Q%r!)WRu*5IK^5xzutz@+CUPq7BlEWB+V`aIaU^v1KmRZX|jP}C>z+wL4 zOW*ejQS2Gu^-qHPd|NRQ$! zsh*`a7`f9oCmo5XP{s39-3nq-=KsjEe4f05gB(FCJYxLqkclY+S+$9l5aQZt^ zNBg3CQJf-$P8Xb5#M*`Rq@FN@>VDwy?ftdg!;s&Xtjvtp&3he zx^bQd=B+F%(0cUHbckkzTgRD(jwGB<`>N+pZyI?)Gf6qFN7R5MxY*z`xs%9{3%6KwrY_UKL?Jw8ROT0X43OMPd8rd|vz|M1=Wt6hXx8$* zuP{J5m^Ol!-2pByiBNv$XE1xz_gmq?;R`2h%#tmtEiEP(^D3LZ83xO|(mwdWW0|t) zXm?d%JcHe;x$Uc)lOSl2*v*p9-bf;D?5E6JsOO+FX~7?7zbfwuEjiqF|Kq`#-s#@Z zedh1~JrBMNXk{8xkomzo{-N{riS8fAc;wDt^r+QODyKaU_;FN8t=wR`+Q1@;5QNUY~985$vgrfQG)3@vsm z$}>U4P5C{18V*q-f9oCPhZaEoC-zGo>j`9bV{6}35sw-74X60fj|eT`h93{l zlc;|2^Jl5mn`%ME=ZS`&gRK4>et8LiQ1JR-NYt`~n`L`J0}+1(wu>^;x3&52s0O%I z8Jz?~bflz~{LcnGt8<5%v{Nl*37cojR?OGq9kvxorqLayl&oUnB!gl74lEW=rdDKk z4*4u+<@xun85Rh1U(0LY@TXPnSQIog%~c=xd5QnB${1IF|EtJ1EqT&0Bk9V&1~&oJ z%2=ya#dnX6V=K%LE|5Z_Cpz-KCIzyQ1n;(VlF{ z#U1VDDh)kIBT`zC4K<~`($Hb7XdZ2a_dw;lmS+~TtKh=PAFrI}OS$NeRtOXAg57af zUR%oiye@Y8&X+eT^PzR5AmUD#>|0EU-!d7zb&3h=m`)cMXPl zO-|ME(8>kz6g>QI^qey0pEGf9FxS+wXbRW9e)2Ixb%Y%faP&TLec~@6hydDnMj(Dr~Re#gjzem&?65=1!ySw z-01MJCkF3x2iH~5T$lW`kG2oA@4RvWj7@L8AY3%Q4!^HXyGNI_hCcp5qyDG_+ts7= z+V19aboN;gwB~EEQdwS0y*}ge5@M5^fJ~OljIrXhb@$|<%KrDqze{2rBZOxIpl_`W zK#+XQ2#DJM;-_2#2r6iR-=$}CLGzqZaoQh_f67hNgFPmy;|nLfD%`Q?cF)^u45md2 zr#FEjraWqVn-i@IRQsP(7Jfl8F?b)O9Jq@&M;+6D-%>Tj1Hcuh4cEABN<+FW?JPMTqHKQ1P7<~4R$0b3J#;ku`$;P zU|dSoC^N$khU6pR^{317uiML7?j*+m^E=X?=BWYr{B`uAZeZ>8MILO+M z$r2?Np4kEx5g_-`<^lUB9ds@;@tK2 zcqe3et~u7{Yjio#8iH*iTTfZlN^PJq7o3L0EPfDfv*5V4&!Gn3V6O=LMG2?{jbjlO zT5JV-7eiulAs_A!g~b*=E^Uc+NQg(FL-V^sYkt;v{4EhY_W%#gc=xyW#iX!iX3_hk z!ojF#d!SOq;yvdj2vER-7S4V4=M#!l|5ElwUq{(X7|*_;CGloREgjY7jNx~63eJ7bi7f2>=Ch%%QMv%Hk z4&lGO?=6g^W@vQ@Zm_MH5P5iwX10jGe)yKUGJ50;@4{RHc-Iw*e*PL)>=pYgm zMay1YB`PeZs+CyyIoZ831+5!Mu*%(m0x#T0Y5pO&5|3k+aBuG<{K<<0G;*=qAbR85 zJKgU4pg#1w#}VdY$#19s&(i|me=YK!?)rCC;1N$|mZLtNHg?_urRwatl;K5|2@%3y z6-;-?IDD<@h#FTA^F;h~X`6Iswg2JQE0aQr)MNuABO0HMz$xMjJ>Z8zlM(ipCr`K7 z4UENg2YeM8FO4EsyGIGUjXXyLrGZdoJXXzn#}@c~tMmwKims6ugA*86^KPxNb4zW{ z*Ae^1M^0|5&D|ci6lMB{k*Su7T^=PR%axM{J+jfkZux|N9snMv3cQT{5jE{5a^fqadeEvT#U64qCENG>0YPS5Tr(%A)F0%ksH;t zx77=lTE(xODY`46P>RwfzewvgJ!G!rgn#AHX(53O;_AAkgLGG&mf;Sj;n}#x{5yRc z-;&pHKHjO(FYyVh3j*CegfwjS)-h>Usv2H-7<1!RbQ&|@4yp?FfuP3%0Qd)`tYH#6 z%A;s;vEOr|Tyd(J;DYXitFG3SQROMcjQyEZPb81RL@MxF z5%yoqr(?1DxnyI?l6}p#?!GRvY&a701V7Km`yCYvYw7y=B8`E#_jVKu=(sOA)7+7d z!I`)m9F#wpBtKnoD^#fFbpY#QXmG&#b{IY>9ju)4pe_hKNFyc0_|fLYw^w?AT&dCU z4q|jLaq^Y@%gFywsh}1Fu?3EeY?*2exGDaMMblU$fd3AgF5kb&f03gs{OKcMD}~P_ zHQ;TMbcC7Mh&ah1GR@uqsv|>t``45kbP@d_Is7m-ZV;&lNVs%RfAFlgbI{eI(IR#9 zGz{+IqOT+i)d=PwS#9FaJ~=NGjqPvQgxtx}#RdsMv*)pdhG?LsjL>^Idi=0ncxiYu z^LzY+8vgHb4JTDV=ZYZ#veH*WZ@c&f`lP7vplC{Ko5`*qU%8OSJEVwLNf@Ifz0btY zAjv@iS-cJ}Z|wQ#_R&Wn%1qMrxCykDPI&)8Pu@1jejRU90pz9Due7^ZA>ktM(_Na@ z`yyYab+-O3(=B@Go<*E#y2EX+a`46AMlIE0PWzlgQRMRM)JaYEsZRxJq^_{@7H+Ayi=#a3+zdDTW`ON&GQ(Hq%H;o4nxi<9_76%^=@>O*I4_Ht2p#euNI zLttY=pnhJjd1Rr{yI`qPRW%p~5m%boqbJE_SX`1f*h91@g=i&x^-U)aMrxooUZpg2 zOCm65$4t85+kN55HY3of#<9Kac8_+6p9ySp+wvIhEKMO;{%V1J%|F6_}sPJDpk-S9^jYt7-o z5VW6q**aP~Y_#D(vq3(~*+ya>_o_?Z6LX!_Bg5d@5W8H{ z4YZ@%n?Y_3hgrO*{f2n6@dA52DjeqafzA0|4AbnP9C#U4dI-9T2l+3FJqx8i^Z$d! z0UK(ypi0Oou*)bVF|)EjMMPlSFX%)Na-q`D&_JklqM1BSKh)Hy1>4R}PX0P4arAUY z25#qXE&rkXfb=28n+~-R38`ROR?oah`1)~Y`RbTMWT3)zk(=wAxWaq(rPS)W((sp6 zA~(JZ5`WvX*_ynoWA0|M{SnyatY#4wQ#SpmN{(h_IY<*6Od-u5=FO%yO3*?+DUx9!EV8?6?lP@s5BBj+bY)Pd~2v4N9>QibN?&8 z=k{`RRM?=;jA*%|##PU!&}a+TVYNt%7t|-y?oxzn8so`^*Lk)Ylt!}nW;zl~Me}}e z-dn}^o76y2y;?OL3`;2*73Q`eCFw>-U~l z28g2HP&L<=VOf9|3$8bsa^7Is!vX_67CG{qnJfwlL+If=ANLZJCF%B(XBnda{;K;H zF!ZZEG7djHrkAdITg_=L!eqPk?HSp_-!NAFyrC-MqWVhpGnt%*z*qlPlKOaDxc0Zl z%(19MN5?CPhw}*b&d>8(6JpCU$wo`92lR2um9`aCLPJ+?NgqzDTFB_1>iV1+gQFm0S`sX8kF_`C?6I}aa z8b^t7ISycb|4etWs=9)nP;|T4nimOFUt=$|YicsV7C(Xqsitv9d-~c;e!)Kbl2*Wc z`g&+6!}FX&dMVRW78+h%w%bfAqAus}3+Cu$y205xtM?6&EbIFUDsYs+uvx6O3D2EW zVOBPsOvR%o=?F#c8t{MwQBjDX<77v~oH>j_zOh%48JzbA-c_$>8;M&oN6~9WnDf@_ z6GnO7azts%i^z#ZjbhuGL!o9XypnM=_ZM3zAb}!1^mf1SmV-dPCl>}MVg5~71>;Ig zyC$DDd%E`)Z#CU?O_>Hm6%m=OPCuB)GQVF)LO$(;|1zMzb4+>7r)+AoYWwaW5$Pxf z6XNPV5#8RG5O{dWf7=?1++LxQ;L(Ax(v0YR5;`y-;mi~VoWIxR6SaHvQM&;W1SGks zRc$s1a(~dBcqC=)DKEu(b0oy_q9N-WOyaT*m zi5yR_OC&hSYHAH7XX_WMp=y%0JsrWg((GX?KRzafG{TK7sU2%*d8~cKy*S!m`Nv^4 zFuQr2^@at3c0_$29C#O-pWA>o&{68e;dM9EH<2i~RaU1lTLHgSFIS1TtfBK=3tSQL z?qIBf+eOyAe0AFRu>AthU8dj zABPp}=Stnk=uVWr`d!|ciBYMZJzdTuj741z>YF8;Vp&B38;onBt?6H;+~xTI@xyJF8{$`t9KQnfDr+($-5B~GF` zi|HhqYTC!$jBj?``#$XyIpf((qUOr_g&2Vn)6k9Rr#$-1N7|=U5XxG(Z2qo^n!56l z^r*!9|3i%H2&QxpTpOp1ZSKrdCk~~RP44E$6w+-g81H!FKK@FWzH#NxW5BfEQTzVj zR>gnW34Q&|^272hBa{DD{sfYu3S%ExW1D^LPX$?H?(`Gzl*{XV%KA@~PmrSYA#DG; zf~uR#@PsrP)7lCXZ9=4~OXYX*uI*{HF2f&zDe_PFRcQC$CQAF&SPb22e!D1c6ykk- zGh8<86Da>b>5!=i4aoiHD&Qr-;qBEZZpMzU9pOY*)4-jKXM)CVD=~mnrhm{vZA# z+d1i^Tpl5~miB4l;6U&w1Es5=pRG^&eP1SreZfF{qT~^GL)iZSO!?8p=j5 z9*hc=qP6_S4co{Dzb28hxl*pDT@h0xzDi{NvyYfIMC~$cvEk!6ci4Z;y14}N3W%W% zm~KZI?9GbJRd+HwyycH0VJ0#4O;OQ8oSI>wH{QZm+Ttjk3xb0Y-j%=WE+*nYYv@J@ zYnk9@p%mbZ&=K1w+?rrq!||TMy+n41fw*$%vNZqpyMi2jS8^@ssOt4<`m^(x&jVk* z9;2~KgUZu6)%z6>#$MXO=sNRPp0<_dV{*mqi+gMHiS*F~3-!Va>wh*%QM6uYu>{Rt zZOpgv5RpgyS^gE*mm@m#IHh860UFPblpCJ0Kj zY>SH}`o_kz3pdy1ArB8&k8BDGtc6=erb~Zf`K%r5#2KTle?^}XvM?tNa8y{qQkrSW zzAzNPy`nsKti?Rcus|5PlpGw`CKDOmov(LHFvVCD3<3m|47_>OIq!}dw{2Ui--!=U zF>@%AKfc(xeFd!Cek)UwPblnL4-m;O3TeLPvOMMpXkI2T-cKqV06PrwxOE^`#HXa- zHHSueRnvH;G-sE5d@qpxJC;%cQe&*n{;P~$B15h#-wV)Ijm^NjS2L~}U*&;!fQ-K} zO){n*5`=TV`HwY~BRm-6=(tC`e-5V^61BY4p--FW@^0ak)u0y!G4wRqMVrKYQC2~i zm&**y%pH~tV{-%ziz+n0xh;SU&RZb?4uHOBot`u+pG|iK#_RCR75iA%9SAF%{g&m! zDHEe0B@`}btos8TXakev=IF|{5z^K3&*4~WeRn%m^k|`km63Q{Ftlc8H_Xh+8VCLC^9Hu@gnUv{ zQzwivX@}95xjbIWHbBtV7s;Fr7z+`>ztcy_wB_zlMJl4gb+Kz~84e3vzLxp%C&2BrHAO*gNQ{ z4_1nsTvq)>Dn%jC^!$-xQGOdo-rT&LdGk}T)0@AU!C4Q|mj6pCh45^Fva(UD|I9l7 z872O@%t4y6v!uLyGW3ubdMhLXyHdNA%A~Z@=>+F^z9KRwXOx+XtM~4NrMkKVHj;`| zPOiaz-y0JXGlLt0ey;JGfq!Jz>;jj}Dl1=Y=M+4C;DGm;UR}x1Q2|rzQd{Ppf zNndm;4yvLw(r#e^ITMYTH{G|1NK>_@<{_b1x8YKtiN+8Mx0IBW=~NEX2LSQjZ%_1_)- zzh7E#=Q5i&@EUFCGXI_&qS3Bk*r5M!Xmd#s^Yxj|fwNFhFi<+^zc0}HzrX0;8+Y_m zt%^Nogqt||3?kp>#SqK74X=Dm7-gKGJ!1)({^=6qWVHmK%4$8XMM<~^WW{`byIzsv!AvX z*Ne?GM1}k3Gow}$nYUu9%kOMBEps9S~c?k|)A6;tOhqZH&bt_U#K{PDxLP%md0 z)~69XPP6tueALwHlqNOO8r96Qc4Ff5W0S~rttG@hQ*bq+qY!c?9H{fvL4ehf>0CA= zH_ms*%6Rzr-Ltb;!^6Y<0`i3l!`bTb5R2U}$Wf@*{Y1%5{CuO038%9AF#3P{$^Xr} zzxQXv6yPT+<8|n)0seh(o)`SHB3A7IC~leAglxm3P8;}doBa2B%luLO{^+WI^Y0## zmo~O#1xRnh(1eei1trfGz!IcNTkY_e9xaJ$sxV4FxKDNiSx%~zWmFduIK2MtOaETo z^&kZOLdWTyp?{dZf4vTVg|XA=RU7o6$m{^A_`2}`-0WUOhBN&aqQSxj_mdgYQ6=a#t|JOcol8&+9VJ71q1E9e8|gw;Q#wt{(F7n=2f+7 zlZOmbd|)j-eMKbkfvz)QGJ3KP>NL%l=Vw8uby`^a8{!Y8+^&wL(LL|2&?On_@kP(? zPiM7Cqu`t}<`DQvJ}(S6C8Dr7D5hwZ@3Kx-GD?Pz2Go?Y(3_X;fIy^E;#Kg#JZ+LQ~*>M1>Wats9n#v?o0y!c2GXoQcoH}=T+H(s;PNWd?Fa6$KV&3hFMk-XG`p{D`^mDm3dxo*1~gy zxHL4%5aa&c>aSB9oP+#Ko(;!caul($6d;BNFkYh@9Xj z<47N0*wt+@P0;8};#0-329~VISiUuZ@btlVS)lCMpW~-~_8X39oy-3K#p%r5MAq)4 z7TIkBmzQN2X=OSCXDxilI4)t>o89d3F)$#DGyUOJ8#NI=j!HqkKW_t|3pp}%n!rdj zxH~}LX78XKKg8c9!4Ge9!peHzh!-HWrWFHm3pT*x$O?_-qfznA;i(@q7>;It4w~bp ztg*HCVOMw>NeZkLlo==8I5KERqwHiH*5hnLUU6+yXJ5vPr%Zg#t2rykb>hg>;1En zc3>$3L!vjC~vouHn=6WiTSV!fh9 zh?JO^W=%E!lPoWr&e`AWaPZgaPM(gEQsjKS)rASdb%9{k)BxUtQN$Po1YxVIT7CWf z-Q(jZnvK?hot=V^m68U)`euI|0~1rxcr8jkTIhdIk-qHd|E~3COBLYyW2?^=spM_|c z9Nr-LBZ-W?5Hx~xLh{c|D&fLUG-wMTHYpPN8fBblHv@03{wjwT3J zt+{+W*joAa7f+Oa3wZ6;Civp?KqKa&mS@%}&r)Chaghlxy?ekAVf`4WPV)oLWiY)L za-8oBIWqNwqzvJ1llu=7CW^bII#Gw73#AmtI|0_q?>_UHA2ger?i%X@-Y|&4nabKo%59&|6Mx!sg~>tMgTz)@wZf zY5<#vJ~3qo`si4nEMTL-C8#d^e_;{CQTw8!qmx_3h^PM_(%v#4t99!dmX_{rP&%bs zKtj5t8|l93mIi6*Zt3pskZzC$>F$nq;Xda%d!N0Z=lk*T1MXW97i(SDobwuE%sDoU za(*1*d%<+}ch~11C~thy1PXp$E#Y%CTwGHdPkUrG-XW$A%r;TI~ zBF00~Vm6cVvfrIUC0uanT2l5cUvd1EHwX=W9-^A1SA=C#oGU2Q@3J`7nphOny9jl- zXsLIoN?d1PO~Ox(To?AK+;R-svt>Rr(;qex%Udy%Y^aT*>5IrL*jK-IbfhtxWfwIvf=gnxjob@*hh9)z``{uY zBZI?fLxR@HkkMMgW+4Tyr=0*_=ZeJXxatLh_TsTKn7Vd>yX`fyIW>dHqZrPtEub~t zuCp_R9GtK1uYbValQ&fJ7Z@RAcwrgF+?6T|vFRfu|tsB+v|2L7p$-`T_Etd7JiVWWHY z2WZ?HPgq3!-H9QIKEI3opqpa^NUu|hQo3|+Ny+68CtF%UVTNyTfRrHI(Tzv6l-`%Y zUMnGpsR`fN@TQ;y_y7_wY;eJ`B_L23X4QBvxJyQTrK$7m4|YWbv`(d!+}UMfgc(eDfsP*?6ti-ZQAsh^a0g&Med>SK+bFD%uzR(Zb+82n z#1bIC1gs#5{wEXv@d|nDv47Fp!h+5zyi#vP{YPHJVu zPDbcCt*CYu=CGFeT(dk3-1?F8v9L&JZ@GOK!G<4sbqP=5m5C81XG$_38cRE;;^HK9 zepWIRcMtZ-zLFN`o=LNkFvV4P?!?w;`;f77^=;3|N%+RvfSL9KQQ=OglUUo=TF$`D z~rp5Ibc3St>pw9tz%1Mu%~9At|VDIU}&(L-VzLj)eB7Ko0s zrY3*gp<#uLCJRX2LDDBPFzP+Un^&A_Y*w{CmU)k&(Y#y9RdW^a<-jhfXYnXdyWULR z$wmN>gGOsswV)=OS3Kaqa)>1BS!-wGR7CXN`FP!eCC`-h?oBJ4U#eTopTf&*C-iSm zZD_2s5HZi!SuE*5xlo;h{?%;%r!s@cRP?Y(eT99%st~|$A}qI_jLN#q#V4~kYd5;A z$@VPLCRDWOP7fYpakgN)(~;YMnjq>f;aDzkliVd!-&`cr%0%FXFjur7R+5dbZ}d2C zOoId$D4W+z(!P8d{ch0E{FqJX&^2bj07Uao_x9!G zPSo~<11IQPmR?q+UsN!x?&r{#5)J?>!o$OvSXhMru>X;(v(if8FA0OFt*jIR+^<|O zcDw=Wr}nuy)zT*OSq7IyfcQorT2!Oq__m*y^I0hOoyg&QT>mIzaa zHa~;rYcV0ALS9~adPOrSxiW3Of>h`*QC}citj#f7wp;Y&^^yEHjQc*x0X-q9AkzJb z^95{XjisNebqE<49-;^4_xlZPXq4AF1q2sRpPjSb?0Y3|>^kmFK(Vv4iwpwri-MU; zRaF&GHC0ad~)0JBsbwek*BU1`uaA%MN4%Fm|I_Ua>)uo7NI-SXAVqYvM$&A zsVS9yWnIjltF+6G$@sPXsmh$ma*M1O)j^rD{UQRHlx7sHb(A+-Nog*T)O`uuQnxL# zhS0b(*Tw0ox2mUdFT@jueDs(yQ62cX*0)U-XKQzjxeb4Vm1bDyZ5G33V0seL3%<4^7|C#Rm~7u;$Ik%T zdK{As0JvV++*+}&xTVv@1mjgLG42{|-ls8OP&<3g)WmaQzf#&yCYIQd(|+IY?-z95 ztPzw-#$y{vr}wSPJg%8j(_7Ts!p~ZNq(8^P*${wS?w!aLE;+)PeFj3(->lyFu&lIr z!xyKVH@1y3m;{gkY4FCGj}Q2ZU>oTTFd8`?;z6Xnbq7n@$mshbzxz!&fqPjIZO-@a z1D0VF$YwPSi`_kMySlq^qM~5y?Wq+ClgYw}Y2%+SCUrn><{dWMRwU(EdmbFtYOZ#;g4R41CYZW2u&kii0mcrNvxE+m7#p zV70yLrA_9Y(pKhq=_aRGxu^=nEyFXHC5qqok<{=dfZi1mCK zNOVTqub)G(TNG_RZ`l_IE5RAY;nbPX-_51;oCSxVWDG7wRH>3*63d(Ya2@S!JY61p zXn0-5z*j_X{!F1fasn3f&JxQD-|xsB)2@|~kJyuCM&Ha05jn+FL(8QwmsIuagwCb)tyh$R znIT`p=&=&=9IdkLKjjI}IWl3W^@fdYKh~&TZ}LhJjA5}4$aTy}_|CCrQN6!uff{#nsY~kg;r%O%e~0)qiQ&yIG$Mv z!f{aW86T}7#BTL6nns;I9;OiHJ`bkx1ErBie7t{m&?INIhrwz4lbcco>Lg;XbrXl~ zq%hVTBf9LntxZzJqYA%7=Za7AUbgZoPsnA*54f4ZYW=iIa77hMvzE9f?8AwLTDO9>gqnsxGQtqD~-) zGzJq?^|~k!=GIjn%&-4s?pj@GL?xileaayzPCSJQ{|v_HSqTM^nuT(s!K6@KBPrgV zXnnO-%wXp=!5`{wUG?rDycX!sU!wfdKKgw%WO9D!UOL;+;4I}3)Skl5;`QB|1CpxO zJ+uS@kMyBWKA}d0n%1~gazaJ`H&8px8!>c@oXja^XZmQ^p`~Xt( zP*bm<^1YcO-jLMLNgInmmhJOwWO_81;vjc@>#-!OyBPu9!BQlu2d;k-!BnNKPhl+| z5cYK~)ZrVbZJCr4yFMh1gz3!CroX>dbO228Y#l#&=qkyn?7kHS*|AB?X6Jf7x`KEB zHr*;dE?^Oyaq6<%zhZ~2Qs{6?yFVByfPzn@l+@=gZ14KZBMZ4M(KSycOU(MfKzL7X zbld7`nhwhTMu_7u-}nR@mfKU1-+i?3>S0VEtvP>3|{bo9>~pGi2mA#odUL6M#^5_F*Gtc=RikcSkh&piR8^baYlTb3s8tVmfX z5L^*Ap8^x6RJ(I~esnx=Sc!D@RDtnoICm~A;BP_g?#yK|bJv``7wn~< z(^wQGhoPM+u?*Jpb?soK#I?FoHd+51W=HAOhhCE0IWiB9su#Zs=;Z)=!j8#Fbbw>q znXjScc071ZNlEGK;?mLE3w^jy7ueFm2h;{o*x1;d+}v4OO^z=d*xki0`D{&1jmTge zeNw@rB-@PVF6)xn_YkNqveQ~+Ps=( z-NBdAlBBM>V?~q6F|aW8YJb33D&bu-1c6nc!HRMEs@%7H_v>3n+)L)xyX(Q7NfNAk z8By?$c{bDS7n_?nv+&{f;X>L708M#{^AEJU;+NCJ`Yaz5qSND|I0zBGLhrcu1Pq!@$Fcig^Pw{w-|}>4?MZ-f!A6y4eU= z(%<5)Oj_fzgafZY_frLvp!?GQ0}cK3QRFz#HbgXA%mY8cR0ruxbBqnaN&}cVQlJ?; zq@*?P{ea}oWCs-cd;~P85``Ew$Rl}nHBxgL`MA{O-_~=RG`XrsT@Rl|+b8MZ0*yx6 zp|$2c`O;b_^&jK}SSLK>yf3))?$XH@JpkkG=gy9>$lGldX9v?SniRvYn$y$#Y#--4 zMK~ULP48yIb-Q4aZIv~IK72?{%q)BL>iOd12SFt^O)IPLiQf?TUrxSC4vOinn6qf5 zF=sg7jE)82gg`JJfdm$m838!P6MIA7NKe*ICzWfD+$=VxRE};h^ zb!2oryg58=j&Q?RHhsQ^NL-q&G0M)=$LV!cG zvA2&|03-l5c6P!`jSjYV)$FBn0|RilxVQk#2{V$y1z})d&~OBh=^Lhme6H1<=juhK zlrCv9Pvxy9i(nAY8SnALq*(a*wU1WXyaX&PE#=!hJv7@qwbEdCcz84$?P0I3u3mWg z1%1!wn_m%GreT02_vg=__3pQoyk*D=zjK&X#$9{;nD#&9FmzN@`5p|64O*?gJmBAN zrt>}qmVzRiDJbDT%CCtxx)5T`IG|uVqKfwR1|hWs0UHe?NsZ*_&hYd1MIS&xa=NA> zm+`~jv_u{BrHyJ({A*trd|qT~92rb+azeuDObKvAsSS|G6|%Qy4Gj(5c<%}i58vPc z(4sjxIqyr9$$5DRfE~xg#?~`kq_WwlU!PAqK+9eB!g402P)!F@;i>RSy?B|9`XS85sN83S001xCYVeDBoWq8Yqdk{y{;nSuN&JfM^A( z>;J}Bc@h$Or>_ZI1Zp`W_|Ey+*#^Qr+1#_$BwCk9z++)E7|FvydcTZp!?E=%l*z(= zjaPt_i}*##1xVTeYu&&7?m!XDa*a>>H`x4No8~Ssfs;+nLs!A1><=M{iZHL)-fS6V zokLk1$qRi+{lC-|5vfINbbC`mj!Dp#&>Y@?q=EgiSPqzVbVt8O_Lc%YjGMb-Q5|Xl zdZxU<+J92KS^#c{9%c(YOa0t~+^mCBe_x4!>XJMsRvb^_qt06OixVe|#cS*sZ~1 zZ_2bm8hCh^(aFi#_R}^-S0+dIkm?+E-X)2(`6Mi;v!hP|+1P0E8T5_9g~yMdovN)Z zkR{Oz+T=95(}l;51?#PLK>dx(?r9f-$#=C(s1cz6QFeM~`r!Ho=g0j1-*|MgLcb1Q zp02q$@gtd!Kl~&Nzs}dtN2Tk$VqsD2?xo0-CpXq?0HIS*^x8O;MHH!IukD!l0#dfQ zpK61bWMq}A>+58(JzYR~1O){JC@h5Z^fFmJ3<|<=JG;7G5D94(y9guCAO%y>H;j#si`^1!8;@e z&%3PatZ(2wau$|woh5K+}|OqGekNZpZI8&2V?Ne58yZ?d&m5aT4|-0k}^Wzk=6mK`Zw+x?p*&^v4V;r5%ocq>)5=!u6JSDvef>S>E|Ii&neU`$dHGn~YY& zxzVe?WbKzXjYUYlVjZ<-nckizy^pN(Oj&N@x-*Z1e{f zE1Wy$S9)TOy4K<%3{>>v%@yL~>HhdCHMkG{^U84(&rsqGu?*MAQ^V}6MtK$A27d_{fJElw1XyXP+VMGV6FpiGAVcL{7F5)KY*K|w)K3m|YD6ntp3dZ{va7#K?Pr9y#>4@OH%>%x68%JfGz zY-{)}MKOh#C1U#zrvU62CFU3J;#uMMkk`nU0W}k}v{NKBHXK)JlFD!hc4zqh#_H{AGGN9;dqa>8YMhQoS&TF5?b;Gs zS*GP5z=8t6${=S4($wpu|0BPFX0gEQYn)~SZuJykdCwsDOjm|@H0!3B!9*y(EwftJ zR!ZK2V#05O*2p2=x3Xg05&R|>=}+j$A1}wrzc>2cOaEobhfQ3X{3d3@gM*_M4DG}; zj=6BIyU|Vbfx&8$ED1@8{b2(Wcvs=tCO@Z;YpkFA#&``e-er(BA^~k?j#QpEx6OZC zy$@g%zfYU)~g%6G_+@MdEw773K}sIHKMaFnC2=^R6R3lZ|+35*@; zxIMVY4b^6oX{0-$y>|dCslMyA2dl~_Ha%dcXNmO)CpYLA!ny&|qE>zq#`XSq{q%^D zWf!Ao#Bk!`%EUdbLVDY&Z6Sc?{Z4j&H!**y7>b~TaJ-)s#+CyuQjJ7DH*S~ zH3%i(LIYx9U|t^O!NI{;jk(Gj3JNknfszPcShzQ`Xg#$DJGfBD%lJ=D>A5w%?MK!b zC1F6{A}S^FQ1|HFPnQtY&M7MR+qziockO>Zp2ofdI^}UTxAw@^&EL7%69S^Rl2~nz ze>ZX;X)4X%hjrS~BYtWn-@Bfk!_T_lbm++^T`p%oA)*={UMaU+d28wD_21!wtgxKj zBVE{09S$xQGUwwshptK+>Cg~;?%C&@x4oI(scZyN? z9E=~&1YCzzRo~|-tWD%ff>J4@lUChBE*8G`=F;8fk7-{RY6Z6U*y$Qhq9;^Rd6{kQJ|LLwgX7y-e$u)lbVJfu@Hr=Yi-R4b8XIwH&yrv-o?e`=6qCObLbIJ`0m_X;Nb_4vy zVJY#nnuS`VpeG|Ze!lM|lLo!| zQWn;}#r;*BF3dzOHJW2ru-2SOlq9QFyQ&O~K4`q@@n4*GSH>}QbXCe(+v2*Iyrx-B znjJ8Xn;W132U>^FA+!(X$Jhg&xj_FRVf&LX-M4;rjyBB&e@9i*s4i6 zs|R~dC%f_$NB}YXmijy%H{1r_)HQSdbZDQp4l8S7HZgkI>`A6zX0M2bY8NbhMc))=| z;iUoKceN&2aE|eywMWJGes7qNGdc4@DOvAkwtK5Q_yMYHR4p*0%Gj3ugbL}2;LB

48f#Cd0hw)Olt5erP2k(pc?0CZISH`{X={-ri&%FV! zcI|RTxi9zch-@`s7(VS4MuB$7o6o294lg1ek-}6Ms~v6q z{EaxmcMLyJ0Gx8c`v#joCU*Qeh7`&ms#go^dGcGWw9>;|2%L68np9S;&NQL}pbOEG zsI2hF@F0Lw#6jGN@B#P)AR+&?HJohYv7a%25@=SQo8qCr8b>3DFJESo>i)`a4C+CeJ!$+|{^5r|XmwY*KcAi1p zXrixQ0MJX2pT9o-Y@iNs+m{xgg`yttbp#?6S_1YwJ_cYcrkVn|;&DX4 zDOOvwe18tpR1?Pe+M*~%eE!$^eWow7mOoQ)OL9isz2M$CDa ztUmOt)uVH*?-#lR^B9E}uhr(9?zqo%p;>Aa{#qgY>s>^uyL9OyAQA?81Rt7>NUcP) zdtwE=1hZ>p`wvr62uxV<8c-AOMQmIg9cy_#U!-v|Qc^K21KV3$WK2vbZO>0li^N1k z;q~>Lfa?CoWxf%Bq{q_JgWUz+Sz0twYfbN>)Dj|y#MzQxxOmaecyJ-3!&Li+y;CZ$ zc^CcU^gcpFquim$vkJ>YGgoki-GpvdDX05a&V<^=iM-~=__$0{aaKOgXs)NR)FP>bwom$DOWk8KN_9B}aY5ua0*#5166;ycqud+BGzx z(CkN8MKHAzmhujpE!JLRWA-k(EGdAV*j$|i7%CFy>9%;AnniK(CJUp~^ve#b$=j_@=0o1fCd&%FELCHpzNhA~S zs8eGx?jALpAMVI3o>>TR&15fdSkP(PT+#V1bTA^({oB)#)*?G7USY?WRdzP7<31UJ z-B7El<3zc%wd@@G5)IQwVdME(MuGe#ipJdW^=+R1R#^dmuw&~~H}uHCm?o+&ga9;< z`U1cn&@KvEvd=9hQ+w=j)=vStOV2L4o!41JG^79~3>s)bJ+pZ{TP1hf^pv++8EY}& zzrp&lX8_a^Aq$1gSij-%xKevQb#D8}>_x!#!L-3L=u->wNs_g20?lK8v-g+wY0fk( zU-yP~H02tYZ0kX!{#!SStKGc2GBo@f>BPW~O9YWlzvte(N=tp#K{%J{h)SHS_`dkw z{g0tJ(({2)$CkOGf%jF}3d#f1#nuOMiO-S^jnwK>f5dm8acP z^Expg5c$WaZ?Z9B|dxUwMp<<4j4=NY(rN0_i?4 zZ382;|NfEB3lz`oC7~MP1L7~mGscUnR}G0F6`xf?LmN2JHlPtWGTG!RXTT=Ze8gCMYuDC&=I^4)R*f2I95AF9aqCbNAo-`d?qODnARFxePo1l^cEkj~_qWjuo@t-yLiV`3io)|^WsB&Hx=g3>eiWi= zO>KL<@Ej`iy@v8(!&PCjm3inJxb22)t~%7`LwHf=G~A(~ER^~xXW-#9?ylU}Jj(lR z=dS_7G`RTY=g7zpsMs-}uHb7P{Ke`=Ka-Cec+|2b*{D4_pQMf5^Wwzs##c{wHxV3{p6I;CC>M+c(f z;}_BW%q{?+VwUH2T_DKRWDMCWz#Dn59q8*f$((FV_w6}jg8wHUaskM`SQHz-08u?Rghp6vL3uZ;Pu@tq@^5_D zbWg=cJ1%&y$L}Q@bT>6q%1rF+qLzWK<>j^BrpoVt{>YGK^%V-AJW}%O*O;AJ2^EjFf#>tvl=Bkn zTgQlo=Jbd@+mUTM{%z04t;bseq1U8-DF5>*(o5dbkZ@z0@4fzo!(yu|ky9t*x;Kr= z#bor+SJ4)rV^oAoJ7D`XTsAs6F&sF)<%8bYo}Ms@d=F``$6~uM`)caUb+p{#mZh_7 zs6NMol_+*<2-IjHw^0K{_fVy50~EP^>&wp{&YqK?+5JE@l!oVF-0^c9R4tM0muS8wHa^~^C)Q_l-REMm8 z^OSxgSCB%u+_4dERnEpt_28-8D*{-Z5eR}5D2FQt8d558GgJ5JLM?v1qJ67@9VRi9 z?sKnWfw3t2m;3koDwMPqYAtP#7P+`Y(%3K-pBXb&JzwsyiJOtnJtEy$u@+3VnHf9_ zR{#$qEiQ+!49SVayR)2Pq2lI!TCK6~QBa{5s@wv|1x^fPHxasvbZZXcdP@j|JkA-3 zVW>9ukTbV|g9d4y^Bs?2ngSiX*A_Qr&o}~=_Dx8%%vCjDLY^M*Iy>&yrK*FEqKN$6 z1N_5!Ik0=PH`qS+sTv;PB59YKF>w-5*P}i?H%CmtJOTKDPJ<2p7d&)h30DSIS5x1T>?)%Z_HwuwJ$KOs`9_-;zkLlZHb?IE)?x#stj zsc7?)V^QZhlCfkuqj;?GD^+@^Mjs11AXQqWvJ?{S>-%W{0ky>uwT&jQQ-IKw#qfJ z@0Iba222O%-IFULlNfS|FDYA>nW4L8+tiG71+1x8>e!GERLGe(D2HynrR$WB27tLa zj)ZFq-(aqc$;nPMhSbYy7^crYeW{$wsJ+g!ajs$8n~DX$Z@_a6U@|*^ZQ}ox!D#qM zYeplbyBJf_w+h8nQ?^xxR&F`1GUIC+Xj^VNDKrv;dnLxF6StxYT(a|Rqht9V4+NHU z&1?_Koh83dYBREnu7FBcdt`|lQ=k z|KA(vc6L{dgXtzhyEPZss2f{_8=2dZk9Um0PfJZs|K6za*YAm38*y7Uf?Q3vZ4Snm zQ*LN+wi*1_YUiQDEW`A2+=DdY4I=5|dmi1V>?(U62m98%Za8Jq`2q*)h_gHmG;nD5 zIuF(y{Fb9ug3Y))+-xXWH-^WIyH}@b?#t`gp(m`@G(QNQAIS1S_;#uzA8J8o1ushz zz&_$P6ItG4`HpvU;;M{7uYOa?fzuYXMn;~SYKDFG5Lhi+FDZ-{*$tjeUT7!bLu=D+ zBQsW3HoiCq1(*)3sM@V_eBg_zqWx&P4oiOBn;&ZnQ6R4evdT(b=~$lBaeR@jG)41>s+j*()fbalIB= zc)|{skW=njbQB%mC55TZ>>@plD31s<2CvpW<}5LPNwWliNCPPHE~%WpWqp4{y*U?x zq2W2}qy+SOH(mNCSfle+8v;{~N}#F3Uwe;vBj@C@-gi;XMN1?;h}XC_0;4(iiA$UY zm>BMdZCp8_xJmjy`QhJ-gw#(dP6XZ>XVx0dKNzZ5{eE?M7=CAFn6N~ht(Uf}+NY!h zN>lS-ywZ>yfnW}HW(E*j6h|;Na%2?ums9Wts&xAkAqySEjwh3(RY)Oc4#NenKcx#XExE9 zwVO27$s%Y6AL-r<_`WUtNdU3n70&jnI*z#=@vR4b$CN$-7NT}YIt4H%PBZu|J$I)P zkxteDtKWdHtWry3{_y=r>_|@*NMttohdtGNa%GZnFAu@h8}xYMQ3l_o`Z_PlZ@1X^ z7>@Z1S$N4c+Y8RSaFrXMy&E6(%**tUzWN^$6T3%G>lv2oHp{XhDV|PtHZea}&SErPq~tot!K) zeV``_VZvIXDpD7-T}RT!2hksxSc3 z{r0J?i_0yY2lCaGvc9H~5fZ@d_SAp*66phS=S>eErDRc5kE0>SO>`>#B`6b+FQ+?E z9xHBFCp=2Zx64434~oL^AiQ-!j_jDgx(e5KJ-e9#EE-NSg_bmB(6lBdSzdw`kcB@y zFE*TKz2xY~vme7PjL3Wj7)B-=Kk@mJXM`4sc`5{o5Ad?#fCiq~4!oZ#*ZTV(smGpC z86KH#F*UA~y}u0V~Sf4;uGq<8N~zS!<~)FQ~SP`e0bPEc$H za~Zro?aKJ(d&c%vN}~$i2+0HeP~z)Qn+HnQ_46CbR~mh{suzXmH!v7q6<4@}xL~}5 z2xNCux5Z2?4WLxn5}-m(m-Nt_5IB&I#n0l1om{9p)T+1-XA{L z=RjHr&6k)fbfDczoNv=#AFFGHc|Q{|;c_Ekjq$DE(F+KYN4T~xq1W5mM3IKNG6oJya-H#W_+^fQn!6cBoBbw(c+SX)`eU62D2~YumO;;G8~qLQ zXx1x{fq$=uP!!abmzRN|J28qIY6hmJ!8ti_&`U8s>c0!J*Dh&lj-5e2qL~w&eg$OZ zp`+lQNH&1qgORhEe;&U385B%ITK=4PMT=$S0&i_~OH4LpL0eYbaZ+QT>Vz`h%w|s{ z#W+h3RKf=>>HTP`QeoZ~=&VR*%)Ld>IuQPzneE=-j8^90^^)+1 zRpf*kZS_$#HzcxkBHh(7s9)9mwI@^J%YNO1yUwbUkXvOV@4GtA_0|u9@eChnn61F> zPm9LuRaM%212r>T`I_BS;8MyIk?+XzKvK=sGfp>D&7ZBmgtpCKLtfdrIyhsZupLpx z$c>XS6E!sJ%tGI>?RR|P_>oSt%|`}Ps6-TC{aS>NI`zDdIj1UYyz0vDv46Atl*nJ5 zg2MgHKV;@Ka9rF`WAcq05LNx}dU-=6O9e(o3pzVJIWa~4op~A9j>)j+drdAMbf=A> z?Wh7iI>awiQy~iTi)h~u=(*^*gd|i%CqP`B=}zV-onF3%n%#vyyalutr)}i!DSP0z zPBx!Mx96fA#gKN|0(YbcrAs)>!UAgMxV0C*+^$ig^wE-+Q?H|Wc0NR_WCoyG9BN~U zgeZxxVq!aM3-&-stDGv|(^A49`v`Oow@^mLee=bmU@za{g$wJY3yf9q+TlBHles|9 zo3O&!o9BpQdF9I;aIgZ?KTBAm6XU{Hu81jT{42AcDllb9e7OSL7W?{H*VPlF!pqm)}+dA}r*(*Xq-m2eu-ziP=dUP*5M!~GdO z!ee&Jp5+Xj&+ow&kRHc!TQx;tSn9xlR&*q#I@xm5v_9o~@2kVsPGp0b^}wg2Rm80Y zM>c$ClW_?6yep!S8A0@q!wJD#Xddlmla0avZUbdhJBFpo~7XzaBDw=E&c_70YoUUlkX_ApZoxD<#_p!Ed3fbal7+ z!-L@&4>U^OnfmM*q#-6lPX8$kkK$i7Bz61mrS;c?l}nOliz_BD+efZIsUDaqbar+Y znUaD4&>N7DkR-IU@PI5(f05YhfpkDbOf2Noy%89Y5`4SZ5Pd;3K?h&3UBQliS6?L5IO1@%L`Yj*DqQOrJ$b$w-`B zBbYHH2^eagXHTU2*;h3s$r89dKj$loVoM~|-<{2|rHr;s=o*pF9Lv+K_;|sR5Egpn zq-0G*Io*rp9NePR$@Gy$(9h=l!e`3S@&D^RdD)=-ZM_Q%8bset;vQsEx&49O; z(DgKtzlwRPRexENm*>^OV4?(bzG`l=T=YAwBi+3f=?7puhjq0P%m2|cx=A! zifzfopWgGaZE5Sw!E(qYo45Kv!a!VZ#sL$OrvcC2#D?xR1KG~naT0bay)v^ze53Kvb&Ep6X&7?RHKqP=&Hh3m!s z4q@C;FK9kBMSwq2&Sq9~h@|)yUwOs#FMAwEEA!Mlj1P zvdOF$n9=h}U|lRe{%mhbg18@p`cpU)#p3fDsBYxLS}cAKW1=`&bHu1iB9Q zBmu{a7GWzzj}lULv#2+WCydC={*1s3y&8nRZ*{KOdKE68;y(HI9;8#}ujE0Q?H97A zq=#=nz(=J~LH*bV>ZJQEb-}G3Ua2;pxuv4hjMWg-)^eN`LQwsE_ImhQ@7fY5i;P$I zojn0v=;mi;WEShyqgKOuou6}0-|fcciu@Q+Hj1L2w&C9BG?5xJVa^3Mvv~=p<2wJS zy-6f_+I-tR(3 z%*UQadi1+@hu6g!{mawfPaasd=}k^ z!7|fW0Ua6bh=j3>1a3drgwGJF)zg|&yA(5Yg;B*CDpWq*x-W%eq4Q*R#rEUK{VXnG zd)DPSb3q>8I`V_RDpxWPoTB4@pVE_XJ6a9xRHwg1r*Px{sAK#!wI=+!RqNuhx4-pm z5;pZieyGN_jaK+foypldyf^}8g#2$Pj$B&>R*x&~@8QB79rj@I=6}3yumNAQXsfZD zM-C52s%Gc0H`@eDR&b2wKDB9aFwi{RAIVHQo{}5{xGy=sbCH#;T@9}_u-@(Ndl+}@CfamRh zg4vC~B3}lxOnF{lBmaRZ5(%JruzqikDe7eez zFk7+{uSWbY?%xY2m;AhwdZ%&UFxTAU@t;bXSpD%%{NBrCAw7Mtq8a{rr*m*_2QzQS z!=#Rh2@E14>9qrkkPcrR@0uE10>b@lNo=ab-gwYmO+BP+TIlvq!yO+V^!OO zCd-RpNJul~mG4B7*+)#qv!W6L|NkAXzv&}tOG)IS{rowN{q|E=34rW+m^HL1O@X}l zrmkFI!b|or!*FTI2%XqH{9-8Qc*|x(rxRubgLgcL^+v8Zx$0a`R-amt#!rZ!JP+{DOOEdy48V*Ln{XbHu~LytpeBn`-`u4EA72 zL0$yRHA_@pBO?H&&O3N_%E9{12Nb*WgN|~8&PE8eMK(H00A3Hpl&s(=?%urmNcToA z!slM{QXl4e))&;z%W6hdV^MT^;*Do^2{Bb{`1&!4my*z_*3&O$JLla<8=#{3Dt}Iq zS+q{KoYE#e;)cgtvM=(QRF(+pT7a0UzHN`H{<%lA;~#H=i<=uc6O)`wlrbXI^)tNo z#_AJZ$+8$ry69N+Br=N?nbEb`=QmsZT+sRQ&zMtgHRNXzo)R68)1B~Dv$7)l7+wg^ zC#G;&Uh1hLuLw%B;ApfCiw7zg&NUzbGpMng0Fu8 z!KVoq%Zw-6R|VM4{~iQeXzwD-UR8OPWtLLJQ40`N;J3XOormD^9fWyjMRq@t-v7g> z3wiUvShMKJcdVNg5w-0pToSY#Z4e<-R^uxz1L?`=Rq^+HHRTarwgn$6oCY7UH zv`MOfDuK@8va|B3${Tr49qVyI>BmHr%NoXj8>YaBi@^T>ig78QaxPmfEshs{GH5=N zpq-mnZ|~_LqSs*WZ1+ypwX}p5>$}^T=s~P8!)+ffVb;{b*B{GJ(Y3Ik8n`~VeV4@H z^u^bgt+-ff{CgM+(7Oicoi%W9)iT5)h%AW0O&05!0ihM7zfebSo$e%Sph5x0eq>@I z^<9pId-^Bit}I|TaW$9IU(XW41%52c2v1ScS`OV0e2P8+|l`e63|_#?C!rsOm+?LaqFtClMFkEF-e)fgJOp=KfD}2v(>0W3g+w0 zG&WEqA%`rYpcjeM%%M_r4oeTtB*g11lv%qIA-F?2uM3ng6?*N`nZNn8{r^~d%cwZh zZCf}%a1ZVl+=D~m9s&di?(QC>kRrH4NN^1hG`PE4aCdii*YEA_-RIohXP+^?JI4K2 zKd7SWePqqG)|_*}R4?kgD9Q~yZLWwi-~54z{=P{5^=fKlVF4B3Vu~w|3r-ek!irfuI+)m})BG!fFN{b+185S0dPDc6eo$_W(g{s@Y6ZWD$ z8mobQ^_fXxbGL1B1P=YdbZzKAtbWqTRsFHh1r}m`CyTjc;W;PYf(|vb#s7Aqf{H z1VVJ-R(WL2fx{?t>ZdBj>8GG?Zi-!IwMUD1@ zm^R2J$VZ00{i%HH=c6rqeAyp{u=L6-S?*P7qIbu28(hggmx{RQZ3v)+c{J?n2W*p-< zMui=23qovksn_D0Iqwf74Tu>f$YRNyQt;*x_g-5|3VN-c(l82}5&|H1F^%lj5yk9`= z>Vra!aj_(FO*5rh((5)br(XB>5&syG_~u&gY3!IbpVF25t6(3GkA32Dbe1uA#&ycnRKf4mo9k*#D&Taxi& zD<}DIOx#Y((b`VYviQ{iaBmZK*q=r#LEWc#G+-k{B?~^TxkH!(!RViCnGRFz<_km6 zL%W|+ANoSjOu-%wCktrYH-7B)b86*!nCt20KvXDyOhtI~IIPfM8bw-y=kYbw<$8V$ z7`h0lY7SN=9_#Hyb5*#)@UcML_VUqTI*7(Xs=Km;^Q7*&577=4x322H#c>v%3nCx# z2%hR>)FqL$eu0k;BG0M1`c~VlCxtLQa*L4ScMJOIeYdbR?_RIM$m#5Xs09D)H;dx9 z$dp;P5q*Az z8QD*(i2cNV@lDCtG$kh-`Tuz%1;|Y9hjA4x)f98E=(o^o9lacs{sPDh67S!`efyph z|7gG5#OQYq_HtH;LSl&1syfa{NnzF6Yz1G?45(yEMH0%$$zl0EHu;JEVN!^V{nqaV z%*KBb92_jJuTQ3=q?83hUsq>{laZG<9gxEXdqF^7(ss_?zqXo!`I%=*P8nNFbt#eK z8ykxaKGFwy`KVSwOIup?dyA3A{gO%t^-bm9;X|)hz&Jjk85rz@wK&Dw2Gf)^_^4Qs zv_vs4YQMjeT1GVln5Xc8?+K{;rFJuIL%yo$T>F0PD)-D5wN(k>_K5WO!DWvsM2W%3 z#oRwo@uC&{6{#n3;o2%V2+m3eeNo4x-s@pls{Bs7;>h549q00K6DDEJ3F6Vmx~f

)qzJmx~#%ew(iH>nvkr*x*Xp69FquK+wREiGvJc8wcT0|HaTe@2SG z14p_bP~|@VYVvTsQRm96RyFJM;QDSj9aY-hJ)%#*as6B0!^Oxiqr~V9Zy}%%1pWN{ z%s$RsSNVvIVxVp5r6n|!Cg3KaDWoTG0#r4PmRQo7!(xAa8dGfg z&eSgMH~ht}NSLm?U^>#%3tA zdc8h>k7q1IjV0IC8gX7utZ^r9vO)RM#Mz~b;`dS`h)|bJ(!f$`9VQ&)Qzt*X@p-K4uleR%7$ZHnbV3;t|2NwP+AN0>_!wK0q!H>J3z$I=0{ttajuK&ZLo zJ?1(um&9cYW@4r8ce7qwk_9qfWz40Yww0)+I~{q?PNWn8AQC5MFe<}&(FMTt)X+%W z{U5>qk0rh1sj^*Adp-Hx9P6bJ>gA1?OJ@9o?C;|=sfKCwci1J(23fIK(QNsbbJ#aC zE^j*!uCyD^x9`UKq#}2JJ&V|2P|nudZS4;Acw~o0LQS$~N&kDi0F+8|kxeh;$rc2vx_W`-!P@lHx9$EQi}vVwi2xllIUV@g@2C(vb%{ zzY1V)s+deF(pCLSlp7GV@u$AQ56~Y8p^K=C;j|K@a3AcuQvCR#`e4%qYuA%^qS&62 zaV%yL1VwmF5UiBL_4rbUk1C;vu99yYZSb5(pU8DX<<;=5)Shm9lhQQQ?BNZYq(52% zPuoCH2EJ@aBU8=*E3y@rwxqUtT|eL7XY7CeSWqd@4T;@f%NYs@RU4rHA(bZOfPY7z zV-AU=nP`!yylD+O=<_WrFL-a_LC4Z%2E&cYK0k-Mzx$DRIs!3NyvCPVN8cWr(S=hC zy^pGJ-wEN^~F>^(m#d|S1Zj@ zIw_#c$g78fX<~CfWpsaXQ5;MYP)2FJ){_2^I*Uglz%9MfawJJ0RN{8x3M47=5ky>t zjdU{wD&dqD0AC)DWasFJ`F?XxwEgKP$_x3yjv^*_j|>#+Tt|2h_Yt2^O#cDJgZze( zVz>05PfDCufQX#MNSG)-4W)bNLCRvh3%ky_nS8f(-|y7efO8VAX7}#QiYZwLccUk& zyXvK=r?%z&+n#~${)0#UL;egnn8tLCs%N>ubfzKuMH68rtrkM-<%>7niz|;P!bM|* z!cQC#>+L6JnY=m}j}RzF`XcjrLh+T23yqK@s-Nsr$E84+NVA>vz>fE3lP#L~8Leh; zgu!TH)@ON`Ljs~~*eBS@M+eQk3&h|&sw^SFyE}*{O zZOtioe>J9oHa5`P7Iy~*vXTg}2B|V|Wo2)~BqWTC-$)P$v2bv}BO(?U>4=EPi1HnQ zP0Y-~q6Yfh-)h7@4*aowJB90f+@Zu;b^TLz#AA{Z(NqIhTf!nFDf_h53F2J<1|sGX!jm0uc(9*m>~MKJ0f+45Fngkeuzb;7@+w?5(ygw;10vO-vCG zQyf7;C9E=1NogA#gyOLm5=mewZ67_Q*3jY)aReeK-qzt!O30ZPzqvUN<|r8^1*~g2 zU>9-udm>xv04)gp>c8vcapV7^PA(bAc^>h1r08oMFkOE?XpI#*RjEdvAMiesOWPa1 z_Bo182C<{NI)j`?pY)85TEnxkUNx#%kn3_{V>h}UE`!8TlK7FAe^l{g=!E*^PM2RTrji956*A@elKh$ znW)Ubp;dvGi#oC*-#`2K{-mrTi+_5e|L-M;)@Mse|S%23Ms(;Msu6d9i2uppvO+=bK z(Z!5Di0S9Y9&@$Yz*}%UeAh@6QRA5TJY0-C0tIY(y=Mz@k5@H9XEJ?^hZ!slGbo~0 ziKM;Lo(k7vp^rYu@8RE(**VJj^|h1%`4f6?W#PR4!;%04+4Lu_@82cxfTC7;pz-s?Hqto+Q8TBi2sMGigqG_j3!v~cO8Kfw6FTN7+O;tqb*(i zJwNV9CW9`Ru8WJW9y^qNF9<#IB&Fgmgy0`?0z5!*WNZ^WXS0m=KJi9nw;u7hbdKmk z3N846Dh@NlclFtfqwI{4Z1yLdaraMHYPf6X=wDlqr)m9cSw%b(vV*`~^P}opuzkJ0 zC2T3Z_~<|<6fRQw*(<)#7~Td)WVGii5o|C7RLXqg*=9c>=B^EM7QEbhYaec_?kQ}e zvx-WjitWm}h~7BIv1<4&FnlGtJ5`W>*c>uky1L^9LTlwAW!$$`4WpBFd3|4#5pIjz zWY80Ad}DmRITeCKWs(ed_3EuTwS2(xDrzVva?Z6C!53IYcDpUNjYHnWsLn$dK;I1b z5wI}o#=hl(u8~6bV>Nmi@ZS&4=r}GWDtl2@E%jNxzXL_=9U>5M`-paLlVN^g)-RGW zsEDQ3a5wHhWZ&Jlfyv3Wu)>C}DeXae=`cQQUNyh1hWATAZ3nawW>Bt7=w-&5ACn{% zE|mDM9nZk>8ZNI|vO3f)E8c5dbL=NI?KGAdS4$B8>UFli=vcIMUNg-VI~?P>{rqIu zC1f5g_V3wK6TZ9k>wIxLH^R+O97rHYzVO+^T7+CwfSjoop-SI47 zg3^SFR@-lDjOASeik&{D1%uIi(cR6r@Yl{p zpHkD65HDz=v^@#2sVXr%JpIY7VvYR-8&lW-{PR@J@c4m84 z_2xSPV}^7a&z2u@tnMKl+HZ$bYu6YWMk{yj$YDn0X#3BqqRn33i@Y|+GrIXw>n_rS zR35Bm+!@%Zao@@ouiRmK+ISi-hojtaV@t+caX}&EFhm7)Nv*VmXl$*-MY@#SiEK2hGvAhPFQf5`iA*?!Ii+1=5?pBGKj85b;@X?~tg7KB>qM*bn^i}4D5;zzAc#JG-OO}zt}HBL1jdEb9j zy}_=)@{Rpn3?E^1;eOMhU~n>xs!?l4GHtsU)@+XT!zg>7(=LdT;`XJBf`S8v-5lNM z0WijnTdCr~M{FwVAhliGm)Uxa^XB+16%{=(?X}&von{j064{}L8Ovq3$Sw@KR3ABwKPj2 z$3t%W@>Vp^@-DnU0Uh{5Y&u8T@dcto<;RX(K$cMZCW^J^#%ZKTU8%6gH7w*_(C_wLar4(N}k1xAN7#Rl}^@R$5E1A!O8g%L$gm#mD)DpOgPH6(0eJ{(q4C5x@%6 z8B5{KJ^@q|0*d{s?az3_R6+22TRWn|ahtTOlOqd`r(!7YCY9qE)<9^fiWr?{YBgD< zF(j@S3vL-Abs^8@lLU1Hed9NCWxlXB;3ht>-(=tW1b8{4QOu17)?Re1+SR;T4IWG6 z8kC3E8%+ECut<^ny#ro;N^E}C**E1j5oXEN8q)}5CD<~uXWMgCl|5W{3=f|#tlhd?Lv%K3Nq(7~S`7{0W?#lZf4Z>+62@9?{ZxXcUe>M#TTkShyO!qJ z8Z(xlGlL6gmc+963>OzW-Ow6wLK=0EijB1v1KUntid<{IrFBp{i?${Wl%MT%oO`+z zVKFzTo3|AWtWs+TkHEWzF$Fwv!hh##zl_7ay~3rRT^@unHoFsYYNk_cg7d5ikZL=5GHC_FS!`@GrRCFNEc(|uC#dN=)k%atiLie&9^y{dD-zAp5!KUCtQ1uphb6MJ=E0%>7%@1)E6 za)Vp^oE@Tmg|R31mm6Jia7M=(s}KZKlkx}Z*cJSl=U(JzYq=67!3O-rODzeOlC{&!*@({^zd47^gD9gWPI1Be0Z( zU_P7T=cgdKZocd_jd%ODm!AP!%kyu?8FnG!Z&rl>mGh2aUHDGhk4ijEV7ztgJ-6FA|sq564!sO&bGIS?&%Z?l(nUQ zx&?QhWYeEIR{MVI9qh-Z;da9|VR-Sxwi_NbX6nWl*B){FRi zYB*FN?sllR8;3(V&sJm3Nk;A>p$iqK6ExkUemgI;TBp24z5bGRjW(&$HrS4AER+tv z;zz#7W|P$&(d-vu_G`XI}_7B~|&85BTPsOST?`Qh>BXVGUPq51FY)SL=o47nRZ>?;2 zhe{9wNjww?Y5eBnI%$7cd)K^Bq8VSMkF&yUwSf~)E8Y~C*L)gK7i|*YF+cbkmXC!u z=lU2B-V}IyZ+AL{`6JckGkr}erZ!@2zmjY5Y?mJHAb)O!`1Oh{t<(Jhh|@Q#M2qz0h%|}i?7xt+4fGk zVL|&)@ZB9{alZ`i#(36qkZh-#QDS9nt(dYhVMnL2u)8R0@C4C_@7dD+>enP9g z{fs1?$P*K``uGW)-t4eebV71{?m!j7dcqw!enWj z!&Ksn>oFpaQVbbWvz)r&fPDWS;{QqQsdO7AAcIE0MP2btv@-!2Ea>0Zt> zpok>#g#_J5y=^OUguUGtXKyVS@n~okkt_m$Ep+!eVJCTb!~;T}S(}63P=eJtV83Do zktAOfj>vp?aphrIE{GD&P0U>JyGmRbKnr84i9qjFmvd+eLhyP?8Bs)}jy`I}`eos?> zSyl0fs&G{F8F-^?*Kmksvi79mOW{`xN2PwcsHF|}S$?L&LR<-m88Y;&pwiwxRY~SP zPRN(mjqYX*9Lz6E-N&VIk~fbPuzF$G51qqf(*5}iIV4_Y;IL8)lO-&3pi=#RX8nB} zzg%F9O_u7Teuhg+3NxSE|6D=A+<30P2i7qvS`HCe%;S=pebD>ih%}Yg5pkxZdwnp8 zjos_^bcNUBk{IYj;E}L)_NIZr1Z!*TMvMABfuWY}n#(&AfQ2kM70o9me^yq2HWMSA z&h$5oirJm=RY_>y-JyZKi0hfRe#Nf^L!chD+C{=w`BrLZv{ae{zhK>AeU}=uNs=@{ z_^i8zol+#j?N`ZZ7$KmPs0ISUgU`3HnSIn~IJlxd)x*al_}3;EUm)>=Peh*3>f~Q$ z7V@`V&A?G=hZBZUXrB(34wUbZX3!92W~yWMGTPzew||N)ATGV%&dT_P@%Da-K^V*J zX1FI(B{*he=IUAKt?oDf=gXYs4ZM(UEUERUQa36(KlsgenuqXbGwsR-6`5}&OGTE~ z9|$oqY_|C@<%C{dJrQHe2v+7I6*mnSDN}T`Fehi4OVbu~+t;v&da4=RFNDt}tErLW zqI~z0mpjfi_Sb26=Tt%3cHm!dYxMLM#mW{|JU)T+PM}5L4K2>-)->AS+QHSl3{y!- z+vQ1~ao+-R+1f{Zqb<$c=VqAT(u)AU8CrTjz`0@1zWgIS@z{w!wFc*JnD;=k?xP$x zU03gJa=wRpv^F+@I?fjxmM>1kX5Nv?aAZxl#Aez}^TE;{4yTbtz4b|`<`WnB6Q(Aw z*SVEwo449wx3X3xdKXXYsoHAXY2qGjOAm&Rhd6=gIZNUx6#Cbw-Zj>EN{!*-Z!JO= z!|`c2xE~#gyN+8Kpl5A$yux1F-~sVvVto+ z1asi}7~vA$+xCml?{T1WIF(ffHSQ809AQ+xW`JKY%QfjDG1UV7LvFR=48QGI3C7GO ze;yA92^429eMLYc$orZGQwXx2cH0HFJyATyoX&=svYdov`~fP>2LHE z3f4y8Qas__iGXBq5$=a#IRD2bq4r$*>?sJ9=jXi@*qVC+1i>=0wXHk4S74_PAKHzh zr`$?AUSe1oBq%vU$=G1%!2W}h`Hr;v_+i}fFId|}Wd3Ul@!1T9cW@p^;9YhZbaAh8 zz*1*VH7vgbJ7))lvm% zBz@BJQD@YC+sS6JT>U_U^o#z(w;O}mdHb@LAf&J!I|rpgjICBeqC#S(R2`3Qjd0MBIA5mtbh_f1bsdsHFIj=; zY(>?jgLgux%4jJ&#=}B_hLSuE);;)qb(cxvxmXo-8}~&S`aqk)F+&}GsZBVxrLr8JePvQ5b>J7?|e8wEP*t|FT z;DR?V%)H&#m6{KR_}5h{Mfd>f?F@`9w9i0$FV3+X@+ac_?+#BN$I)WF^ZD1V#geF9 z-r5<$&f%dq*TuyKIwKgU3+IY_Fle?#U2G?MPVCbD@wk+&mI-hci_20GZhL0%*5)eg zww(z%d$;aF!a}HIBWLdv(v`_E$;=P56bCzV3z8DiSqB87SfdkmEQcB_#)j#v0E40rnis0Lp7RwvI8?exdyf@hgv-2 z|K5?|VsViHjPPdznxsYcuNS1o<-C zdJ;AbP&TQ8s{+m>kmYx^NKozF+TPPsznO*9KWQnn&j>pm>$R5-;2B&Cw36>uU{9`O z`Ch{NZZ^hby|~XAc7#zUj(5Ux)8HU`u!63U5@%{l`EI>>j8j^JK-&L>}T}3!*c+=pNowmht4Y22`UIjsWj-(*4KG!A-1eb5TK|ibZ zz0uBrZ80~LPPDio)|~OL(juP8oWpKfn8Bh*~a5=^F znWzx0B<)@}zUf)yX_hbzzs(kKh_TPD=2^b}wLHC3X@qXv+3_3yogJ4SSp3Y4G?DFB zEbfFH1?*uZ$I_VkrQCONA(G55)s@5cxUXPH=5RXS(psp#;`ma2dDD~?8`klVreHYh zK#9T-h};n6-A`4U@!Jz}R$9u0qyOerR#_u?wA(qJ#w-Z=LZg;8Y=`n-aGdf^95>!6 zhoA0OfuC>Fu`#Z}05xR9sq=K~Y18rFFC~f*c$Z^O&8ggeB=KgbUx^>>UCC*jc z@p22Ey!+FS`9pIVTDRtFaGpWS?loZ&iXtDeEX zv^ESnBx*I@$^2+imazD3cj_b{vy;EQ#q8biOAT_~F{s?EN>*}l1n!02)Zip2T{#Mu zwoZ$%9Kt>REhm+h;#8q&H$~es^!cKvHgED<1H(0&+8}-b&TSo$GVf2cA)3{T0@9C# z9c3G|q@(*G5RTk7Nm5-q;)mU(7h6Hf2(RzXe{s6-NoTPE|9dbtTse!NiZapU`&*{O zUB6r`#m*T`6sgSA!Qn%5(n4erAWxVjv@IKdP$ zR*`u(uYT&;UZ}ejc|c;wZ~KZ7!liHDp4T{6J@}1#+1^-6l|euDEm$}{J(fX)jyX-D zH480RD%9l@=S6$$yJ>bhPO15H?iPLqxO#*4ig=hsq@GV@vD9=16Q^VSsPFZqLlR$< z^++mejyt@6zcxE3ZyD2y-#u!T}r$>fY%LQ>JBkx?wV zqnW1Wm;0yuI%!(%S2;Dii#3cik;#7Pf}UA%Dnyr_rsR6ydZPK-OEI7Xzcx`$b|_Es zhi`8c=Lub|^}#NpoS?vBV@hD|baB@sU%Eor`_3b|-&rHwy0W-?0U?|*y%TO7&zRl{ zD%bsM7C)DMcP+6MP(qJv=sJCF=$rWo1`j!{cdAIdXo~%d6U~Ygh{;6g)Cj>)N+)z6bvjMzOu;!s6VcsghFE9idCQ}3~qxLBc+ z8e-qC<{6vHFX`hhoPyo(7!gw^)lG863H~l|{r$|1$=$tG69_MA=`WJtn;fl8we*ba zC_eO&B7SG_0%kK8C+w1C%pt4J@|o96IvX(3?78?k=(vzWWa&U8LxCORf$6(h%o4wj zOtNj}(*iBI-i-v~h2+4*(Sg7xhlC5KtW!4&KZNmOV-2AGwY*!cN8&2V1zL42M5CKDx<)CDvKfFX)UDjf&hjT+>ZXco5RN61$ z)upPmCt|q+yOK1(ULFvCq)P*ds$Hmj>W67cIPMv*_C54c?=arqQMJ}>UC=37s3HdN zL%Y(&T3iwS>x@ue3q@T+rY%)jT)&pI2tFcKN>xLclcbb#ug|KTk<|bO)$z|UpA`X+ z@CrSAi<@Wd;E(fh_gn8*8TXI#cNj!=zmukZWaME9SlP5_yQD23V|2X)nH&W{j&jZ= z8Q6++!wk4%ufBg~t}K?AVR&ul2^br?Ak(zrRD>#tLd3Ouegbd2_Jcrw=>ptifQt?pxb>?td~cK2LY#1>k2&rOZHeA-*O} zq-C@w7F9U53oksmAUUYh@h1nk7Q&yuC`BB7XWJNAHL8LVE@4Nl*4{Z%U!Rwh~ufOl;|=h`bfb= zLy>Q(b~b098_G{@Sco0p#iT!brGK(rsKI;!6tdw$f8>=i zjt@MokdYkih|w7I_ja+oAmP89ARwd<@0gNQX*ZVlEh&STa}!eFf^@24r|$LljUUUzu~>jMzp!nTa>CS{+;u{%>U`J1@S$UuR|RYOWz z7rKhpl%cksQZIwfc<?k_3P(~i_L_+#Fp}8tu8a5HFO%6fqpp4hkwwD|Go8>&S~9ElkMq-=n0~)2Acws zN5U+C-{MYP)XKyg$efq;o-BSnoZo4i2wNQVMBOkAow3MbyQ_Db)iXaiV%OHm2Jg>^cDheii#>Zi;!0Q zpicJqJGO4T7B9GVO!!I@DoTc=`$oLKvmN5!0h#W(j(2R6&usl%-#@i7JqpEQY)7D`qbcZ&~*#U>rUl&K`L!J zM{0S#w;oL8Q;FqZXU7!11G#7LWX+TtOXK6?ujXYy#JoWEH8HWlz;Ka#Y$e_Ntv}tH zzTyS`p`RPx=qq8Cgnsya!75Soc5y0XM zj(YsCpVFc)DcoemsAoh7{mlRxJxpN;dx8jY6Guui*wbjn$6*9@TB}p#&#JSyGoBc` zBcE#GolVd>eWg_&t*D2N^3MCz;<9%{RCaHHzdli|7WCAo*o+gvOs3$$5A#r8C2w#F@JH$>GrWd&ZDsWk#=a1&hebBChJKKXsU~V1vG%si zC$!OU*6zLC zz2hzI1(^i(vdD9%SB%2%511S7;r9Rq3n-}t>|WqrMFR>CM)i^qavvcfz~JWf*~J-1 zQH2Er()n=HOXhvuSDVmBa zF&?ipnCRYMyqCd2(erEGSo)D49}j$|5i-2N*)n3GE5O4Aq6{~rj(DriY4)KvNZScg z{Z;!|5uq#9QO;3mnEKz(5P14eu~?ZGDszmFes%5Q3kKJw=)cPIU}eAZ&(;{qnE}0% zBaAEW*(qRS%Pxq6s9^wWsqYw3uaFLD11u^X0!9Yi#;S!B^D%IA#%l>=t{mC}ScBRn z+pn+e<$eLI0Az8{OPPN)ZSLTu?^5eMJ^4TC|NGx#&b+waEA;0DX-jVe-xuaOecKiL zOOhi&R1I*9e#Adyps`@78~qlMrc?gwI?aW9l+EcY<{6;R&nkQ9+?&N<$@`65GJB^K zRKy|2ZnDNPizM|Iji{e!g&3f%b(M5p+Wi&9nIhWVi2Kt9D-O_PM^F;X{z3N z7Cp@W%_gGxlX&&2+F1M_!9G3K3gG4(V=2>kKMh-~d}dibtU@}u(V=Z1NW(S$YAnpV zNAx=Orkwo>;w_AicXmNN`vQy~oafK*rBrnw~rk(KYDp68y!m6+SW z)tnC?IR$*(QJB4%U^iF9R{oBK!McN~Y*`3UYmR%z5wT|#5ys@>2*ZC2In$NBl!uF| zp?$r-vHIW{@xbrC_n@&qvP?Bw@sF>I04Du7@U$hud?S!meZYC?QplL+QXl-)m}Bkb z^^5tUb&u7DgC782I-1SgGc{FP(A~jDKiJ|H{RKg|AN<1K7^6{<&q`Ci%_n*(Vw(x_I#bmSJ4+W%^nf9OXc%E7%CwQLyQ#ZBq3-pl-FwGrLq%oV0L(8S*`mZKpoWWvu~Me;LC4`*HZI+8);d^Kfx~;kYeTCexd{+#{Uy62dv6 z2pnw7^p{l#?zp|KRL>FHPsvnYpf4rU;Ql(vjq+4+Ru=P8G2NDH5fn+bzoR_xlmm{@ zKIVb!2`A1ElioWKYO*8TUs%63Tl&rc#D;T1FRiNXCppNekHRtHi`~GJUSczZK`Za} zPcB+hUVCeq-XG6&lU@?I0?7Uqg8t8Tz#otLyo%j=oD}Xo$K>dQbjQlW+QtTqprD|M zxp_7)gb)y+iu{}Ehz=WROi@-=6d(p#O&1};z`z{NRZ4$wzCP3hMy}{>nwu_3E1+d8 zqkzFpHmGlDa@!{-HBfkLEc^okJ^^~B(JV5gXltKRyBHTRBT@ zcU*$8?8WfiaOy3<v8Stu7 z@7|s0;Ozl8IsX#_rU)qp2Khb6`(T=Rb89Q~44B!7fQ}BZMQ6HrmuFt5t~AniKhaPx z8E;G$WzhKD9~~7-@Pj~VKRGy@C6eS4>_XmwUS`WLj1m*VqoVM(+zEtiKYTE1=WJpk z8<}V_YMc61E0J#Y>_wWCl$6E6&5e5?{y97TVPGxLw!U@x?T4c&s9dLW$fN>OtCNO; zYP4_ob9m;kCBkWn?^U@I&Bj$b+y`spFCiH(=ofASNgrnBh}a5T;y*1vjHxZh;!M8rHh8^lGd1P(EW>nHz*;n1X^VW*u?b}}=XDOM zX@1B#s`egIWE3WH#Je$AN_ZaCqN-~VBG~Z2DdAbsAM52=`##ie)TJ*~j5t==e^iM zy`C7iRhj0duzSb=ynV;-N}+czzkNk*y(deuMY;-jd8^9B6!=r@m$Zs9ki7#*FRk}N zaUZ}9@yhMf{>&REugh768s;ge*tG}!S!aNXvPRxxQ}D+fP#cUYskRwvjN8TsP_nD# ztE(sYK9!wtP)qatMU~S#Q%jg~Pz$pc(OuJ>*R88CGjO`kHxo6)8tp!4B@>J4N22LR z1rf$uY!;L79wWI4q;rdOZhPl2wd0h4!~}(~pS5tHNOJ-Xyo6DTGJ-gIqgG`M=-wD2 z?aY|3HZkeofJlWauwiwB$2vx;L3|Z;r6Mlq5?ZR+aIjQw(dS?@jhRJ zb~&wqNh)Emf_0h5AiS!w2(+SCUDZ6%d%xDqlPp3)$;`;v{i?=R%4q&_`aIynj-|W3 z#@JPq*#ysJQcq2<8aBOk^KFffK$@*O2~HL;JRX{brh+zt!=t4Zr81mYU)Fo&w?pJy zP;GE@n}e?JlNQqhB*>EF%jm}W{T89@0{fUI%RiIw|B5{4ha0}9O&dn6)N9L2OpB-q zesf@QFNn}rXGLoMDELM5w_711kA5uTfs+DBMvqe~#$BN2&>;~)c&r$Oh!2uR63M&H zUcmX@Uj&)tZG`~>JsZuUjSI{HlZ!1dtYr<#2H@0L9&aQ8Hh2+_FV!qDOGB~R3-=O= zq=}ZRPt#-@x$H`%yx6?0xVyKgk*tIyA3^l?=4R=iRX9e(0Czek=Zul>KOj#D5-$Kh zJL@H+p|oS6rX=;%@zOIa#rTz)?c`XE#f=Bn?7GnP>j1eV=3pZeR%8=usDG(5%O71~ z*qubgO?2mjbj{~vYSr0iHA8P#S1_=tas!&xeX2Zv1KRfB)8FtbYZfvHV#8@&Wc5R% zokO^4J>YXE8}@$tH}gs6ELKJ{-0Y!ZkY7PhHOE>OIh6B77>e`G)3 z3ckg?aXzM^;*Z_hYj3s}m|aBfX)@LB_K@tl2%OEHux1jbg>EICka(ySyJ?p<&{U5U z7B;*9QQDqlVoP71mHDTs2zHTa`SGog;SJnx1VGz)C%5Y%mJ4O2fBk=_&Ma8z{yLCM zPJFPU9iZDje=zfvL{W0h6(Buf#U{`;gT9-mgolUUG7+4lQv=gN>wI2X{-aW??;(GgrU8 zz5S6HiKTp;OT|wK2S^k{5W*$QoT4mZGJL$r1+H51tJ*Gj)3-bK5a+UtUMXI%urtUL zX2di0T!5Y>p@*t&IMPe%>~fSt4-aklR9ygALO%z?RV9vhbxCUL-Q54T-V;fl=&6Pz zxo!U$uxX8g*`Mub&WW|(T*6S35&!%#KUOKrCV+H42!XHLlng;KHJLfDhQ3P;|4PIf z9wwg(y8K<)E^OS>41YlEz3CU}x&KY^S;cf+`lsSkMM>maJmpdd1M@XBWK!?+_s7M} zGssQp#-v&?=G=qhcj?&_t<2Ea&VER+Vk^3tr@Wj5-SKI@r&?60nOm+x|OK;e#(cKe9r+ep)MCdAs?-PN@UIAj~$0z+m2jMi45 zk~dnY%E;adXuiWh%h8dMIHmx&qU^c&?BGz=_plKyERm6CJzYfKV?Ew9lDBg(U}_RO zf5|})3w!hZTMn&gV$e;k37sDx4RSq%Rr>≶tnSfe7Z!S!a>6&_pzOZa5=fz>SF|!+$c)6X(LKmC)V7|j z*9-&gDAX7wmTGTYb5llR1AH{)ipADhNm_J{YNFP#V>qXEOsUaQ3UsxPi~2J$eYvG8 z^Km>Q(Nf%268cy0M*bKvuQm8QD$AEGjErBoe4z8&+$;3gN@GA*4F*g+1pTOjUEIvG zHDeA%ijwcR&58y5Mqjtp$m@U5YJroJ5|FEOUym5QYM#>I@O7q{=d^ z2MUzN3MDq062+sq#&D#UN$DHZ`EYKNp-M&TxjNC%w<2nQS6`uF@2OQR`UKyk+8U8u zmn44K7s&o>yD_3MD^DtqKtJ&dS*XMD+D4!%S0H%+%-WE51};5h$6Kgj^0nvS%SNE~ z+P3Yi8S(yg_WT||iI&%&p1GN?Zj50wREK6gpKDwa*9w*nvHy!K#UPe;A@X^#xlwbp zG>5h!)stZ|p91#8EN_eQL{uo^fPiw#m1eRYY~wyd{fJZP~9WcgqRFg7&r;28=`ZHKCeGgidowWHe3W;XLhzZL>t z6})-#J+iKC==So7-u+@i7h#A^q*G{vt#BXpRy}o0@|2+PV=<{eZlpeR*;mX@C-T3i8pf)(hrI-IXW9p!BVDJ23X&Mnp$Y9TJ zm_%}#LuUC|km{^3RfW1)yFKY8XqqF~b0V4*H{7Gb$@G zb;OV?GTQY{gNr`A}qGU9R;NJdZStVka%q;bTKlWGTMiMFVoZ7nf<55zMp#6 z$Ghh0^j1cuwr`|PJrjeoP$xyVuUbhM?$aw3de7)*E+GAvlo#}tdQ+lvo#>2t9_=42 zQT8lw%+al#VF$J3+nQj7BwJeUKJAv1ocw=uy>(DqVcYIofkJ@-#hp@$TPf~sDN-m< z+`SOo-BKv7ZLt=YBE{Va(&FwOoB#m=1QH;Gob=uM{buiT=42*+WwK_nvex}P>%On+ zcb!5l(bOJ~{HK<9K{`9K5|}Htix8?4R$YtRe)jmgT{_umuuDMhGu_i!v?w1OY2BBj zt0Lvend)_`H1#dvWDd+t3IN*pcB8F$2CB z%4dHHAwpARl%Jp-=!Z><1p1n{h#h^F4Zhj1;n47Mn4`4!eRZaFtZ27T#rVBo`t(j% zE}l_}3beM~y;egJzc0e{urn&(6>^_u4# zi&xN+lSMf_G;RTbar6%D!kNA*>CEktt`6NJ%J8!`sa1rlnbXI`hU~HmbJE#6kqDnL z#Z517h`kbv@WBuA**C*csCAAaI|AwHnDR6v<1uII>Akd(xs;oV{_25KC~Ib?rKC=w z@6@?PZ2FpE#RuXtGuh}D)CE_*a2$G-T(wPsi{c}x4dj~_TW{h!Qn=P=0Pa-jEXUQS=@b1Posn52NhOJZ9L z63iD@J|Ez&%;UAY4lZfTzPkVyQkIq+5TC&v$W4so(B|284WIFT;iU`IOka5mpTh@! z$t(~wV=tBuMzvH4IrGlJ&qMo6r`+eBU%1#mwjK*U`$-yO%`(m0t-H{B8bwo<5i47s zL*&^}?;!c8;nRq~z?pv;m^BsjLu`m%G`jbs^@xdyA42^!k`FcpK)$9NUG7Sl;E*Le zMvkNw#d01czUf9*r(2K~?rQ87JxUO4QnY{E9V^_nbmFzV((7l;{wfkdnppEB?Jy-wiOz1W;guUBtZ)DU2E&*!Fy}ZMSa&C@dVeU^JCS|F2&TF)=ZfKk)V} zY9H=}B?0yM$*y5jG5f@GCKl4Mq*T&it)>jDOE(4Y@e~`un;z9oW-imexED`8u1wy$ z!JU(z{iwgGLvRC?teYYoAAb}bw>S}L!y)eu2R+RY7Q{U<5x~ExZhLl1L-V9DlrJEp zgD$Q(sjsEhTJTt|{H(H?EauFk_FS@yxP82&r@M-SsuDw1&!GyZ7h58UORMhBK>qR} zTKoTT>)&E5)r_t81A~|d1wF%si8&T@ zOL5zA7|W7d9WkO!)AD<4HVyAr`gU^o7`5dff|6!!gi_SIaTxluyVyn`KIfI%xZnND zANVAJ^AkjUpljBeQu=n^p|$xrt#2iBFhV)<3AC9j^B-M_>SdWofNsRae!|Jt)jO+& z+lYPh(<&jtWN(IC4;h$#HSZ6lX7hg%4z(D|-1yK;tq4xc92*Y8G2HUc5hK1f*T$kR z0lWC%lJ49nwW_Go-&K%gre&4SP2_FJxg>k#Vt5Hkzkrdh#`iJWqXSBt1Rn@ASCe0` zN(Ejd@J$sg2zQ7oj{7a2A=yx(`;x)9;A;n$)T-^P)=GktZ&1vKbWc_N6TqDI0P%^; zN;En($bk|RPW4D2?bJ0a<_D-~^!%A;AGd4g}=N7p=b0L;g2b6QrIWkQ3_PP&x z{7FCNCm#Fgd79_{*u=HWsI3K9?s6`uIhmx*g>XNG!Onx@Mi7bz-!u&VBSM$n>zOTtt zfv|E{$h+K>1S}YTmo(z*KAbDbh63bn#)9Qp~96vm_9lxuNUJ4EAl~d(6qkSHo zOY)BOVj*lYq@Ovz)&V=fekSRqVL1sDiC(#TD!arK-@?n5g;ipeXlS%#a@2#zyzq#yF%y2EZbn*EP*||!SKfQZq^I23Mr}S}T1{z} z`u`$AR1Aao=AH&MBJc~Y>z4iEyd7MVqtPRXjYN}zk3&$(+SKEbgwSY^d5b`M+fNpu zSEQM;*Z6X2JhAblZvOwmj*I3!C^tlx6tbl^Xh}tCNZz zlX6nB#~5XG!pdhv#b>@)`PZoRohFlCb2A}Dv{HB3_pq8Lc^jc;2m0=Q3ks(Tw>p@6 z@6H!_Q&pBR8m!v_lZ8=i4y=q%yZCsBst)BIle+>CNvtD=-^{W2-U&|1Q(mr-2X}dyy$608`FrAT%^E*cPA;Z%noQ=bsBT8b4bBr!|RbIt#1IMq+=SnW!)?w za(mo*{oMVkVnd>q;C_1Y*HjM5;G18peldHCHJ917M5uALP|SO9!zE3J=#ni?+i~{8xywe~6sJ?~QtHzXK|q`t_f~2+U zPtW8|XuQEPmlQ81vZVxW{yma#<*u4&vL4ggBh7-tX&gilCFzE=OseY+nEF{50oFOiyOgyBL4<@dWJ89mp7pBx`Q>7&tA zc|jahe}6q^+9eeHSQXI`f$-ja;R|~}l}@(kyxPVn`vaUkwqQb_*Z)uy=Jkm#V}lt( zLTK!n{fcn_PwLrL`W9cu@W{KfU7D@AArQ@6Asd5VIl=_|@Ymn00dQ*jnYHp+8r<;O zSIHuX8qlHBTqEszfS7XTToqVjXH15xAP%>1f2?S>_dX$MF^-l{+Wi!xVw@1d5fU%$Lg!%dhn@oTiix4q~SVdphy2r1Ek6^fpk_6)`jEV8D z2ayfgyHf1awc&|%H-3<)3Bf$gsbDjYYb_%4#Lhy~JWvgt{N72rP+a|=6mRI{1V3Sq zc~W0kp`qK)7BbaGl5d0UANGf|7~|YJF7krH-!po;pFfmaJrSdpk(BHSW5#rNt;)8O zx9{=uli6{liha{&AmMk6_`>G$g~thO8hdA&MPN)03H7+m*t@@wp{E(>G$7?EZCRGB z|D9{#C9ozri}U>pgg11&D&$EMQ}Pnx(vDCHZlvXS>))!JD3S0v7502<3|W-lsf6`&;rp56M;US-;E0&!#uyGh?HH55U2NJgam+hLCT4 za@7(PPBD7h^sNu@N+iZ(E8-Sk`Vjk2GuW{OQB@4YBWyp`?v7cGB05m*X}=!nn$zmKF!5<=!~5b(vjyieom?$$@MUMjx-GywqwSZy1&@z6KN*&6WIy&l zBAVg3Au8XmFYBEMRORRpa(&h&)*M;e!Bm!F$6$aq4+=CvT~`+UMT$F90+V<@R$Y(4 z0@fDWnbu_$88Wrz0~hrJ1&e>uQFqaYN!)qZ{=Bgqn$X@Tj_jzq+a=i|7t+B6+BXHN&5MUO2N@%movAGxm0j{+tI(>E#8 zW}t#;VFC6){{CjqE`WT_ev7|Uz+(O7rfnm*pDq= zY|H9i4LCOu$RF>~DEYc=BP7=(@%n@R4CQK2WCEWEpjtdd=Er-JlcY@1D=-uCZ(;slP z7r!tn^Oy8`QCrCUS3o=}_@JwH6E|{evHhvEQG1*EhX!RdyhWyV2-+<{6n6~b(tN48|jY)M3=|2xm z?5_NCwU=BFijMd&=`n6Z1k<89#g!o!-WPvrz1PVC&{5QHsa{HWk2WQISR-K?ssQX) znaFH&o*HnCr#RBhF0SbQB_=(kOs?F2Fc+p!SVdE3hfAls84|(dD0l#mISOIJit^6y z0s(NJ#X-YVq5E;SL7P}t<3DuE(T0c*)7}$aCk>$^6iF?s2`<*CxR-2+%je7;cxCw^ zQ0O&fBxC)^lojA{%Aa)WA)VY_EbAse9BU6FqGu_|jV8#_Z=(t9wK`?Luy^c5yyvVs z`UaQSj@j?@$BnczCyWmdHHUpsNL)4#eff?Ygy8=^b2AZQO2Y!OR` z3oD|mhub@2)AVaRi;ih7m{?1AM#)c{kN-{{%fnSkjv%6pe{Gl=Y}X&1B&}+2^cIS^ z_KH(cHz{LJoI{W8luL)u8)Eg{#U@#7>D!R4h)*{IpxiAizgFAkCSiiAvRH7#$L08a zJtDFdzcilvHJ6kv0Qxwc+O6RQW)b)OKX`WtiR8XwT!DB4;B(mIrz0XBmqJkR& z2l@L}tlUsNYM8}-aJ!b^y8WOc(~2MRKJ`%|b9#FZ@$(7)8a*Z$BK~i=)#$b!UZLI~ zEFk09nqWS#uIk>r<*D7MkAeD&uo1?^iGMEo+xJd*={YuyQ6{qgkzuYrY57t1IRQ!J zbmu_i)wDTLHO3@2xKKO~)oq<1AE~l?xx}1(y-NYaO>caN$^?c^8B^!`j`ZevRf(=d zbwZB&_qj}W8Qx>7oRfK_QQTQ)L)E`3x2hB$+MZQaqv#~J1P?XHGSM=!kfV;{Q5uhX zbsJ)8Jj^@0?OmgWXLSWAFRFOE+u^I{#(YQ>w?ePJEy~>B9_HC|X9eSgrptPmi#8$u zeyzTp+I}BWx$O>0azB#s7}Zx;AG%0bf&4Y?#0^fC(E zX2)7&?)pqYNAadLpPsY}i1D%1bkRgjxmwlx<=CygpxARe!B90-A3Qj4LF1fWf^Xl{ zt`|G$9xfN4!%1rVYvZoAA{941KRR|^!%)R*g1%6%4&B?}`0QXrb^UtF!^RU-L6E>G zdbND8gIPd+F^QHN7vY)a{L*927%QOFU%>5DqLKyhcm@q4QME0xGUZlcc&xFPsfkRd zX?0%oQ&*Q zhn)DK4tg;Pne5MlpUrFJc#Zi#()~}~nabC?23>pbPK4e9!=C?R@p^l<{>$8mJL~36 zBG*^yo8e%Eu>9wOfDK+RXn%X7xTnVW{16p$yd$2c%rmx6BvkR}j~OQk6E$Zh-nWCg ztnfYDBcr<_1Ar{7hxw!j7XmqIv;XXtFxC-U5oHz&?)^g&Kh`tPgSFUQs4X7XWFeOI2PpxoZ!=A^84-IK8$DV zP9RUi7Q`!>ldR~yOEpOT_uap zi~y@S)z8zqh2RJX`cYdV6qjCs--X#c0-Krl z?_=()_#qpPP>!1pC|7#ruL}blOx**R22&VzB#<}p19#CQhS`G6M6!!L^=Vzr_O=MV zZ6U>2G1VK1B3f{d0uElpaYo{|b1zmv zMfVBe*oidbQC5AI7R&BrlFgI~q1ZW}1(0L*krW~-ZIj3SXenSceS!zUa3t9Jaxu$s^MHHU ze5uON)u*bX6Z=@%_gvMH*})uu`s*CiY{Xkc*cL_=DPzfERh;Yw|5Yqv4|Z^yde(Oh z?fN=U*_#XTQ)TsWW7e)XSI2C1>gf68p(KSzbJ92t|mz(fgNajN1eR>H5Xvr^*5BJ^#kp2h+Znh-yF}ibA@sINU$hYBGkrJ6-I_0sQTMa zdKXei0=auAsFG3{AKRg%7k{?@4a>mogcgNcE=))4Poz%)S<;S)CjpAD7mVl#~)PSD|D$tUv30oV&OlE?YZBz)Ki*A2>HW@%CrN zFK_2M2wI>1SDtrv7MQam>S#6m%(dlhZYNJgjxh0%$5YLoeN#kLH(~(&L;gGvClk52 zbR`ikr{tLbRBD|N^iFd#5F*^*G7h`WU#$EohNY%UxwBxA(Q}SLNnajbi-V8DTO!W% zwiViHl8uf5%SJt6$ZgiA#jWdt&qVV$q|w})~5$&+)%RGGf_Ldc-qd+2_rTd%D3bhSzMomeFv z-V}N4q%30iQdZ9}lKrLbFV-!w>s6~2|Cir8lX}RQ15)Usg5@qt-x%wOF0#T_r4dtqP=!{QK7@!8nvgQG zC~giC=sKfKW8CUeTkTuZb@9dhDr?12ZC-jP_mF z3+$XnAUX|3IVQ6^ypwv3HkbmW%9_>v{?Z-=`nw_HuC)wi-~!%#?t%9Hf>c!AD%27% z#3J>&8w zLK=ph$$fowd$oyA#B8R5++@Xk`PXrg?z}kc{yk!G;VG0Xq+)w4a*wexG@eJvEeum) zY{>o6^*n4O{%;a2I7Y(QbyJUBwcn&Wi!r?j6Yb-`n)xQF7;aiRpZnMbU%z zL5twzoK}DCuyG%&K&`mcAcc+=Wj*N)b<{fj`Q}YfwydJJ7ukJJ>iOUVn>()ak`v~Q z`CW$Egb6%jFW2!x+2^&6%S=a-nXEP(eU=L)^ltG3w2M-O%_-%(_fK+e1Qg@Jk<5L< zByN_wY`>?!&Q zT{N(|F!68cj$Hpfqy5o=GTfHD#$%1h@5k@28RHXLYz&>!&*(~U>3y+kgCm10fPc&I92ZYAP&HM=0TmGYdUW(Ftk(U2`%|p-#QgSb&{3vyKKFQcVtGiaDtjYHB(0H>T&C`6FDak2faQ%OFvM9M3Jyy@@zRE)wCr|{ z39MhR_^nt;l$7phkDSi!KgE|CfsxlL8~Z1sM`-51Ka}TbBH`hIA5v8?^~}qU<{rak zSZg#!SBRhN5?D~P+vDoqJzo=H{#{zgx_?m{Km_~HZ@ru+AxAQCY&9`D68#nS=BMD} zLEbZkqJoJs4`~>^e_?&HtnsOhQ&v+_r}ldo*-yddMbYZN_wS@Ng~L%6-x3;=2_CYx zqo3=h$6qP%B>C#%6IDjvKc=s9*6119m9sd`C*qov5qgL>kN#}R;v^Nn6hI9mmR$KP z_q|?ACHOg%Dw`YkD;+dM``qkQi1-xXedaQU)B5glU099PIl~eDL|E@Qp67x9R;1#e zHLov`7*hJLatGT^2Vct?$@U-p6!q#^?Mr#3tDD@NpCSsr* z06!kvu{J*o1n|DPek0f*KLU1MLg!jTkLBo5im0tvW&NB+S}s0&-1OBrRnyZ zPM)39%>kHuXOeyCcQ+4v^V^GrAeY)>BD3e6NpnrEtTOP##O`L?iLgHWz59!j++j|0 zW%#BdK6W*JxMrTi3a4V*!*{*vA|7=+6FYd((q*l{`t{BQe(R-^mp;|op*tP-@t3;O z+^iOChhv`nXi~p<(qGc)y^m8I14w0IFbg3A#7f;X>~Xw(Ks<^O2$5!6Pfylzv*4~XHPP;p(W~l{o

ckf(6K zF48Ia2A^Te9{DohBuH3t@*TgGZ;aC)wG&+WGOSr!Eb4;g?!{cO#CC9{= zoia~R?mF>5h}3e4+&ud$`@{P4dgfvi1RmBc3LZN)kk0tU!tn0Y=K1pwa@yUJ!lGN3 zH7cudP5)c%zQ+jBiW0Zp(scr4)GXg?X7G1`6@Y*Y*+%x4AIa&v1SE7Ezvd&$>Aw03 zFa(NHX2T;=0H-8OWkjo;K@ZkJ&7?E2&Pnf-c+xv&8uAP+eSW-}p-zm%5)lJlD1x|} zx4?_kaH^}FStvoo&H{u$7NEshP z-5Armif`r&2>U(_nsuI0p5hJI7?-UGD_5fko zo81>?JO_l7l+SSY=B-v(AJJ6meMwiYT&8ySq#ZwZZn$`-q{dU-A9wnSb_Tvr$5+eSnc@9d2{n`uQ_l!J`2_(XltkUH@x5} z8U^S|Nk-T;jJ|XlD^`!!~~QyyJJ!5l;xrBqF$6gH>VzXBM@p3kY#jA!3?VIk(k75_EON+*?bBgjFxisved*#&dmIln;Ekh%>v>)$)K^%rp>w%04DTza@fxB z{i2sSb&pvk=dETYx_h>uh#y5erw&OsZij*t^4AOdH1OgR1M&FgdlMlszbNj4OY4QI zcl!E$e_juEo?fM-O^d6#_e$GdTJUzM-rfzi|9yBAo05a{9xaM}tiGp+jgXFReFm&m zUzvOPcMzGf#d7Fd{Yd7#Ir5>{F2@>qQ2Jm;K=B}KZ*=61WKJQb_w3&k>&{G}Z1I0$ zX$9CF8`&hqo5)Rb^*VP<&I|JXn@StOP5)S*cq_gBR?a%XVntd1Q#RB86<5r#bpAst z)e#(?(mVa}7UH41TlQ-nw_KmGqp_a^cHz;Z>ODdW&exKo<2*I_{fUjJK)%)jZAK{Q z(Jy=S~PJNeun zcd7nP=;FI-`q-OSgjhc!R@{pn=BVyOMM&2bNKaXf8O6hP2{PN}YSfmQJWrF>u2KzN z&EfISt8jAH@pksM*Yu7OBiQC~O7Ho|@-YeFc+Q_FxxJH~W%qG|3f?DdKI$8e;rGbr z_*Dlt?w|jP+(vE{QlM8NMEpjjZ=k_0+a5~_3eH7?6c!x49k@f*~voVm-ef- zeIi7;)4KdRn)%99wRS#s8+>>xXxZ%H^oJ zLLcuAzgzmU-Ry(=v%3L93x4qv+z6>HLv5_i&)e-|nu$c*V-s{_O*MAZ zx=1{97gy`;{W9-W9s`KAWmC56VsoYv|LwtG0f`t`2(^?x4;Qg(AkfmqsqJi}bD;0H6_|Av%@ zY5v|ljqk8xaryr;eRf8+hkyU|C)auuwUB*E1}*1C6$;Dq$-cp6h2^Krzw~*7EbcR2 z5YU+@-UsYwc5UJUe!EY;P3V|v<-%y7h)fn6$hL2&A2svc)%%T{N(}D2c@QgE!)2GF zJslKF$gr~sFc;SHi;I*pM=Cdy5~?c~4Rx`Radm9!k$Y0e%rrI#l2^LDwT}!l zXg;O9^3b4YFQ#}|zrjNH8(%`FVJ&2>I6s1%q@yjW;d~C4lURXc|Jm$z4}}q=S--1s4xYVpud6>sae@ z8ck*d=Zj+ul3`TXa6K&IGmtjq+3+-Ui>b8d#v%+l?tDJJz_F6Ikha(heOw>RO_8Tv z$7^!yEJ8I(lf+W}q$g{PdWrTQe*7^Fd%9mo*+Iv&9%*z=BIkiLv>>~T9(b7Yyivj(pdYSH8Z9VGOfC$Ov-lQY$MChDTRGmm4xP9M8DoC zOK2o1uUakK|N8l%>tO)qTiX!y-R4_Ot+;*_I9cu>o1-% z^Np7orLr!ygz6r1Rop0fT6t=Sp~ZG1WV)VYPX-Q~w7$m87UygHUhUS$1Ea1i{g{#2 zu2ByN;A=PNou@q6mhM{!V=|FR;CU`UHnb&!k#0H+ zP_O2}`H@m_O&BThCM4 z7Pr#}6O}F6Q_u61raGk3l4@+>^HK8EW(Lh@wFZGZnPBxQA`5UGp`tqlS}(})G%gs)C4sg7oy~&|Nc~N%8uj{yo(B@S?=oy_n07*u=wSo8h`E? zD)0Z$65}0;-~LB`l{oQXQI=9x{99=OtIg2ILctaTg{`SRH2@AClEA0a)^3`yh-odt zNaE^0KXSL@L)s1ZZ~l0-)Ca?#oeT4?rkwNa0izSQ?_-t19Tt4p%_;nm2^F68um#5~ zl}*D3Z~_<4d~d6&z%0Kwd)3R6-gz4XWA`L~Qfh9{+dMS_G8{VZl_%*wRaRF|5$w}4 zD&8bR3soDkB%kVl56469PMyad?s@SnbR?p2Dp*1*RMhJF zgSnrC<6HT9Qco5dL1{bX{I3Xi-P%j@Yv_Fj@fvD+w3n`O>4tw%GNXg9Q8+lRz2Lqo zo6@7f9<(tjJ9ph;{s83YhwnK>>-4R!wX!4P;$y^CFBR7y*D;c(U^>!$<$&f`ObryW z*b!LSeL4~N9!`9nJ1-&i)Km=b&w>U@I!0kn!iV^*TUCKC8!GU?!!j(5b)g`%^Ca!s z)#W?r?Y+z@nywJBRg@2(-EYJ77N5tJqOiZYz&dBmmaSbRM{gffORyCiw|6Ub>7r}} zuRL7vXo(L-h>CGDuYDln_YBqPiGQasTqXU_s9_CxCPmUb8liDH8~cqS5O64TJ;vQ7 zWZFW(!7bN0YyH61ds~c1zJXbWYz1`42KsyYH%lr`ndyb=Dw!+#lXJx$Jn={k6c#DF|HbOwSy8-bu|sB2UyMN-y54Kg=bTWQ*8heD#mb zq^U5hr(NT5hSOqLO3K{wzGm4ZwF_@m{I&`f>7%3(Q^l`@aNvhPY7xk~eOV;H5u1FBfG6&yGGP0*!m1otb0DFQnn!*6kf|AC2GFWSm}6{QTpR&;s$0cy?-+> z94_#z)>>{SO6^Fd{Pg-`_AtDn>K+C zeJZftttu#0>wbdtur)M!Y1wCXc6;sL7p|gr#Z%^MjK~xbAO=?43hV`4(LRFTJ7r?F zI$eo6Z7*H?wQGUnQVUk?EXK$MA|IMtuVLJ86N;BhSya=EeoU(raw<+SbECbH%xf1> z?H_$H$~Q%A$&=Z!6kI3IHGRGH3D8TizguQhrq{mbKjujjY_jZvxB8f7F#=X-tuba3 z1KUR?5XptsD%fRbm1lM~w4-ZXbvt;yP(zl#LB>Y4N<{5<`MgZcI zQ02E(eKMp@p)M2dHywP)k|1EmX zAVKe#_56>Ah6nTWA7hyh1Gg*a)a5!8JTaFGs#$^e?vZ9>Wqm=wPeR017+tU8w!*v( zKs@^8)T6UeBgntVB$bvoK#8J#@R-^Sg!~eee8aic!BfU06JU3JzB^v|%6_@wx2W^- z&MJ2j#q>mF$uleU+N^df#F#zq~RHyaeR7|Y1%lvlC034KmOR}?j|EBYMQ*gdV z`wE~s;L;tUUAkJdTrI6|Y(AYPU^Z#<2jQh{UXye3rIW%86LwrUdHA=aVJ0&gjG4WF z8mq{Gs&ah0$QmGsaT4`~4dMvY?i$u~Si!b?cb*nWoOKkAp-Z?@N5>K%cJC^XC$i@2 zw;QtaoR@bO%g;K8PioJ{Xgb?aXd#8>r2VanXU59?6Gn#Zt*)|!A_v3t1P_9mffZ3z z+{GG0ox@w)4z%ZLz$(`Oz?Giq1>$8R-(IkJ>1xi`JwC>HjP;tk^Hk4y9(o4Du>%>IwgW??(Aj8DfWIF=WSX6iX+`6Y z9QUH9N)~djk1lx4jnV{?U(e(pT(eBoSpExC^u||R&;8r6aX&DRNv+x8ELq?2s^nzw zUc|7D-F1jcy?JWGu@KeaZl>#GH8?8uvJREv%1lCcIC{niyeq~Ua@GdaypE!+!fHd| z{Q0~q7%}Y$u;?e)h9zu?ZdJ?$hK6cjE-!*95ZRR>o!bNt+G($h}t| zG_`iQne{9%AJw)2>w8^df12{`&?y^vQ=v*%mZ=CdKDEeAJpmR^2ZO24Bw#3JPH*oY zR>62j=<5pZF-UMWVW7j|#(WPw{>`uuCbv)|Nc{~>{a1@zSg6XSzxg>PAVLn73H|mH zsLdfD&cwNo(SO=@_WPji? zr4)8Jw|vMmAP@4OfSZ;^TMr>H=!#MD%yP|q>vw0lNS}_34Jor@Sre1}KxPvDt>6wJ zdGp))DA{E+n0L3fe$hG{_TyE3we1I!eOZLC=ExZ{^e{P_y))udh~V3a6JlfEDX#5Y z&7|Zw;xs%Nm#f5P66|{%_`N5wvPz3lN>wwe?+(`FSq}mpt9Od@!Ndc5IZfs6maXn4 zNP<@~^SsHX0lEhmW}Z@cWRKY`v?+YTU|mxEv~nBF?0y0zK*LD$7AHtuTO%;Aj*T%( z2lEe(2OIDcjZlxqdaawVlO*FsugTOsbVoJ$E!&z)C&uCx0?zjg1FN(?9zkMU8I_VICp%@!-`?ICWK3}TF0WPlLY3|(L9gaU zKu)^&Vt=foua z+1c=osHVHS`|!ks{)Z3od!s)Kv$7c0pw@>(J>eRzn#Gbe#I4Z{bFB6^8Qu{!%F^7jgV8 z8xL#%0LPIuzB2vl9K9-&-`JpTd-Tm^hPZn{PB6l-(xA2%nUMin*ty=zKH?o2o^JI7 ztV_Rb{T|deS7Rw}^9cv>wHCJD+C^9YQLZQC-o3JK9ZqPFL(JY-K+(}3B%TMj^lch6 zStH$HuHQM3|E!vEc&$YR&XL5$a3s*knBjvlP&00GpXkWGPMn)8dh^!O_`5e|Cii-H zOQu=gSPxj34x_J3Lf(Kb>lLNXb3ldwne%oJF^4&7nEhWzIVt^noI7#NBKrplMvZ;h z$Z=VcGQ;vw~uGDQ>WUJONqiedF|BK=E&l{xw8yK%?HD93aTU~3^0zB2jv>9}h z16t#qll@)q!c|}joVG>_Z>{YbL700N+tf$oGV%he0u|$qFVzC~dp7$n(tflXLeuV) zk^}G_&!qQL2a6mW{FS-inVoqFr4~3`$^=MuBB;)X#XBVdF(GR|3K>IChl$RajpuPc z71H~fE{>*G#bCqeXFfJxxhH8qZoEUGLM|m%VH>caL<>Ko5 zyDfq)f2ML+fI;ZfLU*A?aSO1zAvjoB1D6nysgEg6f0+LCZyMLy+gbQCg`_r4(bEn0l%a|6LEpZcUQvhyhkG25*4lak78FxtC z&U4-f`<7Ou&S5@)Ca$G0Mc3t>7)Qh{i7@mTrm)Ut-0RZcE-}O)y%8c_>lr0lWwMjP zVOP`j_R8>&D^p>*oN-aY%3Ho|z0UKyW>8n-+>23EQLU4a95>$Ti-5{MwaE=+7(WAOHbk#zlrpRQeQw&$0eV9pKC z$v{^yg!xFUNZKbv_-(x{Kku#KQ6}=ldf2Qdq+W3Z#+*;`Ffl4nbr$)s9lGT1iMSzJ zKamnGxw+H0+JE93-o?f2@Y}e5*Zc@jjn2`U+XQ!wnl&~|+V9fnpolPy0XraBU%+(vExuX6Z^dkvrqcya=sZXT%8 ztb<`ntj2&wn7i>zOH&1kDJI5$rSNmva2F(ma1;Xrc5!oYDahT{4EuMm9CI8GE>*4T zSAQH&8yhyklzXmx%Pg#jU(bRxyRKJZJw)7CdQxu4&2MZN=w8SC?KLEKd@ShaRih^c z1?!R$gZIH|^8`ZPRuLmRJWbgc9$jG%RnAbmG>s=1$_8f2Bxz)4YpPiju@(He! zp--3X7+vtil+w)|3YPs9von<3=yzrXk!W9X?5O)>qdP{th{TgYM&*?uR!Q#NL#XZU zw=%QkL+%d$K*yRE!KR_yyjwRwhX7dGbQx0QqUo_Z423GpL+VG&m-7yPw39*Vv*ll` zCVi=lTLuX$P-l}`O-%1r>d2hJl3W6IE~T=0be)XE-^wua>^s}8r|y->mP$YOTGO8K z-hMxw;Tu(kA!G}Bu4GaIRPWN{YkcdvCZU|H-@2`Nopl=@Am`nxzNq)X6(&CTc0aW1 zRdkCf`FhJcwV*FN;0}W?X8bgrt{Kp8Vwhre@9E2N^!9~QtogGJbyHJ8>|oA4V69hX zPaiMegs(W3YYsV}6{6S3cw5JGusVpuOxvwvR9PrHXP-5IHO6$0w*|OB$l!aN z{VW{BIwk35lL{QlD;Q)xnf>Z^wB7eSXry`hOk#}^^x{|vMSr9;*Qi@92M6ix%6p=xo)_+WJZPqvcrtLdyj9n*XukQaNY z|HVz(hh@{h&-{LA71MKvFLL0Pt!QT76Owx=$NkMh?%xT^%P_7NGzB_c%kzld7MNbQ zXARIdQ<&7&{4#?d`$I*r7h%RYTy*@znJ#b)k_!Z(B--bG*Q0hwhaYcZ7g6l1tU)B> zwi|BL@xIJ=&pBXgKJCO$M@21ATn0d~+J8Xh>osSg&v80G7I5sVRA{m^C&_dptVSXY ztZvJ4D{XMkH*0r|Zb?g>^}nJIu-N-m3ASry`>Qm1|s~R#wvV zFlUnQjX>#&mQ0S{q%ToLrJA`+HOkyb;iH^0~J@?-u~ z&;Cpx{?^31P%$J&{UM2)HwBhdgsO<$cPq)Eo7B7X(BH2F#(zAU3PGu#MzYKL6{?p* z0`014MU3JIb8!Bhmb~Tt)z*4XpnEx?w_d$Zti++XNa@V$u1^)SmTJTcZE_0-D zGX`$!Z?A`jhQ^Pf)m`({=0Tf8Ky2X~hZ9osd!2N;i*|~Q0dj-&?3m;*qY`=NiY?6l z4*$8#1#0pHhK&CXTrW#-JP@Mlmc`Oe{7ie8>3uy&2ujz{=7FZl>HW=`$(7>I9{y!NQ@q?@ zpX~XcoAW=1yLa#P+&m(DX0FCXe)o9v|Do;8yJ#=TytIT>$+a=*YbQlU#~Zboa#--70v9jwt3hYfBep@)BoLtoDVTGia#TQSYDWW*Ud2!FUFDaImfC`$tY@HJAeLx;I_E` zPxHJKM=!82@u@7Phv}j^U-aUIRt=7g}EW^~)-lsjTjR;NalyJBmTyo|t&Pi{7q38nHEX z!1k_~;u42~dy(X|j35i*<@uiOJ4{R7s3_Lt+rW?<gW2sDufQy*M)Fs1SU%!eA}@tJz*6-Bl^T^2TWTZ$Rs{_GJ0|-tWrTKXsT5!==jPFq^8~o%FFMt8p`fT9IVP2 z3c6h!(e`{P#PS7FLqcMm+hn&Ad$U@35)?MWr-%K|dni#ia;%hHPbyC7-5z?o%354{ zzS6U=Z>fusn37Te8f>Z^J7zUKJv~(AmjeQ#@rX`n>Wbf>`d0=gC2E9PWh7p<$_V-X zaO+p%bfb_5b9HsqyBC(ykheHKKCTyMS@-9k>vDZMH>~&(GyGvrmUNhe#F^7QKxY0i zd;dJt%sLc%*bcN^VDG)A?K%<=c7?Az`@#BaRo08L!&Y4VAN@cmwzE%Ksnx3tJl+|v z^)g;Su`)W1Qwcq2RFn99Fu=Bn9W zZlhZ573-aHFn@fFt@+`FPEh*9zE`*JE2t5u4oj0b0p%}nj?9`GRO-ovFRO90G=mqS z<-=Uv4@zMA{dc=-I`&ikBwB+9$tH6v5Uq2G%s^w!sMnE^^Fl6A-gc{rPxIyXsVuSn+i?`@nxsz49T^9DlxDY00-s zNoF`|-F{Wo0j2y+E!zhsPs>cp<=`*v_n1BQC~@-S)-qBz>3ZoFd*Xt_zG9xCkAJ;S zL(Ox~-0sh3t*%N=5H0EB6`$TAT(;R^E8W6M$>1hVy{inE+!T}-4lyuQtu(Tk1a5{B zH7)B{x9(XytSygLv=LAH3m+0xHWET=M^#^tPY)st5xH0BuPa|DSzQ`rkk!g5VNoGs zqZ>;$+^JqN@$pvF!ptlCG}g)M_bR;yuQrNBwE+bQNg;XDB>Lw`#n@}h(_N@rY3K9f zg*7J^KjV~tz1!_@;eJ#a%(_iGXro#@5FA(cWCz>mbirt@Z;3el$VIhy2k8E*sF0u( z@*mO}^yNUr?1-`UZOhpm5)ugybB0j;db#Hc;Li+Na;@K5dZy3HJ7CF{>>W0(+Dn&; z8}nS|bGE@dm2AqBW|XMs9g1r%ba~Z|h35_MenWXPv7ZkGt=W`~x1axf48tU$8b*im zx0cwg`elfqauh+$Vt(Ak-;!^DVauN8f_Q)9ec?SrzDh=BCsq3@yCd$n`$g;K;k?bD{Tf$m(c|g_7Z<$PBfh&TKawn(jdC8+ zzB=+CO8xsY{q7%8N|rEgEWY5+r6|3zoEJ)O&N3oAI#sCsQ*SZRp2~0bDjMtdQ1PMh zd$++k7KlY$ihVluoXNRJgZV#aV*=ou6dIf_=;-RM@2YL!puZj2l0Q%tdkm>ggo=Am zurv>aU11UPH*oYNgeg5c$7L^$fr*%}gXWkCTTxX=CB*Y1xhnXY23H?=20p%KAt@}d zYW~GU12@ilS1EQ-L`oAS+xDMa{_9LCvltrIvttu+bZ?O@VhUT&CDs-Itsv(Kn6cRB|rki*K)6+m+uy>f?3rO^0+a2+@) zie6}K4R6jH=3e^I{FK}6Tc3A(vf-~6CIv3Zy8Ro`x1Q-naNVKt68RQbTskhpq(%AMlE z=9#SD^S97TeM0dFD9}4@^Aq{It{X@+i)e9PZSO2ipZh*K-$mT=c}CE4WM)X$>flyR zf8HPBeQ)yzw#w!U=AN4>2jsSqNE#BEzrFu(FvU7W+JS}9&uTTE!F|B}Y4!Mpvs+;{17Z zE&It@uioj?4ngPZ!~K4hfxK;nlcG9=!LUhQ_c|~fMVi8^xv@6oCZ|SqRLujCOa5te+Xe7u29*ZR%NXOhXor$l$d4(*T^h%c627e^Jk7`YFkD(_NJ`-^d{qs4LFM zJOht1c`+N`r!}hEFA8{m^5UUgOD1}Y6M9{j?Q`%Zsjn4P(u!nH-Z>kW$~Yj}Fnm1Vb6 zpS^B=jd)XGFgKE*k(!+~_B4SN3m&lXzh0AC%2=#H_utO*u8pc`flrryOy{(2GWe)e zE?)6bL4VU3u+&9hdxAH2rl0+(*`~l6Iub<3c~S{@&%V6TSg5_Vby9kmC>Xamp3L5H zO&$n@MPjRv91xa#dT&4R>`Uz}v(gf~|5%A4er}oHe_si0BqXGh<=JA;A@xV6W@D8L z-+}b{N`L0*`=;C3jbK=P4LGc7VMdyR|5c)EXVMB@pMK}-dLbuF9MGPvzk66EJYR{e zvu1gf!~vO>zi}HNa=}V@zT!k1_?uQ)qZ>aRYZSveNaJpq+?Fj_;6gX31O$nSY-Gja zmqFZ@v*HFleE87x$`w@mg9l?^V0lw!x}$4UhgFo7i}V5}rsB;{`ehufpYJv>mxtfU zA_a)SX$nExubQ5O!V|5+vr(I_gGNE=A>S{)dik=-<&pK!^p;eIBcop*X_5ifQ3RZ4 zl9J-^6BFe(D`BBZ$m~5ddw4q5aKTecpZzJyi+%eGcx!rk)ohFFiMbWV8S3SJCY78| z@bxjrxQp4x>9!yh{jodEVE8|i^OUQL5m~-Hyw%1LSE-Mhc?sY`xf&(Ew_D77|IpU9 zwsAluexIM`f*aK+7ZSqZ3hpubLMMaPOLv6mz!SgH+DXV zsVt`)9T%rr%GPi~tU@pz_VMmLoxmQp4L(#e^*bJ{S7pJ;l=e)MeE_WXJ~z3l)jG776Y>LJ(L5h2EWW zS1oo79^ZZ?Rrho7aAR25$epnm{cnGrO>I{eG*8zsiUL$vH&waPvdYYgSRUme`E!m5 z14vF_`)Si}c6ZpaMwdZP3`C5{+toH%gIn{wCz zJ?M(PB3~FQ*=d_z)F{GCLhc(GSQ@#sZRA_7O6fkdhfl+DJo@vmvni5fQwsSrxpQWz zf@BtuF$nYVDVpd`E3h&*L=}(QtGm<=r&OA0i{`m)!Ldf7I}VuXSKa%*_mW5`vYopg zKIQ)UR8F%S!}8i9^U;gS5?&AkPt-R$y5>9KlI8q-#=ybc)UP4Uu!fLD_`D8b<2;Z= zeZD9hN~ikJ!^HIl`*o4EeR$Y_lGSeC47ILMcajjG!>2nHyjAANBcT@aYt+L$a$z9t z1|L6WjEJ*fFi#!uG*~EKIy6&1=E!proc)6BDA=1~?#Iz8zJVU*y`G=xNg8Jr(2m|` zZEZ9AYj8cmiOXOeYo@{4CU8?(QELs8e$Iajxamx_Q3AXf`fcddCHcu+Q&0C@O7**E z=uYJ$45B;?H87-I8@HF*%&&HkCm1s8qSC~aJy_sq}AUTZg7oHr`ZfR3gsP8q3Zpnu$QhokIaN-&=(%{T%BJ&zEAvZ;Hp6#erc0p z_Gz7wJVx={m4JT7z&X8k4?&cpXQaWyZEqq{9?a0FOEbkfH^wdp^p8(YSG1B6s*bm& zt(CZ2W|MBnhc%VK>oE#PoFg7=+?o9$Ue!R=jOFh_&L0$gAZ~5s^-O?d0w-b_p#Vv+ z-`pp;glt%RZ9oj)9nzC-n6|l52S1`w=QYOqgSEUkpXR}8e-aU~W)gB1tca94&CEc- z2#L)Ql)aY?gtLF&KE2W5Q@lFd#nK0oD-WCPiYX?d9>>O_TQbR>0-yoWZPE&do$gx6 zlWV9j)#A~+VM5!Ttc=;<`3XHzf;?o5#~z`+NeL4R=-oWK5~q7sA~GJv_(3usSmH8* z!t_cGH%R%1EluavHyoxs^e@<3K#wyLQJ%+*6i)7g4BE%(^%#lkj zhav07Pq-U756Pb{*b5n1>d`qIp}2GBbjSyS$|bj+bo{q(-$ptsKNV}O3!ZrHp4!g4 z5&Yl|!mv=f?A4`Y&yIwHwVih5ZdcqLE0=i1UIkb|_H?5Ib0YHD{jMI&?Q;I}5o+9T zWcvni58ZJt&7m(#Tz807s+ccZD+l0=8)}~l3^;CrM~TELl@oQ!>z9c{8^VfVJt%Hq z1`+TG$2oGBXEj_jn?wyfV(Vgo8%Yw^x)T4`^5-nK|u`PG07$weP;jR z3qH|94YUTha-m2LYF|;SK{&}}3~2rcEk~_?#cbxaH}UgrOwhyhN-vvFn4^R^jA}G< z%@h7f;!(=?I(?$+kT!AaMcUEj!MR4@C)<}g8)xYgf(K<=t=AfKFL5p@rx3NYA!v=C zIA~@ag-`iPsZMx`ks`wLSRsW2*vj=xJ!%7zs;6aO{?%yYo}B5TECEbXxu>N8+tKix zGU! zk6s{45dOOv?U?&S|G`j?Nk7>>eQKR-(#jN${5gTS_46OlMWt23x4c)qOfm2uF{PWN zSYot5JRpiHrCYPY*3{}-_-W)i8xB&Dv0#z7=y~dRgRX6(-4Le;VBi^6Zh{8qMirRL z<<3v1rOz!v(6iaQi_D5_q+D)nO0E9(Z=NT<&LlvWeq83}{b=x3YuYn2cS4AD<1k?eDx~RfbeZIkcF3B2wpZVD2h#|IhSM`75-tHQtY$ zM{$sQFk8A=rUGM;*07^)`Fp3?4q67+ABoR_p76GjJP_>wZ8GD*I44{`gtwE`1~Gx_ z+d6JBzKUJ$>2ynqL^iuhjt(V9f4^m<2C%t7y*CIMwdMQeavfX+)j-xzf3=Y<6O!4V zh4U!dRM_7biN}w=7m>MTuAQl~)wmB-dAVpl#$1+swjpL-p>B-}=L&=kI~(1UPG+IB zeH{4)FinHkl!x13=l#6tr5>w0XF*>^_NG*rUCMEfuL)YdX-pJvoRZ{%3jb2a&ljGW z=uwEL#Nmt)s??KYi`@zE-@FZmjsjZ8IMX1jWSaRlMvBkEZJ%NM?N6$0U_5qdiCAxz zH`E<~H5`V;J(s%>%BmblEwCNZ+nUm5Tbyt&&DnN#uw??hsk?h{n-2XuI+MKfdPmqA^Xp3SebUF+1_cjx%fvaRQ!M?j1RdY+D%O^gZuhgw#mU~tA4a>$K8%jukwo6e;omN6wvKi@%t}>f*z9vQdS2- zKb=AuoxJ?~(*9}W>Id>4JA)L(vuQQ_=eL5?K#EOT@Oz1CrySq%c41JMApBNy2&7T^ zSP=WhsL48QSHdkxPmZqnBUQLC2i#v> zXz!&BR>}KdMFYQ8*OW8?x?`s-#zFe~nYnjT3y+*v&Ah&nqR(;kDzQkwjc_zxB4Xqp zE2)}Zy^%*%FTi_Qx>mYML5gy2!EYN;{Du@RQ3#c+T^kqN#DZz}!_`t!He_BsH|oOZ6jx2j6Yom{d!O|?*R47f#rkq&Lh0Yi%JchP++?u>3 z>_pD5(?D8Mo2feWDP8R|d;cOLv7|xYG=0>tJLC>&4LQRmDSM{V@gjGNZLAY%hrxi? zWUx@te;Y9)qDH)0;_gf*CYPAm;82|pR*3E1KD~Oih(`$*^J*)#)|7N>*27tTv%$@w zwfc?141NnlQ&&mez9H}E+GS3Iz-Q9>bGYzFN+m)TcgBQuby4LityA)(>z1(Ye zB|`V^U3tzhpS30IJ|dV1CD-Nmn?P@!nt$M5qQKgLb;oxh0~;516Km7 zY(S8~AhKxX?&j_^?U)g7C058Sr`sp{guQT=;>xws+A&0Luftn33gO#Qin-@GiS!mX zp5h18fWu^9>}X=Yg3Fq8`O31P3R>uG;&ydw-54{;0VCf=usq#CQh--hUlhU%TfCUu z`g;AX@k)Ju5!usp$o$O6ihkv~Dd_`_N@urNhG!I-aT14?UIwO>=rzzCOgr;!ji56w ztVCQ;+~6NBgu4gEtC|-jtO^r|sXp7G!0t{=PS)N(HR>cb6l_oJv2KgLYvVq?Jwgy5 z*|Kj?YOK|>*6|zpV=psuXUC(*HuOn2X+B4~z-IEc70Ud=FTGq3$r)jwAYei`Z#IQb=n<~yowBUkU7>#0=XO*@| z^%(Mp*^7Uus&cl!C*FO-okBoMgo^Tk9NLJ-ODD&T%Yzuh<=NJ5StD}iV+WDCZLxT~ zIrL7MN)mHTu(7kz30tSCs`JX%p9sHv!+rQ+duJ$gYKMMcUV!3>JG1aCwBSe!wgH3| zOCX@(d87=*?RIliynd%%C-KK#nur}lR;;bhU`7>YpW$oA;67KX_!q)g!cG2jNkMJV zyE(ctx|U0Zjkv2d^d^nO-X}oo)zuct`Nj2dEK?a}gH<}iV6&;Z1KKf>43=B#tL>%^ws(dld*yhg^A_4PNK3Mm*SarS zYfD`1e5o+`0tif}*i0i(rOL4IvYe^x30a%rkh8975fnXrG2*Cuck0!i_Lf%Mgt z-EB#(f*2hm(5_m^Vj;t&g5{&MB{*isV`vYdKJ094FEg2^fW=FFsCR``LsP?gFRDiF z(x8JSfwO||+(R3vF#7K&z9Wy!G|jZ!ajm59UsgO}YX~@AurQ?Jj+7uvo0}u@Kxh*i z0j(;ssKJSJhcR6m5K0i+n(R$~%8UQXI|3$r7b|G zl-w?F1m?mvWo32*rQWG7EwwW2@#@t)xjO#q>L0zA(!wfC9`6`ES<7LbD-pK(=%}{? z9$4{!W7r5z`#8E6({y)L?PUC4e|-tr3AvSZ-Jsc9ysQXe!0z^Yz1;l1&B6b}KC|k_ zBgq8s>vpW6$~0UvWE*VvLYEF*qmOEaN=!@~U*3Gg|J#L0ZOo6`lSlnU8gJQ#9Io%S z9d2|LZB21gkX<*{aS+?Z+sZMOYPM~n&%CYeH7R+pMH-lxk`!*AglU>S^A~Ym2&$S(W~;P# zvkH=HAc-kXf>-rzq1bgHarR2~ngYVI1?9Ui*`48XPyCej$T+c|QZt0qBkwWsW2h{M zs474zpglA`u*pLs7xw&xIL64LWBT`{0+4XiHi1fEp88Yj9c;tV@`4?P-{0>w+q8$m z0*F>%ZsDCX>v>qUvrXdnd*k|)f`&(rD-h{bU}k7{rxzU9P~>>ev*>pz0slQb<>kRR zdM9VF%egn2yH^&dMB&T-%%ZYq;IFF=4IhD8f;LiNSP0{D`{#>JIwBV^=O{LxSpS|>-A1nd18kPw@NF>e2)XmB#~nj9HBL|D z_VL-Mx4hRarx=-N7sv2=?g3Lf5W~juToUTzOgAvG<3yE+!qNLz9Q$gr?}%cqFrz*J zB7$6PhFu(-=R)kSMsQX*ForfvhJeaLQe%yw14%9!>b#v_>AT+vZhm(<&i*MGnPp|1 z?x{!rxvi;Ap0C#OE`d|f8;L87HGq}IG4s`9WV07^^4NA*S~G* zTVW0XKOt!clYja7QDYU{k0)Da`8@}(uMste3dFoOx#|8s+BZH+iXsFB^&56DW#g{B zbX_nU?EJwC&q(!;G)ey=Ffex%e#7>aq+z%;aVK0-!lK{q6b(ZLz3I7Zi3Tp&+30~S zr`uR>?D4Tw<-eFwPn}|Jp`Y8Zzqk#yShL;YDbDPw@yDX6R%nsESw z1Qu0U+<3oqipP#3 z*rAhCbldknJlzD`)|K~ncjjZu5*bn@MOcmPCsJ2Xb~8I};_E{ih2HmmGmv)9dPbo{ z&l!}WL^t=$tPX|`=+~AmJzMdj${Kh>UYAfOX>g>{#f0m{3_)!-4J~V&XHzs=v}rTb zb33{`_U@*0W00_{q{`zA73K!1tOHkYlnO!^}bSgk=lb4GoR?ZRll** zUfcaSGTgf>)bqvFqpjNl=JsMdemHRhUNds{>`nh1AGCklM}R&uwVmIt14#P$WH{!{ zd{1K}7h2_!wU~_=CdyUt?tcJ_`i>lF4j%oo8s$82XwX$PmQ_}A^XAQcNx8q5tz9pN zK9nD|o3WFMc~4O8Wj%U+(cE0KYybu69*VPdRf^zAwls%VTW?a2ODs5AuKW(sC?9nyw9i4y2^{8BSO+-8X(Wp#jLd-; z3vwlh!(4wmUz}gJMAWZa`1)w1G%}d$EwBTbnoGm4vq}au9UF#0tGcj8o`MTSq+GQT z>pjL=bZS5Jb2^uR?v9@u45*7z26WfS)aAjk)u`)jy?v2Vu~3T7WE6g00a8a;nn|43LD6C;6vy`f?rU``L9U=%BRxbQZL9WhXC!^sVGvlXF=dL}??(p<> zz?bhZK-vs1$#dcB>eNmh;B?~N$ktws&{{W}z+|N>dg($@5 zk@O3^h($A)Py=IED2Zw=)Bgu&`4sx;c^RzPyeN5(R(lnh_?dKGq%j^1G}rtZJYr&q8kW$0_(J$^=K{cfvSKukeI*QOC>@quA!m znQ+plcSTd6g=wA-_p3@a0UpCNbnBd>5ZHinO1j;`I~xb3cibGG%b=}f3)a`lxAV4B zmB~)3hi4ISh;%_2efv8?ZQ=mA7_i3JwtDSxO`k%YZ0TVRt2;f%E867H7g3?R)n4>B zDv1k^JP^+{Ww0Cx8FqUgmw86GP`g8q^Tew@@p8T<-5k4AsDrLT5pvb=Aei#ae@$Bk)1VNeAn~5OjmL zV>fAOAnTyotWuRZWoZyIwDh1R^j_zXilDq(naW0=ECHZtB+n&<$O9EiNY6F@^p@`fBuhXP~YG`V{DYj|=ldQX|$j#bP@_XXobsLB4w@T<+cgzw8 z5^@#rLjxaVJ7s9`dpCH~QpZ=4))(~jUNx@qv@89D11ZS!amo(f?}aNa$eHJIU-<6D z#P|jf?z7pGb<;xgHPqzDD3wskdNNkyfDz!as#Z+*m|cMRQe0#tS8|^G&&ujHMS%*E z2|q$gP!+CXkZcV)#2=^s*)-wGL^YFJ7mB@%eL=EGZs|xHCHa1K%fvkr7N31TlF5ov zfnddR?J8I)0`wfBevy*6*>r;?OoG}_xKK_WHI8h;KW=NdVZDau5+N*^R5_z#XJ>~2 zQ5bJ&^dLq12xzr{x3Zjv5JtkUFuGKCXx?(HMI(YP-^=b$I6xt6AjCz~(6A^^Ect8#NIEyEq4tAO%W_6`%_Vi&)nZ|6poko~r_~x{aK>0{z{8k{!E`7V11+ z;h*qB^fN5VJh33%biZ^r6R1>nggx}~mdBCK(6?Tb7WKQ!q!ML~mVJejMqLQ?zBgtr@8iw%KTOws2MHlEs6rWe!^^;#>+WERCjj<7F#Qto?fnxrB|8y~iRcc^ zAkt@9wN@ogjYf=8dV~8Qa(aBQB-}S_-A^`j*!a%>(nXjVPg{hPoTJhq&=ZJznHKj) zURiDdR-(x9a72AU@>7KsnrMO+gb$PU1T~2PXZq#d`+)pIlBOg4ARsDynFqPg0Z@XN zx=G=Zv&^A5L!K?vwxntLv~oWT&{Kb!vcLav(y8spaX9!1vrz0^XoF(R&7WFBhvvC( z{Y%16H}87Sg}nZ~@YtqJUhi+pm@skXB>)K9by;pI4kW`AZc%YxwtrUNTKjwNN+9{E z!Qn~f%M@W4(qZSsHn9Z*uh#e3*$q;~%W+wh+g{_j5rRR2ry z_+_X2{~tTG>?@1oRg$pTg3Zmps6y)hNnZLl`}pU$EV`$vjn@45Nv}_|=@B~OxQPZ4 zI21?&)|~y{BL|->N`JnLf9;cy7=N4&I8Q6@r^zvx`!|*4zlY@20IKK^#HMx=0vGl( z;r-vQz=!cj-!Lute%2wb%5jUm(y0AkekB?IJaRk&9P$gn{Wn0K`S*6$|0-i@f2B%M z<@^CqCje?bP*M5WCtg99Zaj}M$j3$TOmC;Y>5+f6*d{4)H=8+J-TFW1@tNM60jafr z6JJqM1g6H?|3OwdWw&>QT%+ z1jx$&p%ET7rDyb;8=5_`z5}H%e7sg~7@FV)ePqoSEVsGms*k5#RN%t%=lxCYz_?1o zmy}Ypuide2&SO4)_aeC6wyRvaHrX%gw-g!69<$Qu4g47T^W2Y>2QlJzr7u`I27se> z)vOyG1pK^Tw!3AP>NAv*C@)s_r0DClxO9PGBz6{QqjP=!>e1oJGl4_FHEP;t4049v zT&drP;~Gcz5|pxB;*i-@~Kis6Avc$!^2+4K3qYxy@0m$zyec&51-iSF(Xdy$<`Jjs|pYd`%p>B=_v zm`Ru2HyGJ&pny~Td5Al*ZDg*`z_fHgbNNDfd;@s~K^^~*$UL++-|PjvW^C1!i@dH* zossO9gG&vf!I|E&=P!;2PD)Fh+PU|CNcjOTtr2X~cF;vy*7E{!2g2d##j~m!D=E+= zA}L{JQ_442byub7Nnt{vN2vL&9{3xX1_4IK1#IL&Q@w!??>f^4jy`CFv0F_=X zkl}{8HpO=jJPNRfcQ!SHvU)_&y1bC=?Ce0`)2%q$pTE9)l=$>%HmJMj+x>FQP2l18 z!=*OzqD<6!jmk6XFC#S3FV@(!%<$P7V^QMd43U`diyDhS1&CUXJ==@gL(^#HdsVM|isy5!0L3?i zxC#^$)wLvMxdto?zV=v6++2^Doo?6q^t>oTd6%FL^Da^y*?*#b$vV=*6JPx=)z=OSg3%d z6SVP{XEpw4MT3vxEftJ>yg^6Ul!}Z5LMb8Jj8RxLQj^bEWNk~Vyo@x`x)y(R#A8>m zX^NgbGS@hdyVx*YgR;JHA8#u5uMzo)1Gm4}CUIBI4RFQ)T_f`A*RO%&i8eJZAdiyg z`Lni55BiG`=jnQ;Vyw@Fvg+dhCUa{9t=oQ{)2=o4^}wskRmM3JwPO+zx)=QY3AJaX z>HCszWP_#b)%Wc)2K>hw7J(Wv{^9dh^AlN)p^NX*Ocg*<;_KKL7bNRvgnW8XyXj;) zwg|vqqdyi9_1iha)mDsw;sHfuT~^OY!N)W;-4uE~pH=|4njT=W#G0jY)sReS(p~_1jCh7YzP2#RF07=>&z2{_4E@TqC2g|T}Z4-1*H+`m9=0=j(3t$%x zT;?EYdizKRx8KHb8i3|DfWwB4>*?tkFgFr@d%O~Hrv>k*eQ^fF%xM0)dIVJ)w>;PW z;;3u1!8=-AO<6FCNwLJki0Cu9JbQKeCC&P839YusiFyq8YSbpBYeXN1ToK5?6@o!D z*=4Mxx#y4VHHp=zaC{~fG>QX~T<4d8+nmbsUzt;Hx0(kgJqJZrE3p)2?wvdYZ*v%4 z-5#gHNtgr#r=Sj-z7uC0tUZVWfM~|{PM(^&oqIA=EDXAmrhgs0iC4!Ee$LL$fut)s zZ;T(w)iOdpXB$WV`R6B(+%)Sc!)sTo>-ZP$+^ITNuex{dS>U@qBNy6j?X3wOA|M!b zJuCFV$jC@N!6^);25<}+g-E~7^_4~S!Vf%y;uC}(3U=mur)E&B7C~kEJ8am}fR&$M zzAkt^m0w0Qk}ewIpDE&AA7WCs! zKR(v|2`~q^!2i@|SPUO&7vsJImB%cCKq{zJi}RBPq+pa=F>$SnLoFJ5ywM4zct@iw zcuAAW?3o)+4d@;e>bZ=U3>>m6JC|b;ht8$UixA|(=T^$pu=2991W+}1yIyiT7hc)3 zt$_11w!E#;hh>e$0CZ35^EjzD&=BwO z*^H>fEU*ep$k_5eKR{?nvN zO=@Qw3`aSEup{)Og?#_e9qKGFwk*7S_QA%_E6n{h1U%b&36P<58Mp4iIfmOztGzQy z2Piy(ux+Lljy&xRbB8EImHAARbsn-3i-c+1A2Xe=EBQ529G1|g&;QIw5y1=)+KE=m zFhadKBBOGtgg>$;YF9QrRB#2<`1^Kjd(0R8Fd}aw8WFt*dk;RUCx(~e+G$3hZa47E z5RX=dsYI2OB}~-&19t9otO48i%nYI1S|0tel+VAYnpPpeDZVFUXj9qVdmHsT-tWFv;eoC>eBRitFQp#|{d5seXOiM2$d?*Mq$CD@oSSfA-0CDO zl?sQ$x#-J8{=>)t=y4=-!O69!yBj^>F39O8B6J{iRPz4+k0(uLLp;5c&n7Ot+HP0m2k^jV85BJz_ryw)H4m88LsVT3y|U-<1p*gtvcpD^RZUn;#1#ndAbYU_I66-^U|JbflSfnxRb^5A$ zPNYBnF`=8bWViDQ2*J}3p7m(hj{eu>n@c0jpoN}>elTR8HBv5u3wJ+MH+#mtj%6Tc zTUkjd;gAh8wjPvzI7Q=CFMfuu%g#+(`DbR18|vNADG$QBiSRM&;!2pr&^Q za5K%*#-i&RH8koqM@3(GlTE_jj7Sn|!L41v;Ps%Os{@I;bp}^#`(`L)%p@VsR+pY6|6ZZ-k3as2@a8%-2Ma>x z2pmfjrSTISobn)M@F>&pR(r5+?MS|u$(<9-5r2}qRH_I+|uDkE`Svz0}oyw z_(uQTD2^b$0sp&pMs79)DDbquUUGjR3?b4kr(Gc-unRher*3DRhXmVS=nYTbSNa9v z?3@ii`bY)nZttuskbKPd@1WgIULy`jtmEoj;^thbD(GLUXa#_>`02vMbEmI)8p5Pq zI?I(w&>LQSWr#KG&jHCg5!dae1-9E|yp%Q!t@C0`ceN@Uw{050@Ck5QOyWCCGNBAR zUON4VVMud9xz6*?)V8(c%Kb)YDr+YYBkP5ByZbxbWn>;pA)p%(F;I*pPWG$g$x_YhLTsu8ION5*z)lGTe9*|QtL7zQh1V~9O=f7Tr! zoPa1((G|e6F9<5mdYoG^zF~h~FeOlK2Z8%Nyf;hjiUUlS8a_nWC1w$UCzbo;J}X|J zMiF@%&QL|}oafoJ;;eP!_0EENhvuf(og&n2u1|B2*G7vzUYUotO4+A6Esdk(yB(Of zMEwfkPz$|nhDr+}?1HpY3F@plD8;WggWJuK5IR9+|?fw#2~2;K~Q-2w9EcOYxq zLNJ#uLokZ}dBfQEyv1zV-ggJDI8X_tp9qn})xn1EIqK?S&`)C6MCwd%`3m{_LKvB`rTkkjjjDbPCle$()G+ya}P?Y1+ zj=UO_yxK0)_ZyTiiLawLngM4Rg2-yWX3?4^DVq)i`bjZ5&o%M3ibeH@@HQ9 zpLs0^2he4%jmjtP06p7sexw~t@BmV-c~DEFTt|g+y6nrQPvt92P$AFul&;!_BO(P3d2tyA%uI zOt*RH#f#&F^diHoLkuT`ri;KVuOs_LR(I=6WfiXGk1TR!y*uP;t+zzk%PikR=P!; z-aBY3Rhp@LGYd3pc3GQp5=4P3U8hLvc3T|aq~Q!3Y|lolP~zkFU-4JiLP=b|5|obs zUC7=hZRQbM{`$CJ?|;>$gv7p|-AXK^R{B+8z*|Why>zJh?Rt-;awoSH0@7~J!{qyw zkp?6ZY2=7;IXq?cB+}4U$FuMK`n|B8zITJkWwr+lZDl{UD+Q&NdovP;Br}_BtA^po zJ^i4UjbCvJ_p-w^4oT3`k|9@74}w*YvDegVwxjMR-{*=zej(lpDK}NWQZBZc4XW%4 zR=9j=&a#X&I_4G;UI(RwegB|pKy3qQ0410%5pcaQLhitQa#t;#D{uv+xrf7u|~)CnG--~jY~rUl3!M!5QZbt)KD^`#vw7g ztW3XxpU#a|Dcr<#i_wU7ZjT3f*unL4D>Xr8JzR21qg_qln}CfcxP4Y>V~JXYEA@uy z>YXn5(gG#h9T)X6B34giBc64)d0ZlN1&s;2`wh+X#e-pzT(+kZuNI_$f$1xBEt^pxv&kiGMo`})qzoOJJAC$dpUUjH2pqG50n zRJ)umqp&;>kn5&F<&E!|f_)xo~5_DcL5PEm#g z4qe}%(KH?DbH6mb7V7P_YQ$;Jr?PFf9P-xM$V$Xwv*fo|uBTlfQPdMcZ1luLJ`vF9?x4|IqyZp=vjceYcw^I(y8vb^`SMSvuFGdY)?7 zgz-|ci;O=lWd6!zJ-QQ0+-9EvrW1KS41fbbGkPmhL)nRw002P4-J65G4o{TwiTK=h z-VrYeClZL~$JvyY6~i>nrHh&6T}d8-T0{5tqbZG%v$a7Sw%PTjSdguw9x1Epd61pJ z(}n!+S$4`Ue>=*X6(u`Z8Kjv<*}Kvv1Q@OoS_J=xQ%H&3W|HJ9InNuQe#!tX%a9og z&y)MJ@^HS?Zs?twm1Zs_w+*jg?~PVf={khWy{loCb*4&;0bVEvUz+_lJJ;_Pd#vLS9M(A};rJV)*~c$IIK72MpT^EVY0jz%YD3vt|bObXV%!qMtp zSb>bD@k5f8@H|q-?L9W-p8aa>cI3U4TBarG>G-U>T!|5Y?&NC7y_ezH$7#V!(u-FQ zyd!^}c~<~d017^5bHguk1*>r1NyZWqKc{1Xv?pe$)OjE*QRDxMy7!K1D*N7taU9Et zh)7fF*yu%?bfVIG?@d5@6X_+ykx`JU^p4Uy(mPRlM|usB4grD?2#}EEy*TqxaOU$} zzqP*WUGMKbf5FYo&AI2^bI!A${p`JCy8Q5mD=IL(l2ILND!WRb^4SK*8&rQ*ek_Gd za?Z>Y8;j40?3ufLzx)30)ZA)-+LweS?_*rZckMPJ;AHn4{5aI5}aGNU7?Q$5C4 z!#RK$eE~fVA1znatCcj?(RV0`oMmnwgClyg?ML%t$m^<7cN{@tTMejWlV(mMq~o+& zk7eQb)1)ypi7)rm5s>O_^VeL-gg|BcGge7s1ab3W7@#>&F`o3eTt&y8BT)8RRx#&@ zBUaPFp|BiQNWBk)(0ya4@?bO$6uN=!vuS9bl2oN!Y`L+^?d#LJ4kGsVo~&E0n{D~p z(~%(>HrXhtK3DB{zxM%@0vnhfQ+ztGyJ!KqOWDgVw};#6a95=is+jt23Rpu+$Mq66 zz}8qeARzKIEzPXxsE!=#n1&WP6_tiMs@6|dc(gr_3>T*QT75XNJ&gE>cAqvG`_l2^ zaO^1p2wWLF4#FI`>DO?2I9{TOwN zZZ!-Gw@>>y-q10bj;(@Edwg(wOmg*?73VOvhJ^?LuW}i(wo>mYpDFZ*cD44|{r7a% zA)@E?Zyd{CqTz@WcU&W}629 z*BB53DfQkY`|PAEuzzQge-N7wy6yJq9Q7&?5#jbIdyEeSL>-!XcH^wY6{mSQg6w*1 z0RAX4GIAF%jYQ`raF*+j9~u!O0G81N;Go=_0ZmKg7suZXp~uSi#&W~k7l|KZ%Y7I? z{te|gj<5F9pO$SOnyqh7wa2yo(oxcc$uH-0Y}~XG4}}04avDISgWS8~u7APRSN{gE zM|fL4c_MTZGF?(Ab{wpp{G}8+6y39IzivM~DPnNo4`dO{O6-Vc)#P_wRs!;lZTUw4 z_`7remqBSx=8?Lpg_n&G06?xf;vDs(;4L0>6^{Y4)gC9ht~dC}!~wf&aI4vidg&U4X9ClC03=5e+MKqG|w{l}5N|6(Ei<~Tlm{DE)* znWvQ(-b~b>j+Cr-xlbPnWbk+%9R>99#G4L$>7Bz!@4$fPg%iE{>rxNAbJu1wrY`*- zI*yBv&JgaO-R-Ry-|Y@c4fc?wci655W!&JyXT24S);*aD=-c(RWB@g4Es1M~-PE^; z#p<04N4Mbf|IvfWxBqtAfFs?nEJnyFH(M));fVB=%wTYMD9b+kKQdY50_pBrq(1_} ziPNoH@t-~VpS{jcOQ>3}=#=#H1Ybr0F5{xzw({KxK2)^+y)4z5d9JOJChB(fsf12u zZcW=Xl|fK87n)Pl089{;F{aJ2pZ$X6w^aUgCv`QceYJ}?JsLCS=(8HeF7QmoQ<~FT zMKD6%Bj;;g+PfxCqm1xATDFGRt?hoLtO1BDD!fJpJl(0=Z^&=w|0%OR#}Sb<#;Jmy zqG;S}w&_!;loe00Y!wL z>Eo#$YREllPi?;(RGL^l=zWohMOIk&U!@MWAIvcvF>aEtgmX8(f-#PNEYGw|>mP2Y z?NaFZO?Ouxy!%CY5J@4Cavp(PpJKDqO^jTr8(xxT%btFKgOl7huCww_$QP4l$3KFO z3#X6bwBR)xX%%0>ZYBQyr{~xkva=(5t#V8FlbkwMUr^(DY_=oA zdu7F_WLxq$E0#i+1|JwW?piWytnD9t76}5Xotl_99V__eu(X0}D(S7N92xvDXA8H} zjYy4(ha{BKn_M_l)9ay7pY*PR*`(0nH_<4%e?UB+Y2M5<;ri;C+|mSpPR#n-aWq6y*u!u z7q4|nlIq!(KPY7>H8`r?U9w|>FVwNDY2fCx9`0JCPjL^N9|8)7<)!2$~NsHfc79 zGChRN-^!{C;kSP+YRAnJyxYgTRhAh-`}eGJB|V30{iBy}(N?f{ZFKj`!R#@X2_6D3!46MO^%eN%-6KH#psRl#D@j?* z<*E7^CFzsDo<~9%TdmC=cZY3z;YpVM01m%AFuYHj)k$T%*ox&|Eu?ZsMPrsY^r4ux zE`UJ1Qz|a7Q_F+!bbq0eOPk%W*HiJOT&ho{lmYegGyd`su%**>E~2r2n&uTd-j1oZ zN@b|q_JE0QoDsk81iabC*-D;~;u`!tkI;JyBSldoxL&GD19*AjS(e(&xiABYI*sSd zJD=})=00eqG^TLXtI}YaO;6gYQI%w5D3S+K`V{TeA}O%Hb7~s;dG00NIj|EBQW*^1 zfjR0?Z%m!uv49cCCq8!m3!lR(7qCcUkUMxeO}kImWe?hZvr``je_;mq3o7i#RJZA$ zb+Zb&XGw_9^hUaVy1SNB*;FsHIa1&{X9M;!0=b8=(;-1Ohq5O#NkWe7f7fYLAs*xZ z_$PbWYf-&uf%2Gnc1b-4Ym!SW0eo9Xm!{e$ECSvMqTj+TPdpSr{api13_ zdn^_9Iq!)z#icfsq+!r&8UCbV8Pvt$L$Ms5G!T0$TOdDRv#MiG{0Aj4LB0$tr9LFE zl+xC%RWpwT)mz`#4;!p`zuj%3>E%eSn~BBC6!gT)@_!aIhD)3Ug#NdK3o7^Be=U^t z_jOmwksTQj+%zV=toG;=-x)tkFSDwlom*f_FOva~*hf}LI6h!6(|HyavEPRX*rtKD zru-G}^rQ0+Dv$d<{dJ5bj8PE%#uhr`7Y1uTTrBM@3L=lJGw$zZ!HhwS4uk210znKWsfl2 z5RiQE!NqUFg417*Chl?<#g;uQbdjKY0G^@7&C%59;uNKydoM zB=RReS^6XOKbf_D9A>c=_*bmU{U0J%`}6$;5aBjby*nN2UofsX4E%DD|8sC6^<$W+{BAdKnfF8V))j_H`zA(&>#a!U;ODM~c>0d3*y&J{PlTm<4Wz6U_ zm~7%bCdUIf_`bv9S!2fE_Lavz-lyfqE>~0DFD$8}GyTxJQ5hoO+N#$#J*xx8wX^dn zqfGpjG^w`o261T}shD~^ehn$)3`-pr?<%Dkst+-r*_#lDhxJS9W?pluQyjljGu_4P zsvJ3sXVDm+rQkkXc16W6zF;OI3QtbnJhq@tHp>7&b*m=sgWRV;eu5gqwE7ggo~98G z+ODkSPh7;Que%wKRQ)jqLDe?l&0dae1`qwFoRsIjZZ#DjU&y~wM%0nFkhM9o`o<^N zzR4Js27VABP5_eA_NNl-#?_~d7{e0Rf*RZv4(AoY`yl9{o0xGRgz&lv^#V~UzPEZ- zmkk+YY_RWG)^vnqE}9*CkdqA4?n8`d6d5Ea;HrTtQ}a3^gnX)Cp+%t-7p;8!-p8{v zqMP5+^p37^i4X3((Z9uoG#wq;<7&)P?C7T-@o)}&whiPOV^$=l@uiD-p^z9tvAsig38%BiR$UKxlm-Irlb8Pup>W?GZokGzNl zkyhiYvJh}aZujL{UzmqfUQaD&rTCI7XBozGWxCGY7%a>!ea?QaU;!($Ruw*&pAu8& z3%2j5825Grcf2&HtXQvZ^YNUcv9=?6aOUS#BDxX~e5-Z-o%q<*_ZfHN)3!D%yYA=H zd!K9a5_#S8+d+Qy_-)%)6gNuPox)vnTt`VYrxb7RqIsd~zq--nnj9k;yDA2RXPS)i z3||^lSxMbWFSHKb)LwmuyvRh*Q(H+dTZ0My-nT>PS#}ElvII$DgOVZa%E8%}vQ~CT zg0jZ5_o*Azc1t-Hd(~%J1ZD*zST)mzKQl*Ge9~p)*`}`PLGf#i#8wN~Ot_x2q`hxc zuDis#anO%=w#cho3;C02QmkG4or|dzCZAuXh}+Gy&QQPC!g)^lR?Koi$a@nUDQ#A( zdlNHF^;k>}mD0k9OVSGwd>|Yn!T*J)&&2-NBYdho4|s3o@82YPG5%j5`F)PmVku~0 zlRTJ5JwokYI$DKTM&KQB9@~q7uGr%y%tUwNBZU8{CHY6H%c5k7o4n!UA9U$6y^uvuKS-W`gDti{-#r7#@_ zm%SlTPpfuIx4IL`fgrSEF!eqUQV|baixRdEzgsRO| z6F2($o}VG=(=VgZK-H3LjsRToeDmCNb^beNpYh@boN216$t;s6i&WDR71jR$-?i0E zCP#h_X?P9>qAk}De}MKc%2%aN7`m2_YgAdW1C&jH+5#0T>k+b z==6>QiO-U4a9VJ|U^rI%yQE75t|GNw#+g4H5*)SK>Nma(#l8pQ2F&D<(#A$7bmO2971S7w$}OFR`LN{3?F1yFfFM69J&_oC_Ti zB_=L&-G&0HB~6sgkrFfowu(R)t)Hj3h;8Vr-Ri^L!H&M4 zwb;5*Bn5qx14Tc_Z%>(LIftn^1ir8}93N1d|Ffflqa!6(>LjF3@lO65&=^(Qo}JG%0X{qmB%&9!6(Hh->K8nY+q|H0TFu+7 zU4scvEi6_Z`fER@54q;XP#A~lVE5eCgP}*vJ?{{GTwDaI8=P9Uh*)TWay|LnN7qt5 zcY3D1Eq1=t{`;@nIc+RP-raJyCw`7ep|cS{pWP@-I{UbRaQ1K0FSysztP8tC?z30_C zGl!u*^wrvHwjfs6{mJ+0c7tpxJbNwCac>J>dy3^OzK}09R29c)h`ub5A6K=djb5Q8 z9~4q4QVrMfDssqb;xQs^j4`>#O7yt;-%vwFwpI)MuWZ#70=82$3`JDd9@^thO@=F8 z(m>LF0o!~TnCb^m4S$gl^QfqViE&}SU-h3+8PWCkrOP{DipTL=r<#zQ9lx`-D53L% zCculnI!4~lLI2n-1%5sPT;pBxUv7?5mm_*0{LOLx^TD6vEr8D-2>)Ms&~)=NZp_&Zvc{Ka0B{ieN?$djMs~G=`y{Q^~gJ@Q1cSII@ z3+#0>u$g-ETuP!x;?i86rx8ISI}@iCfkyy{;Op%Z>cs$ zfji%?inSEfic7ji5%ac?bz!yqAHCQE%;Dm)%jkNKy8S=O_$mdeAK!Dv>Ns*<|JfLR zZWr?zkC7@(o**3(Wh-r zA6*)gxCQ@t6@6EC3rHjJcV+?KF9Enqy8HFMtW8c;v5kBtuV(~>zjK9X3g&WX}YH6y&kQ#)CX9b?Atz4q|x|R2q z&tzC}|87kLX~m1BKCko~Y)$m>CdkKRFUP$94{{tJo$z)}Ei4_e` zyFC~zR`^)S#43MT`FgRfA~8c!=M}KqzB@goCdkOF((ks%GAk<1n}+b&jZ;%KEP2pa zUGWDAaH}PG+_FS@(2zTHY(s11J-g8+=JL0|&S!>qpIB$weJaS{w=5;l{K*b5%?Mw! zhV;fmOOD~0*K2mT$GUBWiAC#MX~=~$3gFG`>(6Mc%?-1?jX!JTl*wN zq7Hr5>M?Fy?V-Eg{`TB@d|cjciM9PaUwLKy!K^*A%E&8XOuqfF94ou@0ya#iO!POR zcjjIHWlo*BwEu-*lP2Wpm)q>VltG$5uCLy$tUT0Ei{f`S%fCPBl)EbDc`a>XHe!A9 zp)sYQpsuayVRq?SlY*v`RP+&36phDt=d`E-=#I$n9YSQ$*Y<6MyDzA%E=q{x8q!z8 z(>+8x1*8#egHkZa=5)6h-9x^mnP^YxWv6ct|BGU}A?ZOR zza`VLFAZ4i>@#8O@eSEk=>v#7g75An(>!APnGEQ>j_SDMIQ-rEZ|I+2mC;Lc{=Zh< zv@h6lj&J^jeD!Xf#-@2orod|&%)uSy1QBh`c9QXw0EW-4B{2D^%b!1nSWv_!q|2Xm z8kbz~8}=H8@l~niiZ{q-4gq%idnEsN_tpH!=Ew`%5!-h@m9Moty6=$Ch#5pVn2^h^ z_IIqXikG~fGIo*v7(n*#lh-z%Q%Yx zk#I(jK&GrG>>O1gPCyR(i@J@y-aa+BT@*)zc^d#<}_+3@<%k0~8*8`&V zhRP#y;ceT`To1y@Y5r849^MxO{9h|1uXG%IalQ624apS2LD@0_7%; zoTEl7UvK5ry%qW7IbLTb4u>n@FqUsByZbd$MfI4>Z)taUQd5ody;Ev3BzT#wW#!6@ zEq;tD3gu7#dAkD;zyJ^uEByib072X0j-t;HSnuI?d>y16Hyf~b z*FOrKaaJ8q2j&9zDyKfYK1#l}8{0xJc9EArT_|?0x;A8ZCeKLpo38%UD2%Eov%=}6 z_Ov}d;bHf)S2wL0KBox6i?>mH(YnwgAQjPSp1-|Qs+OREOO6QXei9$F#m;`6SyRB$ z?!&Z0)}OILiFfjU^@^jr$dI*!{g>5a~d8mTX) z3p00L*#7Kv)ABtwvdgZZW!cJ_L{~etc1D~lJ_%CjRKMr5LdJm(V+YkXeb8Ekd{%^B zqfzGU64DG#j~ z`AxU&+9C>i%8Z%=uS(>Iaib4T+c?~3JVB*k*i9;lON2H1r3f;W>!G+)qcnY`3PehV zZGHf#f3=X+4@^m#)zE%U3Rpu%zXXp$2fwH`eaUJL?YzfY#3otrM3wc_3tnj(*t};< z!<0u6H$(m$7`A21^jV{2Q=eqMo-yqVq|D zHTGB#X()?UminNq{-72iW3B^V37BOEq#y#y_Uo_w6(wL7!K2aF2FpIEF zB)F|qkG;L|nuf4i);JF7bHiE8h-FzSsONZiEKk-sC0a@FDB8p1gQHUT4J5%OsxTJm zYF01sIEtLYv!Wz+nftRK((Uvu0HU`H%juS#7SA@o`|w>iWISqJe_W~NM0+rq%eqt_ zaN@{cf4&nN`6iw_{lWk5t;+uu&MWvY4!HkPsONtuszdz^>sQy0Kt4YRqZ>(h4mv%~ z03sv@PC4bM`UmpvmM?lW7$`;;%eeHt$V>EpDe|Hgog(U4BYFB)q5&V3K=IyFM=~V0 z%KwnGqrhEjLGt2$+&e@dmgE>UJ_5|QQYPOxpGM`E zQT4>K2}AS0@mIM!s=!cSHCvGaUh~*I365QmwH+%H&mwl7mfhb+=Eh^@E)^`%mhu_W zQVk5H4D_z1@0+>vSHz#8d=j z*tmI--qVk~EoD$if2)7|Qc^`9k+`=rHGMU^v8jKR9H>|?qp*c0e{v483Qwzhjh#rP zIn+~4na!=L!XITx5HPYu2Lg&@VM(mZi)fLYHAV%aRpX*}G5yf|m$$A6t60;;2 zK5tj?9oNOHjgbP$A_tFi1f6K_3P**ucc%{B-SPo1s8&fTR=H*#BbIv;W?o^7zX%fs zL_!i2=fr0_3KMdYE~vtW$^E@DZ^h&((GJ>vFsTzaQAo&qm~m8m`RcT+D&ACAI;(Fe zjI?oqb`CvbDyVA9D3<-cB%4ZUh23=jLYj6-&AqIqZC&x**byZ1x4HsHM?l>q-K3AC z(uY@%ge5e+x7qWVCrsAw9~5@;nI2HTeyBtg5KqxXq^=|;b?5QJyPqG~yU2)$3#9}E zqZBsBj7f(bMHxPH*otaY!kXwwQ+VB<%0%aZ?Q>G*i$gC_nq4&rGB1q$)IP*QVyH|W zbrHx zSGj!zOIaRSYMXhm6@hiXg2%808oHC$BH+`vC(?8vrX!BwEOPXQQA(B-V{MTspYRoE zy(2dZH<^bNSNcpcN^3dys_%8Hrrl^uNGNpp0J0n@jOWk(U1UA3t*HJSb{JtXH(xiR zACmD5llg?J^l*H87#0gXJSh&^V4w5%nGl~K)F$m;gztAn9^eNM8R8{kR{nFoE-RoT zW20v(drp5~%>sxuAd2Sg%KPo<(&8X^NJ552{VR%&(uA1TakLh;8pw()P7%!{v%BQH zE$t9PI`;dXGA?`4+bJ(STLnv+ezywUAZz004*!(b$DX9Ki&yHQ&0wu$WiUygXPz>( zo3Owofle$eADg<@kt%FgTxu_(tw#x8dR(^QGZgzpc0sx!Z07AR$6Gy}plnvVol_lS z?RvN`k$OYx*3x1z9P8z1OP6Wwv~Va68JUYUmYQtUcj>BbB1dr*%272)PY;(|-6&Qa zxbWjm|3K=7WWMY937=w89L5O7Vh(!S;@TX0s-;%cqs-Au0tv>B(;~OelY~|UZUvw7 z+(YZrRVKt>^Tlc6V3ekW8B3S#@vV@$u@@{LYn5J=KqPJA!sv+AL~i29FxuQeKRWxq zauU{SNf3A~zPIP#7;4zr$Vf@e;s9Kmx}TPY6@N!?{g||7KHGJT$OP}FU`aO_`DB0m z?rZ?s`Qe;;TYXAFBNA@W*1j7>A-z2@Vl_OU3%==2N;$mHz2<9DdCO`bUx6Na7oj_H z*VPxbeCj4k&TFX%HTcTSvUa_h1ipeHWN zX-GrMwguD$()kcbe9{5t>>9gP>xQ%6O{*~0p#HdZi@iisSs%;GtReZq78$O6Ip#>% z+Uvv`5B!okZf9O-tIl_byk4oE3E5C6V!pZQvfam?zKjr^4_=r`ud3oo6w$y2YPF9H z_hdZnDLWX_MrBBVm821~O+xJ5#3C7olcS{~U`Sw`%&6_C`u$8k8ioTOL|sA*YhGoD zm9*_MyfJ3SkBDwVM5Ky|^81)B%HY*+U%__Id1nDP>E`C3m>-}zU7{nq5JGD)x39bW z`$XD(ewj3NO6IV<(C*+;9`wP^b@WuW*Y51}eC!2CT%oscs*yh9G@S3gOkA9-rKOKC zLX%gh%E^RY5kJ6fvCy;To?(GVQwb-7Y?w2(09!xn?O9)#%Q3Jxh%a?Ha_PdwL@)-5#WJp|-7$ebz`r_j8$RARcXBH2n_vT=dD0d{}_61j-wkXybM{n9w|AhWyC+3s@6t}y zD}Mm$S)WbS`f*L72hh&r_2R^lcczQ(fo_ENMfaFg6QVIE`u_mZH4W4O)Og0iCXUUo z+3jXGpN$zl2h{xg-Z1he)$O>zitG!{uV1n!SxiI=pCZ3-cbt9Y_8F(9EY^x#Ek23T zeJv3optd(f30zjp3(1(zOWS>0exk*Rv7slfdgZBi8E#khBeZ5?f`yYqPDc2CI*?~N z#QZVu31lwxdCA>VaX)GdM1QhNLD!%5PBb9jwvk8PY_zqtRnC`uXx3Zv%%nF#gRZ2| z=&Gx;G1X>QYEwawep>Av2_s{wwtzCel)k;v#c=M9=6U=1{+@hO!u&^6$U?(9Ql9dq z`re?TML(mitiH?8B(z+ZhC%qH(Ii?6*jdyN+a>-ttCuyBFY7oXlt>aYxEet??+PwgH>LVp5?I}+bT?ng z!p;ptGLn=wb$>MFb{ndv%-(}7Twb?7_=T+V>yQCaP=7s=5YjQ!F(QzIc9&VmUz~|3 z41cw828;Zfcrb6tm%g~24~vuF9#7(?b~tsvys<4Z0#HsahyRf z!2KlsSJac;XMVQp&`sROUD z)rHFaIOm>po^lABQb$_`1@#k=z{N~^O7!GFW1G_Eb0s`gHr5MH+B%J0(_AwHPM0ze z>D;ZA)^W1aQ-?hJ;h7o!X~!UB$p0G%iD2>fb>+7vKX7(9+}z%S7)1TKN51F2{m9>1z@eHYVe${b9$C@X5dQw1uV!D zRR)tpgUjwT5y~+(1MCqArUxc7holhdxMWTGwyxPGmf}=O*J6BqyytNBLjO6!HA3Cj zom_^+HO|_S4F+0dd|VAoO|DpNo(1Ll8S3`Xfmt$mE&4^gaPgf>BGdEZ_Hpe)fjUx> zb*_YUH<=Z~#;&HR)GOOt%7zsJ%y)l0?~l`OsA2MLH#zo2*5bk`&t- zhsTs1Ob?hcnnL%A^`7b)FY-#78u7B`d9Z|91n%RPAI^Q<8JQK2ksj?Faj|06*c+DQn&@Az#dE)Uy~Da=^`&<3hxEW-d(yv z(zk7ArzvLlNb8Ap8Jkr{CXak$4o{SY$0%|e-|Wg2JS>}uEH^V2i|;+LKsC@G%3c=V zU~dUlh`QOhwmK23bs=rY6?)Ya*Euocz7YWm;U)}Q&)?1o54PwoFn_eSc<}XbE2K0) zbUxvNQ;6)kC|`jIjjxPfg}GF8I0Jp#ZPhSW&{J~`+(Stvp&XHJnG_0Z2Ekk1Y#nWj zuFI{K!@=oGq|)jXNfvvM!XV|m1=(@GJ4}qjRC^#lq14{w(!krQA+AheL6Q5(G%bqV z3*eOzDg2H=X`ZDkow$pPRyYlT^6|4w=-=%*WGTzs6oc3u@W!Vz?aA; zN@Fnxhf^u0DuyZK^J1-ZsAXD6okFqbXMgmsAVX*&n01yy6;Mxayvs9}3P%HSVyFk0 zW8)C@z1P6& z^#_6gu7YFbK7Z#2rUH_SaPRD#-knXCNUr}5JGscO$T80P6y{Zu@C1#9oKkLpg?9Yh#SlT?ROa0LKAJvR&f1x1h{L9H>VU~MCxB}$&H z?zPhhL8^vub$s^=XX#T**UL$~vL~a@-lZ+Ndooi7=A!j{)@StI3_pix_u`v@1+c{A zO(>jXHf;aIB1gw@Y@dvuA zblp;+lpSqNh8~8*`xwbnP(9hNgsRc*6Bd+9Ya~QfQtlR~K)kh}4MI&7=^R`*J@@D= zm0A>?I-NjT0~R#=08^alTSJ0#H|Sv)>W*#0D+l}AWNSztr#=b72dt%HM! z&1b0z9Qo&+!&Wo~_Ih#z+m~Cy!}48n+D5jGx4#Tor!OcYZxEqJM)wR(%|mJu_Ji&> zK!k;a({7aB;2V>eKd~XA8OW-2^G{JJ2^M_W z#+0T=l=qfAi&DYMlyR@!tg^-7!GF+`|pd41FuJTF@Wx}z3n~*k6 z0&`>4eI3w_T7%z_K2L2vNBHd5axbqvS~wrkhWroI|J zzTSRwTh2kw{wt>QrqoA@93nYlleK}%*0L`Qq z`NZaf>As!>BZCy5sh}Y;frP9R^9sjWQZJe()Y^FV6aM&FZwhwYg_w|cTmcMY_-LC2 z$do3;zWNR^`a@$mP&|63=g5Q~RDUN{Yy!LTNr0s52j(Suj*nuV9uU2@p_+F%5z4|i z!cYmvX&D^}>UPYO%ut}V>e!J4Sk)70#>{#YDQifu`sAF`D+;NH098=kR*aNxU%I{OWeq%m*v3mZ{oOO4-aNVG*)rok5W64zpGD_HEt&$Ec`E$}S-X<1sc7aA{I#UZ0AD$uRalaXJ? zgx@KHhL>&jscZ4GB(6iQlY$Z?{N0pr!(BY{qzhR6&5nV3m z4m_I`;gEIk=wrTI$;`BP$rNsf=*{5I(~psdpYS*G5sq)cIYJHS!?>M7U&2ij>ceq^ zH&i9k7#Eneqz@-bc|1nQ292;$dPmMArF%8qLS{FlGP{rF+-A`@HlzIVg0RfipNSN@n-sehxCzOuEp^MK1ZChg&qG zDVarts%bUHE9weqTn2&J|7e6bufDHvV=t8ve7~HW$m4{H=0PzD3qIoym<61V>+e;5 z{`q}eVhw5tF;TS~d$3C|iBkII0n+^^YpVf?L}vc!S&aZZS=UoavmTyQC3<;wMQyIU zQ*(KEv}D^xmO@gBwC*|)LG`h|_4&=)#C7Zu!UBK)YC6IAs%fL^GYTiWP!ba5!GuIs z8huJ~6|RuxBXlm|Q`~~$zMxgyFCYDf21^Ccb7pCyO++xS2~(w`nv8AZGcYb-4+v{LKu&k0rB5{pnz{&>-Qf3 z=nUo)-vH3ez|Q&B=b0xAZX%2%AZ|OMV|W0)b~26jbN|>lhabBw(R2Su!3U>dgzgEh z7eFB(@}Isx4uhpcpXk#A$km_Dpf1A&)-=b9S!y7-Pn?L8UIFZYwMpH!EL{^aRB^KZ zgL6mr#ds4A12@TDmG%>-Uf?@68HNL@TY-_{ap+Dy%XKmn{L|dds7=sFWyg@=O8blC z^G5~dXzC_26Ob`EgMD_Q_G@z82!a_0IvLp)>kku2CMIaXX%lS5()qZi+swK-f$O<=hs0b;fa zWetCE6ojT8YuzW{WA)11HG0>082d;{7t^2&#A6%yOlOaxNqCK*RajTFc!lgHeOfSW zoax_O1!|$*(5gMTygNe(Vt)kJJ>NFiQq>wvD?wgeqY+@EnYqleV2u0mj#9DuzuEDSa1FNtKB?PUy#J+n&|Uh0h(%an*6ags+j)^47? zAl)!R6M)a9zV8(Nhedum zqEXYrZ$DBGQ_$b*Epy6F>fKl`B|BR%5E@mN7AgzbR&wYUWoi%SiqKTK!EkqrAk_eQ zDk)ZV%UxCZ&_zkwJNaNX${ZWeGoP@*ig7Dy_(L)sj2gS{?`ON{Y(P$0lCLPf&Zk~o z%td3M5>_suenUDiEPS8An33=dx98H+%-AtN3|Mw5G?Xt72U-Vow(yPqN9n54dtdvu zS3xuMm7Ks-y^#46d3pPI=X@8KJytaWf5GAfCdUho)NC~AJsn3(L|*BtzMqMx=S^!{ zliAJS3R3mY6*C`>JeXQC4WH)4Iz`kH?EOcosHECVP)VA(LVL^I&CN+a zr51<`L55@{@mhDWa5#lufC_S?`}72F}Cw9~g0 zy3HT)R_1^~RpR%>s)Y7D1KaiLc<5UqYz%x=IbfBy?b2-Iir9m0_mq`fXh^~OrSw6= z)6g|Kt-w=PvYXEhj_2V?P+&bON93}|!B9I`pP3U`+<_?$7_Mn4e}f=llEgS_>MT5! z)ac7&w@p2SD^GibqzqVAT00T(E(tDILP z_DAp{NVMlg_Vz(osL$7l5we%d|@ZYk1-{> zA|SFKwbTDAHi<6<6=FWUTyOr#7(h6{Q!2CH-}MNG>0${6VcR(Ey+M612PM3k)Lt#% zFHQuM$&O_wOgW*E)fq_Vbi^n8ZAFV`8rh>oHbKiQLEUTA($c)+y3Q*T;60sUZ9St@ zE%0zt4Hu0FamLQB;`~Pb{A!^oIecKS=LAXpv0l}GcJ6EwulWJb58uLCt!Yq+{}YGs z033H)sQ}~aZn7*MA0?OQ6wG$KOLLiCMYBp)1@a@NxQL< z3VC?c#@bhU04@7%e=u)>`9HLWl4`@j{cxDs(S-$a%C(lqJQc&`PSvdis}4(Cc9p zmWVl7x7JsT10jKFis&;>KdvKuI8W}w0AOqtfI%!~Jk~jDHz(3WhMPqR;)o>Tbcdnd zc;Os}GG{Rg5d?p@Y>|yKXd1#n~4H8EzSq zg>AN}zcmpo6{-?ouAgmF)E_b?7F?0%o3~qP@n$ zE6NRQO|E;HLE3_CIZ)#yrC+`}ef|kKxFG}mc~KDs=|VIXd$<=TsDr1u+JZ$p3-*`lP3TH-O%~V*Xdy7szRK9!=Yb@f_^q-y?>%Ve)g%5pC&`B ze*!J137E7Kc;^^z^n@UP@K?ZO!T^N8i8=Lo;HR%INqhb3yMi?5v0&6&)M>5&YGB znMFp08i9~ZqfTYnCe3s2#t#$n<9inF$!DG9Co#+__t~BBAmne%Y5#dO=`R6fKn%*f zKYHHFa_L39?|PYyDtcGDZxkNF&UC+R9#tIivdc(E*+`VIlk4y8lI#f+?=mve0`CsR zqdG>_b&}m$w;aM>$x^kBBMqYJJoI}H$NG3&pIC6zE+h0lu+~2bEK{AOgCD8cj=%|P z2ScQ@8!EoFcmNipyDDU$!=YgvY{jo9hkI_j(i(3L)+{$2V5;M!Tzy~_e>-`aTTtTt z+C1#V7{+q*=FWMRPSr5Yfx&~Gwr!X*cQ|Gv*mxX^^vqb3bTwagX(KDDbeX;@*cQBt zZ_YnBAk?r}>BLEIzw0F<+cY%agMyiy4hNq2X({&}CP9PpI$~PG8Oc^1VAn|4soMp4 z;geUWTN|Xy)7>^Vw`(aWT{d6xrHdVgPn+tI!wFbJ^RAu*v+kxsW%kf6YGYbzrGlWL zMMYb<24e&aY{8*dj)h8^jdsir5v-Ssx9($7s4{k z3dLPmPk+ys?l#kr&gQG8<0E#fl8|6odMClh{!+$9=c{-Ev>3j?aH~5%%HGLQaP-mcZSt~;mbKtGoU+``GAzeBVUOUgM^k8)+<3Ayx;TlhD=&Ep zz2*JZ>ejJg&_tmt-krTlVox%gBZjT8p*ik?^h z`de129O3AxLzks+>=6>)VeO=MEiC0O&!GilPci$Ep3#06f(7Xi)CSqlJD5&d*{Xx9 z0?1g#kwYaSO%+0%QfldlP9(-V>LZeV7{Sja6#*N#JgFI|HAd{RIk_}g<>BAkn8B3* zSB-@;m=baX22(HdA=c+#x=o|!hvMHP9PE2-B#Z<{=EqOot}(&=ktl2Tn}Q!rjo4o#$tYNwD|d1VP~p9wuS5m^z=ayZV{Wr!zigS#`T zo{;6{h>peJ5n%*%$2f9!^G^LnjS8-;#(mOBHfN-xxy?P#l}dJLSH8>0d>A1C5WC%R|0S-7v8g=aq&P}Ms`K&r9nPOeg)g1U3%Nr(v!&$IyM7zgnar$R2h zJ+Vm@0@4Q7zg(3JbDOx#8XukBTFjRDtTH@Y6d(+b)|-1WeB{dbN}qU(+%ct#8TQCr zv_A%kLDV`OVEd@N>O%1mO~dlth%keRMf$3b+!Z?$(dAgDVYhh35yC z=ScU8H1b}W7HqWu2@%yb3;u`b)YwmLB8)?jhG?de-|wujh&x$%%p|>9?oBkyu+t!z zH^#?q;^7sw_eEz_r>fj#F4J6h{C`M$&#LtO?n_KkR?6c3Xv+fDgGwA z>haSUHn+B%j2x|hFs$oG*Y2flTdt+?x*^_L8Zc&QQ_5iYyG#^HP$}i@VVBmlWtzLl z&b=Kp?cIb;d920BOfL?J-nM8fAM}aXl(*BPFX#C%stn^auFU+d*76nCPxF&C>eg%sDiyAqM zNyWT8T$OKIEHZ`4ti^uao>_SdamNmMA}?e(caJ&q?wiK79BEC?XMB`}>;)YkewAKh z_7fMl1#t1^>8hdpFgh~xxAP`DqAqhK*0KXTK|?iT^m%wwSv$pEIxf02Pb|D8hb^YH z|M`gL)34yRT&ieaUp}$Sla+7O#q-D3^I&Rt_5(xf9yOCz#}WOH(bf6nvn~ zi|JDfStNdB4mT|v^%3409djNlCWvXeU`YBSeN)f-Y8X+*CyS}C_t z=%ed$+#T<`;^nNj0*Dr7lXy{$anUZRe=chVK>k#{tKZ!@CGRXSioeU)D`9{fb(fl^ zmW|Go8xDz{PbN*KHP2XpXc;n)XZD1Sm*U~^&U9*w;-4K5n_`!v z*ukQ@!b|z=hIMx^^^9J6$^6zbF?CBr)JE!zDDkXYJ8^~M`=~2UM5{mLTL8Bil%0uj z44-tUXSHlR30Fb4j5-)zBk3W_n9pqQF12iX!9=o+bDW~$VNoiHJtdU)YM!$v#T$AY z2WK9x2t&)-YZxZxvsMbW&z*y8HLX@T+VkPA*dToFW0%Jl*{MZ2+z^B5b`OuWFRJf$ zIfPc{SQbD<-KDy^OKs9tCCNy-Kw)kPT8?Q_`}NbF#`!Ztl(OxkEKBk9?UZ&QBx)!< zezdJe>z5_(`~)M0=8BQ_FVGY3?)us##~bTB`^8&%!mYk}wCVN_WQRVWm~aW6b`*7W zVzC8^u^B^1+e`R{AzCK&Itp4Kl#>wkgLZb#Uw)uS z@U3^?Zwm|mOzNPWN)-g(xCibC12Fp^OE!?@1^(|@-ap#|lEgCvbUYE!URYi5zZ?9| zypNSf4ZxxG2yp0sV9WggGhYP=CjMu-o0KLM|CT8z?(cA2?jPa$P`F*ByteQMi!=W9 zD?bmEAo{n!Zv$t5iLR%SVN(rA(ENP~EDr7!TtK568$o}3(m;US-xxg~PA^`BiJx=+ zE4zIE?mx0iHDe$Jt0zdo5|m?ncNPy9gA~(GPSo1t{9a4iZpVbpl|lstJ7KrOpJRt) zv@Hd|l`IaJFOm?dztbP*g_6*!&88d(L>-VBl~(hPNZtiI9KnvesflJ37yvc*#lN5F zQ|43j@Q>^?-!Afr#$t;$Pp;x3W)YLOn$F*ub`0x^N?_X<67zm;>gke&OXT^kqVTuc93y(UR_Kp=|n6z*Ev+*DN@ z%g8AQB;+?P9`K3-HiK>h{WK7io^uP%t)dH%egnE)9>kpn z*EPf9*@B^^5uSESDG#Om&-5``I$AV6_??x*J#7bM_2QthKBWqTes~GkNR41%6QO?h znr50(Q+o+<8=#t-DD6tO-@wNE$QuG`KRhE$a*z?Cex0A~mIlW#C_D6vRb&=pZ`*;b zln4{Q5l&6G^@|-dzJ9V!jFNlO6oSL*JVGYasCp@n)Dd8Qo^f4+RdB;U0nlxWYRt?X z-3BH%17}UuJXH&uA8}hLfBO}l@UaPMx~OeBYh)c0ZFEgm=1A`l@?RP=hqrNdqTd#7 zjlqkbDM;);m2qAO|J;HB3rOA$0%FQsj63Oyhx@?>?c^ZSNxgMg#UkM-^^E&c4UeHe zkKwnOZ>jJpQVx(i}s@ZrN!w}E&uj|G~z_LaBi22Q$5bfVUke4K_~4Y?_r?3|;L zk>#t@Hoeupo;y8{d%0vlkp&B0w$q^^z2)-v8%RWidURH?jebP(czOG;5%NP8t{RBb zeYs6#j8lD9Cy`eAj%#H4neJ4H(D+*jHGjd0g#ll&NLo3s4OEv(g@NoG>syGRiP99h zTHi$W57kl0;$kq<+4Sx0b`$AUc-rG{FXF{cwRdzT+oJ$VvfsgRW|rY+LU892tQ(`~ zJP>U5z!8vlvjRHx4eh-2?be9mEexj%^}5 zf3-IJL|ESX=c;zc5x6CSsF?_NQ?243R~+}#*>=+Of0k91EC70t=qzPL9076g4)Gfr zG^g0taGSe+Cp6w;VJ{Fo3;jw`Y&C$Mo3QQ>A+`a?&ede$mUS}%Nz~S(Z&a6iF`Wa_ z@+{3BkG6T)S}tUzUYl2Cq?*rF4b9EX6;g20} zQ2CLO_6lxW){}=_Rt$gOMSm_pGL|K%cl>|gIAe8-Y{hfJ9aED6HH*x=NAVTe_^-{| zW_-k-8Vi3C3@!t`-ReB`0^L3ik`k73vd{`=;FWkqNfM52-igN5epotBNfPmuxlL|3 z0Tk?FnQ~o&jXqB7Z1o_cl4ATMI0_yBCZfRED*gERjKrDjItl@aZ+Y<|l`S89!jjHp&@m~k+RfH(GBscFnNY$rcC;Q$QurvqjL;o{b*8P*E<_nn_|izx}p+ zd(Wk>J(J2Pn5wew8W+N`|v(l|I;KI%?VG zE)&=BSNpU%AJr+oyb?P1PpOVH>IPkaN=gsZQH*6*8r=Qw1G zy}qXmQPq{!|AgzV_y-#QJR09+3m`Bpkl_v|u!zO8XR~F+kYv|Yl#OlZ(&|X-F|xv( z?Eo?WiU_-))h=rd@pCuPcd^4RFmJbnjekAq|MDeKGw3;hT`knb^Jj<{=~mxZoT<4p z5iRMwXha{4Fuhv@z3+4|33vG@k^z9dV2SGZ-J=Kge&@;12CO86IK>=ia^e z1^>Y?WdJ)BRkfjnmNEPxwImR}3!f7sRK8=rHPM+2h-N^1+L3Lh*GF5{R~8@!uM<%= zur@Y73S_;P^SYS+541Q|H|EPYJqheiaN%^h#gd1*%RYK8G(@HNunyRS?EAa;GY<`5 z`x~U~%HgHAP`@2`$WC4=-`*t#`E&sVWEIE)SUV%uYp9_=R?M{X(;T(=Hj;oa;bgIAQHRK zk(OTOcAOh_A08fgW(|6^GJlGKcYEh>M>eaie{munpRi`y7&?*tQN{NWPZ*p__xgAy zKC4X^o*f?b<^6!u(sf>R!CUdsJAO8vb&hQzyzbpw(}lZoZP2??5Xd#@`Gk1>((d3C0Y%JtcsJnQuuNo6WQZL@zIEglBQt%F1&moK~Lx(GuN>Q z(Ul8^hJ~y@q#NJlj6Bf(AG$N5;yv3sAl{xes>B#585nBgV$ru5I$woOy$+JH)eEQ7 zr_5-6)z+Vu#!j0!afLGi!loQy2`T#Ly26E@t^LBF47VS1)n|#kF-mB_|m&HLj-jZ_Tcas{4r#@K+l+p zr!2FgHG`K)oPf)FP43kpl%;qp90rlz<=-Eng0D)Bfe))hd>1k4-h2JjWAofKMr)nV z+&k&0rRBBTbuCpwA%W4=j9<>+vy8e=81J3DhB$Y=h*Iv+FZL0tlE5$lK zV9*AD!QAMCM3LHDk-3+{&d7=N?&9W48hB@cwpV6Yxd~y%;I#pf~c*VmHqZg)FFghVjE+;g>$SVZQ-7L+z&ApE!Xgg%^7Z2K`% zpnZg82@ZDET#cU*-xbD=PFUF~X&>&he{FH^eD=6bs>1Jljcnb8fxXO zd1WR1SPQ+u_yx7TJ}Fp{C5`nNq_po*7}u7ZVOTMI(tWtju$^Md6Pz%wnD(xe%dg(u z`i`%atiT6xLQT~-o!({~D_cb9*Px8NkHtp`?dfr;ILOlp4u}-Xg#(W|iv2uLu)H4x zq;J%tYF<~vx(eNXAW>8!Wu)k#r8e$kdD63e*p@jK%S}qhn6CPz9*X>ScMJ}pLk~NI zh~(bxO{L^r+v{YvLtcg99*^oyo??JNeWG(m3mrSXQEE-IWJV-ILgEIXI^OTlETH&b zAjyM$$se>Jk$=N!ZCP$IJ1jIR%?{8asY$@OJmU0rQ{Rt2_0hM}!|dwdP29)ws7BlS zMjb*cHdgNYU6#ze>GsM9i>?`qVJQq#JScf(^zHvOa2Iv4v8Kop`l;rFU|xL6&XYBM zGLL7Eq>bUOnaiL`4X)_^#^_!UGIsFArFb#oIZhlXQ%v>Y7>om(^h37gO-mOxC+0$^ zj1&z;S?d=MyICC5_NHuI7}xv8T#fS!P~lC^(dl*XL{q&zWlNazZ~*|FI{|=8{G1J9 z_{FM&FJUIVvQ(|C+Q_TOlMyXQbiUG>9d~e!3!Z7wFd@JCWO5ru^+@)KrSzR@4ARA; zPdq<2tZhi)Ql4cyP#A1BDu}NWFtS$}A-Iii4~eWzFODoBlXL_2dppn#-)80xBfjF9t z?ZJJL0o{jJ&++6(Vn%KaiUSh3q(a!_NvTv~nm}$=UpP?G5l+KKC2!gM%Id+R3^yqc zlYhWc$BBf zf?hP0WK(Nj*Yd$>%IH2R0qn^CI%bJtnw{{ksbd^I!%OTZGwlY#jyiN~SBSlz}-R~QC;Fjhu`QQxbO4XD`2u2aT|5NHs94`)y3yhxHzim?_E^C(6!+;NX@*VMQDZ;cBfB zUD4%#T^jJ0_}ys<>CqKyZ!sZZw*A)--jg!2j>jmuWOv2z2NMS#f{3eX!sfOFKM|o` z4|2kPq81R~@EN95!{+j?%)mj??a7RmaA$+{HHqAv<9a}jh@M1;RtFS zi_BxbSYj*s+Z4GAP&Rm4$G~^~N3$X#fJ<>a{_U4JG)r@(sZ%&TCY8MtwtUi@2fm z&I+qseMT4BS)OznfaeJuHf*Cv;%g6zy-oWqf3X4B1Ft>!a@4=m3D3&E6u1bD|5f&7ZzcmBZagJFRoHnLsQx<2-)Qpvb`0h1!=CTS4OM!&l_$O6x2?~h*S&|J z>&%LMP)87Iaogb$NT|o|kgY9Th`fbA1gvZxc{2 zK^XxN?ha2)^li&k(`gqTS?wBnft#uwu46o*(Q4FhTqjVWajSUFk%oAh^(5^zAf!vW zxx0Dqcp+e5o`0zz9vF+%F{x{zi%X*!n?J@35z&k!fRU&#Je(Xv1RuxoZ=X=>Jbjvc zG^1hi4RVy=TzCAt1a5C~IUkQ)GtqESr-B7<0|JF;B|b?^dfrjB=d=0(LUmJJ?Kjp* zdfTup=(ekX+lMtQwOGxaR~C!RiBPnwox*BmCRgfMGM4WiMQbpaHnHY+MR^U0dT(DF zLZLO#2+4!cWS?>=Mtyw{kNGbr;$^aHZS*ZDxWlw$3v&1xi7g121EUG#(L{A&>sh_H zkkfTvdqj3{#Ef2+*XCH4*V@jRZ^on5l&y`pmjijEL{$7yRH(p@9q6j?aru|LUY#F? zj0t+=xXYjU)s

a^RZ`M7**RmgnW-17Yn8JST~qUo+6xMltYiSv%Wt3bjH#^1h9wNE{c}M*!B~ki_irqS87&-TqQ1Eh6i0n~V&{wN%e{ zrQO|!D>g$<>%3Il&)kc2bzOhvLiYEyJe^CqfVQM)&2}cA`(~+uldp4kN8! zRsl@f8k2EGHW9t-;pvJ&ZJz>OI)8i31aWQo^ci(Tch=Az;PD5G9dMaeN|^^)fud9J z%_;DFrx&lKqI2ETtG{CN3bF16;u$OxaD6fuE>k2_2=6;}FmJY``WMcac7v8t1iUzt zqI~uqutUV(0sL!Q)Z;2>(42@v6NmHE=P%UWo_xdFlM{0pZA)`2$H!wO@Y;Q}t5XnW z@Jg&d{zKKOxOVF|>_pW@RFa7-A4Y7jAVi!ePgT+lkos@M66pP3+e%`-BBT@NtKDF& z(qSl={7D`+pp4;2)URx-7_EuI)w*UZR+J0M4>}6VO+zKGq49f-hetIYLSs-XK*mtn z8*%OrkATxEz=T;$t(xv-PDOhohbf;TaPE94xG?g0Z!aN!)sH`Z?}D%GYeZHklbQ+cFj>0J2}92r<`0HwP+6rnxR%A=^B!WYQ6s(>G62{4rY~l%Mlj&}a)4PZAj` zPhnSqt}e)4)|~eUn>RPHGG2t&fMvo8!xr~u7i!jPh_zcZ66!f#0;VX4{K&MWxE2po zX9MBRA5QQ3s}ZD;Qpd}uE9v2Iq2F7=qQfSf?`t?z2LL=}>}IegKY-7B4gl|X|5Tp} zeDt$_!S{-qf3kA~-2t#|r9YWy{ND;bmkgdLr}A;^Q~fkA$1d6G7$L(Qow37SkpPw6{iY_+*xznecK@D;DoZ`eA*!nB85QsT4_ z9hZI^w-xBE0g5dYU;x_hHQL_P-N2Y>Sh{PF;DW5XsWseEzRLq!WlFd%x#*FAi;(QA z#qidyEqI-I2l}aNNm4NAus$w4oBysVP zYu`#V{GMnUd#damX}y@!HjMkw~G`K??ecg@Eo(MW`lri9r zftx%PP?}NXthOmpW?7VWW^G7YHGoNSBGnp{{HzHc+HA_rDFm{-eHD8Abn4)NDTPW6 z%c7wkfVVZ4ofh#A^^LYReVAHE&GwPvICaUfR`9(6IBraQGrGjq8#+EtKrj1Kd_D1y z@u@2*=ht7f6!uj&sw*9YVwA+a_fVUoJmqY|0jT0NckGvYUfsuS=Mq*)fD7WJoTdwN zf3}EF@=GDOuE(J7?lC0@O@L*5ww=6Vr7sT5#E`gd#?Z}>YEl*+j_`!*yWHKe1V0L@ zsoMm+3UE1=-w~0p$_Yz^lc$&Z#^%^pac>M8Z6b0s0(SPc**U-a`DJJFx}n4 z5JP9&_xUzwJpa{#f;MJ>(?r_V;`T+h-Voa?^R)*IUK=lmbHtTwgKKK}Wx>^Ki&90q zy>oteR|HjSti@N9giQl85A$i=)@eYUp%NRte0He zyu4NzOou8^DbNL8*$o|_e44aFIdg<3^5ysr7duQ>9L0pG-d&aSV|vH4+2A+oveDzv zmxKe}&T#_X*6Hd%_33D@7XsuW43tJ5e#su~k)Qn3NB}T+7a*hfB{3elei{bPX668I ziE^OCsXiaYc8Lmop!}m-h=NkjoDI8J)1KmK!}me>G-ep40zwi+Es64{5wl`M^dEjQ zReIHn6CGvDJ4ayhK{N)qRui=OFM&D1%Kabpa6i#Y{~vZigqJH1@^w9(eX*>% z(p>ywuM&U1pDx_)(-Zk`9x!mV7|lUYln8F!8uBRSGJ0r)x(oD7qJpLQ54Higl%JUY zd7|Yh@XgT32c0wYkQhC}S&O*PgL?{`&!Tvq%}vb|7T(0*QC!anNMWT6I}D7T(2EM? z_|PVcA&Wi`h|s44pLD=V;Y*3p z;{m)@R_eDx+f_qLGqZZp4W%Y?ydB@pr2os{fXKHL-;7&%jQ_Snoe0k*z7heMM}n4= z>8R49xKFMJ5}SuDhgKjR6<1@B<+A$fS7;61aGi&RIuG`Spkbiv(u0n_ej|<8=^%de z39+}HH}{3JFxX35m5NYb|4waZ_u@_iUz(W=Uw3gT;K8;tSCsY@B9wdQyoa0IS06dc zz~k*8PwR~~&nNm85E=a^^!x{skQgx`uu+({shM)Bt9m%S_t>T*%QptbR_3m`;Mk?P zR_*9&`nBaTXAQ>!`+1&pw?FIxAp9kwjE2)!Q#z!GW@r0Al?sce@XB)tCzOFFQtyEsFf!Z zg3e3k!?k|qkC(OuYkQBxHUQ!%Yp!j~&8~1sb=-~gbnF8}P)*&|D;-x=uNuV_UW7Ev zXTob{I&xfkQM~F@bbZ1C&ku#PJj?SD{4z@tT8PesYUye2A2F6TINw+QJB%kHqEFnZiN2Yor*CQ-Rjp==nTE>a@;YXRRfJ;m8!U>8|V!qZw|Mq#Kw7$-4$gCC(9WvsO&w@p?rWboeAa16_|9Nq8^ zne~57a)>;5pm90rsRE#i$4xgP?%wWO9;k)tsc2qNpi&vwduox1jDZ7Yld3j9rdNOI zo|6mctg_+4Fw07o?Gx;K-qn~8-kahR3&Segd*o{J&AqDFdQUf{p+bGSzJroX;LHG* zQ!!JqFs`GG@Y%zE>SxTuuK+4}<_L(uN>sduwH6;b>rYTqN^ffX~)7`w=sAD9O& zt)+4E@Alg2=qKT{0@z_R+GtOLl1HN1t0l-L9GN`?u{mxv@dgFryR9m^;kJEJxp|o5 z{JV99CDhI~)N*tfH8707_l2?0ZlgQ)XuL;!qqydk9q$LeOjRW+LEiG481Y|7a(vC@ z%{ylZLK5TB-E#qz_PZ+EeYT~5Q&EV^+(dVMeesTq_mt8qKdQ-$U_ty;t7+t+zD`v* z(q02#4@sy#*n6m}qO!y-{;|9{Q@Pe`)6nRF8O@dy3O^o-IGdDXv02@Gu4b9Pw3SV$~wB?GwYDX;O~J+^-2%P=TT8=<$PEAkqdG_V`J^H0>_Vg5&bBe!( zwgij3uem8cwlePNE-fwKU>#WzS+G2js*HLaR|9J%&e+UGP{<9-5Gq*U zpR9ffi>*O8ZK~@5^rPr1$oB@LZuPB^{AVnTp01_>Y-jKR@-W4ZQ`3uGlYm)}|yatMv9xOM4R<>WT=c9Ss=VGCJ4FCqRK)Eg>9GI6d z*IttIAnoyKvZn$VW8}xvFw%Drm4{7E9R(h&ar8Pt?BMA!0seY2Ix*+5mKwQ4Te(iQ zh-@BXPQP0nXkTa-x?gCv7OtHdtit2iHR1(8H)D3y!aY0=p_XtR@{cJUGGGo#^u$?# zF?hMj@T(N`&_fS3b%uMfND3wNp&P-t^ADW%uWP~rRdHHu0P1a$?B?KgStV{V(FCUk zU}W7`I%;u2DTxMwFZGy8dtDINumMAMeNc*iUXjlyeI*3mW=dDO>u5F?)ElwGw35q8 zy9s3Tz}Npytv}tj00dWkbQG-fYQd0p z3N~_|;%)RmgQWfydZF8GBwZsk&A{+_vho<(d2n!uOZpWPrYP6utVM46;6C4gkM?qO=4k*$&Lm?PpYg<-_RmV2uu`4Qu znm+V%uc<6JX*F$^Z}kbC|I8dDGw}5+Gv2L`V^14^X=Wd15tv<7$2Rxk?2F6OIcuU+ zvEmC0@+V(qdH0sdAbxWl&QGoR;Ms+~LPGfWoZ_EB6w*qaCPTr7jVA?QyGUT+U|ffZ zFtuq%sC=Yjl!h&{j=}xjzcXEP;Q4{t0UOZ<+zv{?cyLHrXx3%9%3KETd}hBx8*^b6 zRkYtKxcv!guP7JNm~JxlBHFZjD~-B}IUC`tUsk{OOrqYw*UnooVe)GXX^T8(7;^`{ zy#id;GExEb9m+VgM+Fh4!Xw1y^HdtRv3G1KKhl8D<+y8`sGMvQn{H}tTA+&Lpki$A zFtB*BwY$KGLRMiM!fWNTMn}8{Kr%yUSlE~5!9e?gGCymHM+p4!-X#Ft`=@b-`0+Os z2vBo0T~H_jXKYle)!i=wf8?qVaPZ#k#hgy_Br3&R{M6JLY|6o*jR^$rK2hD;db<-8 zqNyyxr0BtdF`lMS!8~|$j zp8s}z(L+rnM~r6i^K59mnD10?0bnDeOGCOjP>%3i|KN#INH?*vP|+^KdYem>IVf2m zRom42dA0BHNnCEy zHlaqb7}|vUuK9^;@5h?em2-@M6JKl+1K~KiYUI3Ps7d=~_~LOD{>^^J4cnoFrIrt- z=ULP9?YWZXR*VZmmW&i&axI6Xb;50w=);%(!=$YfRHe-Z9evFOMLCA~UlMu{siQmj`d9x&f4@%6Uoin!{0f+l~tuNx(wy z6k;MG%E3>5`KJTSPL%y-eU%WS-t<*2!w%1f*2y9T@?IBM}GuP+q1yN*NpPza2kI}sDh~b%nS6F@m9Gxm0a$tg8jG=;b!mV8! z;@2>NX-=-{nIzniX)LvfkGO@gGUq=+U&rx8F=Fl6cMG>7@1d;dGVywRSvG z^6Q6Hvnmh?XGl~pS262_eUyN^%`?wu)@F%&j<&$wkP5~p&(o;AW&FJP5>pSYB`SEu z>j!6tjxMS%`LNQUO!Jwg?w|2bz z*8F#o-9pEW3?N3T{g$co=5ndc+{96w{QhgRswGh)%f5YaftEjNwb^ZXY@;zE?uC7C zYQg~5+E!sy)ga^2%Jya7W5xsQ74P!384q7%t*z%QpjY?cBbt5pb3Wy|iRAgi3;2G4 z_#x~RB~xCl{BSpyr`7|tM6FJvk;S@yWzZ&V$L&6@KHgnrsye&!F@7yWdME6-szMl8 zXzm5K8x)aE&^ffG#bdj5~@)LBf|KNfbr5?4=K}{Xy3(}guV^P$u3}0A-27mMw}K7h_ZF%)-n6kNx+-+nmfcQ3 zYLh@})1|TTGyqI%m%vH48vW_`b!U9d{1oss_y#{VFs-ig@%w55z?^R(+NZAQc4u^n z@5Y?ubDVFHJ~6Jw7c515kAs^LtuhMRL9^&)`Y_t{|&x6%Fg#(iYnNB3Gw|Z zC@Hp%zTfxonXL;}jKf1ui)!2x`b0DJjigHt&D(KfTF(Yc=hVy|pN&35&`$hYF|}iZuwDft5-Y%V87N!QM}-Mv7!MXV*G#u} z6;h(E99nKJeZ+B42C{v zl^p(!mDFsdrZpfRd~<>v3RNxx)2<%VrXkoCQ$0=`m=4Q!T%OWDhx!4Q1`3XSMZ%aJ z$@S^)$v5NJ{_*c^@wz#?GgnKanSQ(=pY)lg5b*uW-(C5}AD>JXV>1tz%EwD7RFla; zjHw)$ThkjSb>9^p+l-VWtd09jZ+Z8d60^Hqs~k@=uu|XH3yttf`Kx~2`O{*DS#Kkk z*BnWKv75T2M7)aZ?fS)WN3!mHZDF6(q?aT#WkPl34TcvevMsfsBklZ&qFo>M zWD#4W*i2S$<*xP_Z!g`)sDo{v<>-^qgn+;u!rY{9RQoa+R9FO zde}$yCAh0$1&*}*cX$^P?4_qA6YPziYdX<0{WlmpHXaOigm_)~hN2C@ye+qP2SA8jtWT0#y1_1NmlOwQCXn zw16AKIR@A9)4;l1Yw62KP1zr0Kmj7QPAQJ?)vnD5*)VrsfSPeHA8AvIcHyeqJopwz z`~?s?rnYxaT#rYo^er)}Gr*_#oe-ews&#ekzL`=>>s5mX*@jc-xElnwd%!XUH_ccw zs>T1&!x67O^d>=e@4J+%yHneXNyHF)ZmjJ}8RKpG*^ z+9yWWj-~+qrfzfemxHiZi!*pGecSnpU8(EB+-hwE=W=ZHZw^iK!G>ggXRJy}d!B(P z+P-mUZ4Y${Vg!LbhWFtA@|=bCmbcpgRUIezgH2+Q(6wIjL+xu(ZO=nkUf+?6B}=DH z14jn-t5b+XI-ZLQeOVg!OIC^8g57lFZ7O1IN*1fMx_l2lUwaT5PW_s7+GpBPU|Lc#k1`Oc%s$^P?T)%Dh+ zoyUay=h=dzI3!7|S6Tn_mtdMo_r?aIh>eCo#i4<9MC&HDZ4>29X6m^y*~`+gu%8Ce-Q+A_i^^y}G$O|!kU z%A1sfk+G+7ek$vvs!h$j;=|l)Z2_t-3r8@DPSg;-Ye@` zT|YfS2f-Q4W>aI-lOeommQFz;z`=GeKuIswnAd#KMWSZ$oh_R8G@gp_}@ zjn?U#qJr_$Br$%U=xle{z7XE@D&0niW6!hS{5Ssoa#rR*t;#*rI!Z@-g%wK7V`|*b3 zu{zHueB|%+Q?A59ROVKtCv@an##c6>xPoY@Crc9D_pY1zCw3h?R<@&*QUT?>}zPkJKl$*c)qxGsC837IhiGko=mm}N`F)XJ!6pI6qXK<(O`ikx`d zQ>U8=5pINoDNR()C$gG_{*KiTHge&Y}r=^2;NkjK^%}o+@)jo10oqIMb5Y(2$Y!knn8+o1+Tw*6}TJfa*I! zsS<6%4CL1)4L#Slg5O6lnck0kJi2H#gX7Leth~9_3ek62h(k3>|^&DHP zf;yy_ev)!UDHmTtWIKJ&68XB}UUY;#Y%0Q5-1cs@zOuOXY>P413+;Lz&S;W_j*l5O z+zK+Sp37OrjSZ{xRp*0>FmJEKY=}e(h~lJ)X=iAEw{*WE1U|gJC#4?qZ9bNhTf%%y zT_B*M8T$M9u6qFP3wxr`b>#dJV_BrxJ9pgEI%jxyBI@;JhqvZ}cYAiIk5(@h$r*U+ z8G(Z~EDM_#bc1~bS9@rpsAh9EChLE3oXVStw-tIs(_rZ&Rtl+yYFvwW!zPUw{I+?U z{-N!Zf!TcTvEiaqLb9MQl;k*c2)noEV)!=V?owc~g}15|98f_;<{iaDCdH=Rtw-<4 zo6Dx~4>)AycBO3E+T%Re!}Pygh5?V{?_(gj>}vT-ntOQjbsR;u(L(E$eN{#FzShoU z=Q4&9=8*;y&=^mO#AMj3C46w(?)+!YURgfI$+bS}`F*?TMP0x6CBtKP>X9&NZ2+sK z>>Jof?Gr!3@!o`=4Z;}mMwTb!yf%$)u~)dg-#xRvyF(p95%{hiB*Hk@a_`q$l8ZMC zl2u%heFj2NWTV$ajan+Oog5r}GtKMh7j|8Hyu<-GGrDM#Q0)+Ix%L*lER|i+MUjRU zxQ9EId33}?&?cv9y^AiysPt?3_y^^}# zWxRP`qp%91YZw~1mi}9X>dg(4t65=RW*W`3-<`8Mc>B)bL`09Yk{PcJO5cuu|Fllx zdFCisZlTv*z&$vrbmtm<4$ni!TSmbA*Q6~HQZb7Ec846_YGh}%dVkXDybS`fx=!7B zskD=*(9LO#*Z-jDd4ljB6<1^ILK+s1lE;a@+b}*JSnQLT_RYxF%9BwN`mHQ{HJ7~Y zV0TU;PwD;RRq>0?pR`|YDDe?#U#Y-87&?RQUVH|U*SDSZ{EQNh3{6ZR=FbX03CKaQ zWM%qMJrmY{ST}NGgnu{*5#|lIkY6`8es5Kk$j2JrM{IAy5FnpS&M|!d!-7j$82)zb zi#+kLhuU{mf5WruF&`XmG}ok1_1~i1jfiygZ;3GaNarN7`rQ2^l^bFvF=ITbgO{0L z;z>-ZTXU5E=<|!bnn(Kf)>X06Mbp8+97_J^fC;?%%Rt+wLv< zS8weZ+?5DpxL4a1AsHLbbYusiQ<>SSbGNFgy2f>{?ALN`L9n#x99*Bp=FRA^tStvq_OEzo6A@$S`R(vFEtS^i+vq(eY(EANgc%tba1vceuISxXY?zolCyJvMO7y z`fUGwxurpvcwT8pdal#jD3h9>l|)koR(ZP+Bp+^WdA{PU<=hKisii8AmpLm_07j1< zblIH0+dJeyXOJV`cOf)U$yrc#>|spg0cp*E(<83Zfg^X~RW-w)wceLwZgG0lmMag! z>|OEN+EcKIOT*!fcE4Z*5%}LgA$W(rQeZ|VTBFKqGi)q*-F?y*^VuKIBwOnA#z1~L?p6dJfzdu?Y&k#mk-EMpPTkl zeO&Ru5%;>(c-SlGx=fdo*oY?gqqQlU-+f|Ns9IQl-7n~9)~j6i#j)AN3+eb#)Iu?A zAJO}BohI~&<|9Wmx|+`o7sj`s$27Dvk5c42FBNAPK&@lLxNM*9$Hig#w?Jv{Q|H@a zQPunAgCa$p5fTH`mxZp>KIGu8Vef_yY>ywLyv$CemL22_X!|gh8f{`s6&luUoGUwU zRoFM_Vk@uhC83D}q5U*~;V9E)-N|GR-%(FKYP@zBYjGyfuMF)QfK4;7!x&{)UClG) zQ#wYca9bTN4sGSz5m`PqKkB*mTb{#tm8GzPuj4Ev1FjlZ-9oLp8l)+v*8J* zGaL6ZR*up_sfy3XUAbaXyG@gKSZ%n}Zl4;Fdk4e&fbZ6P=w6Fc>|;v>DIUKHrJj~l z#z9SHKZM@Zn_G66=T9b&iwacSz2kNBd%~^yf_t_F5=Bt(m=7D5_7h*IA9nJ|&}@*j zm6Roqh>>e*wz7Riso0wiYsv@rk5NK+Ze^!8&XlIl)x?}pdqAzlF_L@yAo8ZElwW{M zv}rE+^FivAhdxQFNv3ekgbPP0(`O&>kMMpSQM!S$;pts}&CoQoS6aI*H{JBYycRaH z*hzl}c-*#K!Ftz>*4CKk#w<*Gaz8u2E515EdxB`vzz+vmBG6V3{PD*-ig(D)RUDPm z{CZ&P-Oo00r#cMrN`ClS&uZb?H0})66gxa#aw;a3%=lDT(!+5;T9 z8XJQ0oIX*^!UGwkcn&0WLZ$QeSW_IsHW(@3U%8qrd?D1wt%&-`FWIAf5BqK`*I>KG zZqf$D_3oQu%$-ZM>#rttx%3~|fc50R6lX4WWozV#m8)Q%89m6f9oFYHxN6@NOjn_D zF1w2Nd7Cl(#nSj-Hg=ff8$O>QVu=j`VUASb6MHo!u=jXb0^Rd8XyLj1c}v*TPV;6< z5G7VBlH4+7=J9gC&{uCRHfia~J9OOngEH zgY|eK&urfDlytDmf0`}^zQh>*^+UL?mDo${Am8#5<$y3{)V{BylJZx5=8(948Awg@)qaw{JNK*DfdjI(-(K8qO`sjuZSN<$sXJ32X|!$pU}rSq z(nF@zkpn+xtUOJ zS~WG3g?baO@N2tmdJE5-Q)n8VJYbiK=>`h-vJv6`i!4HicieG9ZwxSd)5QfBb>O0R2W|@sgPZp8lCzHB%|{#uonf zXes;*@!`YuDf0!jc=6w4dV)Msu?)wI`#DEC8gQ_nq&?%C*-5o9bA()J4s&49@del5 zedJL^B2}uFrhS$-&sG8h>{oPjMQ=3PG{Ljp?xmhQ#)0(R5nI5h#Y7+0tOCP3b38Bt z4ya>2C*lc{`VfznO7Nnuay`lw0(040-A))V5|9ACcF*yqpq<7$k8G)N^9Jqu#}OKz zU#q=evy$GlLg<_CzHPR%MkPRlj?kkoE@!3H^OUmZ_3@q5QI4_GA)d0wvg{4*#4fA^ zEXJk$dZ1K2_N?!!JDhxts;8Z@xW%WhDLZh`(ndZc`+=OC^H!Cff1cIhC}Y{QQzLr% z;`-n(*wR)h<48ku>$Eo$FGJ`2&3b!G90^Wxa8rsjUovV9Ok(=aL&-ubQF4Y ztxmWgEywL%H>oFO#NqGxL%aLx+rgPdK*}<(0rrEjfpIGX_;9Iw94O3z=?bmvS;3e&aVtmfACP z3Y~s!80)R3+LpgQA*8=1xz9hczA;gwmDvj_MLG=AFqu4Z@CA4F!3%naD%yqC>P~hS zj|IzSDn<~hk#IMk^+M)H?-4!|zQS5~;seAq`hq#~4cjla@+?U%H}0PEJ5_33J)|#B zZ9sM}D423ZbDe!6H~!E~7yqt?MiVnsF-40mG+Mj~n;^?fkBz8TLCJ%k2JHLLzF6JR&n?&zK8=X<3_ck+Z z-+!OH-~R1=vd^CL`?>GyTI*VCUBsF}so+2^r&Hpgr~=LPVPOkXKuEwvl+3wpFFT~p zW-m{98`MW17$grM38cw5q)b`S89mwmUHotq)tUCRWvl$#G492vog+$;cUK8x#yV;p z)~hL-JCZx@bn2@Uvpq1FT@uNn% zVWx>uU%fhcYBa5;Fg-(IVa{ulz3>f8E|63~4J(us7qI(8N6??(ykn=!NtYjm67aeQ z?&l>vI>!cNUZo;>{g#FjN8Pj#z0)!dCYa^|zbA%tcOMT^!`QRjenvrhowgb@B7nGS zj(;r>%ShFKh8_TMcJqLODC0?tgwXaOcZJ(%&EYi>hnoZtotFXXg$B9*j!|@Po@uz1 zWJdyA}eX|VNm@iPVOmf=x*O=TD@}PzS<>n&Kg4fH|T3|RY{fIp$;&JN-vWF%$4#zo#%qDz8rEEOz3IbQ{Pg3rY_8LtqO>{t2V2!JhT9r3kQj$Y% zNpaWnu=lGE7RI&!0it{cM`HF%rUDbu+KhKgWnPiUJ96*@)yiQjJ@5uJ}6GN~}Mwg9Ra+tmc zJb^x9Bk1T=gP7-U*H0TWSKuQ1ugadtWGR|XB#!#oTN9r3jY1o2PsX{N-8uXzRQ;e* z!7p;vG_|lN&F%1&qtefhvU8)~t0sF(*6w0{&_t|!2XzjZSkXU{G8B=;k7M-a>K6~C z;LDe}T9`=}S(c9tzc5|GXij@2e^OPjvN5 z{ni_tax1~hxYWQ~EtRR{!3mc=9N(0XNz1^Vl3y9|9WCEIBJC)lQ9YE7+b}`+3upwK z$=_;SL0j=wl$g#}cmIRWDm+!MiilhJdk7U8vD;@W-S1`Mwk8<^?^18EB^PUqUd?2? zxd&qmOuz-X!FOgx=oojTJ>?N&{Krz-lt<#DMWJgc;Z_BS)E&Q&01caU5ki82a8o!k zz6_xv^5AW4Q|g%890ufthwI-%h|y;sPwY0qlvA?C6$AAd@T9@~Gm#x2WowI|d1zDV zK#|9|5iez2cOUL;+;AHNKrJRWbz-}5*KEWK|8wU@7GLg(8kQBUHmA>S3vL)T9J|MG zS%X63*S$c8+WQtgyjSU3wbQYw>^j4RG5fjGp6A;Y!WO^jkSAqX&l3}Z+{&Q52eQ`6B=jogyJ6J~Jz5l_dEi_TVCGu)sZJ?_rNUJk|I&gMUr+H)@d^7UOztCea-7dR=uk60>6P zXk-Z@uHzc&d}}V$XD*D>bxf8@rrS{;C1kVHwep|4`rPf^FSW%I=d6acPY$5Zm=IO_ z!@kr0Y+a7p>LiKI@&E466#z z$|NMDAWkPJ^eiwTRo6$6i@B22{f;r_0F}?q7$rW#dO=WF^4x&&6HbKi=;| zQmwp?R_S1J48F79zBR=(ditFbe*#UIM7i*?&DnL;~eqwF==yA*%e@yt^ zgE`slp5hrImp4^Av7BFobOa?2IJv@X!l4gUO;%JS{v6**Mdhe~n1Y6+Q*_p-@)#9|o|IVa(`M+PiNnef$Uv$6vPLaiJhy** zqU?1`0Wf24@DI%hkUvy|xF;>`JI~nD8fAGOp)ANoBfbdbeb!T^nP~*9 zrGSGF+b3*bvFylpPTFs;L|6ae=iM3fL>EL#JYl*|m-SLvxQ#i5m7p}yv-i)=KT!3E zj*Pka$qMigvc7@GUlg~bFuALl+ZR$oFeQn>1mCt*g2kShPCq8v81tG;bt$euYl^kl z%=ud8H+k=YVm|>K*%cqh@+$nR>LrU4AiZCcnzp4GSpIf!IQ4}cX5F7l9^YaHevPJj zx=hGLlA((m8=%1+57&$eFfGn5?`I=23||SRS=-*uv#Ppi&{pyl4VbWmWguxs`mp~hF4EM^h~rc_03pn;K|>5;jV~+6>Ae-rgI%=a=x3a zi?l!emfZ!}el)RwT;m|+BIe7d(~U(1ff5Dj^tMW}iMMi&Gg>l3agTRQr$XWQvXT!I zCXj`nl9)VVmrt+uP@+zD_kfjz$*$fy;g@yd<`05^`Y(}!N{O963go1cMLqe)2Hzru z*j0{o)a>J!h$za*90MqifPC^fCIyt9(^w}T73Fa^3S_{M@Wp$IWp7=e=#m$S-`zPC zPmrgHrtLVnnT0b&tmSs5ls>(kOgoBpfxisr?ts7Q*92Lm;S&O@;Ja`~WF?K{@zrN$ zn0Klr)^25dL*uJGakyay)_K$q#|SIpZ;&mJNAfr1?&9p(U5O06(!rm*aGT={5BLCL zj->{%o^U@CjcEP#SDs9CGbp6dyQOwDrK@r7EFVcxxz{XUFrEqjGf+8Ucg5%VLF|H! zq~tdrzQe{5@6D*DmdMUOmdXDpOyz4Zh8eaTBWomemi^59BZ!Hyt9V{42VFm#rX(i5 z;@;jZ#9_IK#?r?Sx2&c=d4QAGPZSj;gJdS}Trqv2??7J}Dw7*}f2#GU>NysflGSSjz{>FTSuI!K$_y1(f zPT!%kV7zc>)X#YMm%0+~D5rMG!zdI1J`B9}m3c6eB-Y7gLN+BA3~T*3=`7dKQ}OeK z7|~XbMN7#y5xWK}y_Hg6Lmi=J!~+`p4JqXuBfMXuA`h3SK8jsVxOxqjmVW&;*}wf6 zaGc_a3(uWp{%rYKf0WB&zdk?oy5tt;dy2vA z(=Pv90=)eaMP1Sy&kGlwOC?w4kNZsjngFo5RZEb)T%;6-HUe@ir(2d{%yx_&+FNk0 z>H+8c0kNKUE)*&J-UU@;MyAQmQJ?cCpXHGa+ByOq9`|SRzGG?<1(MG* z^>+QJi~al(WU?2*(9M3owfDH8W&iQqqAz60JRbj&h{D}4Qi2HLcc~{_b}n4V4#8|$ zb9;NS2jyNJKGD!LHDaf0WsUx*E!t|QCROxWTf02%SSM1&u%^4txAW=ngKSv z@Jp4x#u{a&|KLzb0gP|LEeg)sciV7WB7|9{QtWPr;5n+abZJFiTV`CG>KV;Im0DcY z(&ajfMBW@W$W+dkIosybe*FH;q5et6Tl#nHC89+;U!;GIT;9O$>U@ru462B(=BAP$ z{u3WR0uiZ+vTLxkmRiYgDL0^lnt zpE9%N207@sLUKcLMMaSZ;kq+swwAT@4M?pf=! zPYRQPzUXn8Im&g(sSGT)zz7JG#+06(I=Bb{t!h5W)>%i{PC9v^UJeU`Pp%yz47rYGb&gZSXJacbpw;)_Vo z?d&}ZSjrShq)I*g;G^2N++B&eAoXWa6-hrpB5r;@x?PY5%8cpi;t(-Za1L9mF6Us0 z$aQusB{{gMQnA(R#uzRZ;Ns&Z;SW*U-%C7Y!0%ME(i+Hk96JA9c|af~&tf5&=E^zg zt8DR}<&%xlr=C0)R<Jb3OU7}s9!^-ufj zAgnwmAtQq$g|K<+g*WX_-c9;Tbql%&u`&l(bLW}}g?rE4iit8cJV;SDj4vosX!GJF z7w#ZdLSj_+ z{Mx1pCexT7+9telQPma3ycyqc+B>A{L~U^TthGBdxJb+*H(&m0CrVqjC^AWwbL>?f zlVNp&9P$~6HOwB_lzh9y5L9C0AjI~Aib{9A+71w=e-1zW_(00olPL-7XJ`1r6fog! zU1wuSsw0hNTXrd3JqMC~JFXS64+8pM`i>b{Rk2nV9xva;j_|t5SH<|hnP0B|D?fIj zP{BDT&?tMSk}MJs+m<(=Eno<{{Oq;RxMk`9zz02|nTogCgNSjsGSrRaN{n!oN0dtf zoFkR(1jx-r%|W$wQnbv2!)^tQ^H7it?Ou&o<*=BJULmOi?-*2D4B(vD0I<4lL%G`) z5#>tK-e$5&;tX*if(U~=z6QyaKLxK~f}5GgZdabgqmLnXrQhpxK0P{W0&FNs=6V(H zOm9p~8-y&K3`=eV=5YD_^Zlu-<@6(t(6X-}_0^;tS8agP9~<4bg?tfDjdx|viK53G zpHx{D+aD@=T4k#j(*0{v_Ov^RhM*Wljc1HmzN1UP_EOiEjP^EmTnjZCQQm>U7BHw< z8J95qdWgZz^ZOT{x~q&6>7E)O<1ZzLT2nv6Qf#gh;D)BX!a0|#>vx}1iaaa?x z-_ViJJ3mv2bz$&e*3^OIo;_WP7#Y+hqDU+Cnp-*I@Vt6Bzbe-q*3CD89)A8M8E)g% z&ugXbS#Zp2jPqI*WB$y^4tIJWp1tQm!Et_f1^r;`jww4nnu&WMmgO*D&~?3qd2+ZV z8e8L$uQ^5Z^8L2F-g`n(ng7v}de+iKuPU( zCqu=f^;|l_5V!PC9t_i3WtiCn^1(ZNY7k%k%2=FJZeR6NrplcYjbW0|u%RGAA|~tW znd_sGqz;AULKzX~*DO!->9VRiPUl~*l@-0Z+TNQ8*CoPpJ34o!o1yL4%}VJLaa#6c zSy6CxHE%@ywdln?USy`td*u!-i2`$O9)9;uE$v!Mc%UNUv#AT~nB28ar2ZXs=v!+n zYzibvun$40G^VoQZfRMUmn6dki*5Nue|WzdNf!b}TpZPrI6M)~-sPpO`!cHGs8xV+ zqNiE5!U_q;L<_YtI+VQ+zi09xvez$mMoYV+JgT4gN%pMpm_!Buz`+>Ly`aBT1DT;A zSlpb$fY>_ea@$!p*QeOGK$?We7;la5F>=o+-El`WMT9h5m7k>V$05h67N0ZR9JtoE z%|wYd@II$p!tnaIpT`Su*~<3Zo}OS{bhWF_q8**)_97D0t4B^1wx<&PUgsMMFIcG) z2o?qj>=NU`i$^xW?k zVdav~@XL{qUN<;n%YJGnak%IvnZr~BvoOJiM)9e7U>-GetXc4x$s62>tn#jAijxR} z03+d9_(C$D?9NX^f>D5Tez$GkI7RWsO6F6lAFH{>!5zGvzTM4F@5I^r177&yDl8;t zfe1_8_?_5nM2Wv6m)*8y?SnfWlZs)FRXy2iY3aCz`3AyE*%M|b4eaiSBv^%|D!h3i z^^Asm`TldV#SiDMlOl81&BWQ9?J7>XNxpjuhXRG8pk}ECr@oxkYVYvTj^P_F3?n-- zXh(RJm5KH)6W`8I2IJYOA)^LSr-a1+LG>veiW7dtJ){s@>F=_n*Y|(JD?4Ar%`-II z$()g+bG%SYL>bXTr&GX$v>SFZ|0I?>2|7E>gpyXsvXlCbNb3o$xp!^#@65veo$Q;c zF|k!phhIy@=JOmLAzN3+(JyB=D>9EyyNteeOi1js``_ASalEdL=c+km?>u$jcC|f0 z*2h_t)>`b)ZL7Q5?4&EkkJlc^+K)BUP<}z|q2WT*j82Q@u-El_o2ymtq zRo{sIkqVyev+{XQsw= zI?pwhy%F-Na=ihF^mOa6xNAI0Xf(npMjSwbHw9!i#*9$iKQ@aC1@i@m+Y-0$P) zbrNxIyyTnxG9-`nW+Qk$SjWwv`$f$0M)cqXKtT^L9IBCvxGv!uM;=NC`p+>ZK$Sh$ zM)?p=r(VADvbJ$Qg^d;SxJubjsXBfSE#Dx?zgbW|vqWFJp0|gjQcL6eqB89tqh=Ut zEPYjV9C@4O-w;LjZ#A+&Yq3`ZXKx8+=Jg02uYQi@yHoq{Hnz3RZ_*9A>+b>Rb`O3s zo+;15C4E2zGKDlq&dX+~Y}Fc@Zr^Yca_ z!>n0ASN?LsS|u`t&=vGO$5xacXf18sp4(UUAopN}rPjuTwA0n(vj5yVz;dC{#Z$8r z-rMb#K9Cc*=$g3r>+gSagzO^$;f;a!kqBXqGd+TzJl6TfmlLBNUwS8WZuEBp1^FrM zZln-JF$zAq?>VD{R?2kw*^ioSb1Qj7|H;$qWjkvA<~MZ0+xVb?9bXmRKjs`r2uauc z)%o>fR2?IDB5gEx!@Xr_?9hBoNGbuIVEg!zQPxXnc$Bii78x~2!(tKpbb^ceJ;jY? z5Tj#N*b!ahtl_qpEWRh5cX1VW-o2B4kQPU;w@WQH-1kmv+B$k)19KZg-C{d5Clf`! zODVfU_hYzMwZ{*cvwTeRMtg$_y!iAzR65aX!Gt?njVm|S+shw7vdF{S4TR;Z=kuui z5#R=A#{n7XVcGBxyGdi>xrlXfQQPS{m@W1ned71>ZAcmWg7x4eXRrL*Njjc(FCwo} zaDNJc;mw0DSuxUNzOG}(>mfr{d>Tq!SL4R&gC^-B8BOPYc3zDr7UXO9LEGC7y_y1p zXwc4Y0CCSt#5ZnrSmUyqfN)X#|6K>%BaV;ORaqZ!|nAMkq;dcuJ>v!R!g0?C_TzjwfF~$^ zP|a$_-Ejc#_1XmS9=D1O^TPX3%6lE6D~vV;)in;qK)8cgrI>P#T3wXh#W(?{Ha;Wu z+i{kB5e>3I@u?G7NL%TWCVd?!l(waP^PgNsbeC-S#fKC}WXhu&Nqiv8zx41iLzW~= zmUTWahH2S2QXRHzvo^Q!65<2$EoASaz^_-Mb#&=yZ-+kxZHf~r0~F_HSp{?0NgWJ~ zft!lbC5IqBw5nzuC&wlo`M(<4BDTW-@71{TW|KVv7bgDO8>$`IoP@BT|LEH54OTj& zKJ9m4>CpVUr)r)mtfWpq@v~yiDlxZ!wQVNGi8>UUM)!xlLm|O?i6F4xb|Vl?inE?g zER@FX2P$TR{YNtI9{08eTrjKa{}nJipH_HdNi<;2pgZ^`hH-Ygt7*X{?rJ=WSN{ih zl4z!yiA~_9_3c_vl}!|d{pK$$qVcXB&+kCJvnYlgf+jAl?o;ZPlFc-ypzbzqpwMmY zBgWcC*Ou`DVit{$z9$sA`w+KDclsQ6frWDt+#3Tkr#BCi3y&}Ck>~z~kBM1T`zg&_ zI;LNIcZkK^kEW5TCb{!|c}Pa>5&t}FyCI8KjJzhEZRd2O)?Vx#R~-I3LxkUu{~G0d zooJ_(^1pzua2l^kq}lRMCIDQfH+AMiS^VSwvf@DE|HrQKs%s@s zy?mD7|KXIm7tt@j`qzK+?@vx$sLB7QiG~0Z)S62?dOS`T{~z0xnv%9+^* Date: Fri, 4 Sep 2020 13:09:42 +0200 Subject: [PATCH 218/248] INAV PID Controller basic description --- docs/INAV PID Controller.md | 25 ++++++++++++ docs/development/PID Internals.md | 63 ------------------------------- 2 files changed, 25 insertions(+), 63 deletions(-) create mode 100644 docs/INAV PID Controller.md delete mode 100644 docs/development/PID Internals.md diff --git a/docs/INAV PID Controller.md b/docs/INAV PID Controller.md new file mode 100644 index 00000000000..7bf5945e48f --- /dev/null +++ b/docs/INAV PID Controller.md @@ -0,0 +1,25 @@ +# INAV PID Controller + +What you have to know about INAV PID/PIFF/PIDCD controllers: + +1. INAV PID uses floating-point math +1. Rate/Angular Velocity controllers work in dps [degrees per second] +1. P, I, D and Multirotor CD gains are scaled like Betafligfht equivalents, but actual mechanics are different, and PID response might be different +1. Depending on platform type, different controllers are used + 1. Fixed-wing uses **PIFF**: + 1. Error is computed with a formula `const float rateError = pidState->rateTarget - pidState->gyroRate;` + 1. P-term with a formula `rateError * pidState->kP` + 1. Simple I-term without Iterm Relax. I-term limit based on stick position is used instead. I-term is no allowed to grow if stick (roll/pitch/yaw) is deflected above threshold defined in `fw_iterm_limit_stick_position`. `pidState->errorGyroIf += rateError * pidState->kI * dT;` + 1. No D-term + 1. FF-term (Feed Forward) is computed from the controller input with a formula `pidState->rateTarget * pidState->kFF`. Bear in mind, this is not a **FeedForward** from Betaflight! + 1. Multirotor uses **PIDCD**: + 1. Error is computed with a formula `const float rateError = pidState->rateTarget - pidState->gyroRate;` + 1. P-term with a formula `rateError * pidState->kP` + 1. I-term + 1. Iterm Relax is used to dynamically attenuate I-term during fast stick movements + 1. I-term formula `pidState->errorGyroIf += (itermErrorRate * pidState->kI * antiWindupScaler * dT) + ((newOutputLimited - newOutput) * pidState->kT * antiWindupScaler * dT);` + 1. I-term can be limited when motor output is saturated + 1. D-term is computed only from gyro measurement + 1. There are 2 LPF filters on D-term + 1. D-term can by boosted during fast maneuvers using D-Boost. D-Boost is an equivalent of Betaflight D_min + 1. **Control Derivative**, CD, or CD-term is a derivative computed from the setpoint that helps to boost PIDCD controller during fast stick movements. `newCDTerm = rateTargetDeltaFiltered * (pidState->kCD / dT);` It is an equivalent of Betaflight Feed Forward \ No newline at end of file diff --git a/docs/development/PID Internals.md b/docs/development/PID Internals.md deleted file mode 100644 index 6cb81db68f5..00000000000 --- a/docs/development/PID Internals.md +++ /dev/null @@ -1,63 +0,0 @@ -### IO variables - -`gyroADC/8192*2000 = deg/s` - -`gyroADC/4 ~ deg/s` - -`rcCommand` - `<-500 - 500>` nominal, but is scaled with `rcRate/100`, max +-1250 - -`inclination` - in 0.1 degree, roll and pitch deviation from horizontal position -`max_angle_inclination` - in 0.1 degree, default 50 degrees (500) - -`axisPID` - output to mixer, will be added to throttle(`<1000-2000>`), output range is `` (default `<1150 - 1850>`) - -### PID controller 0, "MultiWii" (default) - - -#### Leveling term -``` -error = constrain(2*rcCommand[axis], limit +- max_angle_inclination) - inclination[axis] -Pacc = constrain(P8[PIDLEVEL]/100 * error, limit +- 5 * D8[PIDLEVEL]) -Iacc = intergrate(error, limit +-10000) * I8[PIDLEVEL] / 4096 -``` -#### Gyro term -``` -Pgyro = rcCommand[axis]; -error = rcCommand[axis] * 10 * 8 / pidProfile->P8[axis] - gyroADC[axis] / 4; (conversion so that error is in deg/s ?) -Igyro = integrate(error, limit +-16000) / 10 / 8 * I8[axis] / 100 (conversion back to mixer units ?) -``` - -reset I term if - - axis rotation rate > +-64deg/s - - axis is YAW and rcCommand>+-100 - -##### Mode dependent mix(yaw is always from gyro) - -- HORIZON - proportionally according to max deflection -``` - deflection = MAX(ABS(rcCommand[PITCH]), ABS(rcCommand[ROLL])) / 500 ; limit to 0.0 .. 1.0 - P = Pacc * (1-deflection) + Pgyro * deflection - I = Iacc * (1-deflection) + Igyro * deflection -``` -- gyro -``` - P = Pgyro - I = Igyro -``` -- ANGLE -``` - P = Pacc - I = Iacc -``` -#### Gyro stabilization - -``` -P -= gyroADC[axis] / 4 * dynP8 / 10 / 8 -D = -mean(diff(gyroADC[axis] / 4), over 3 samples) * 3 * dynD8 / 32 -[equivalent to :] -D = - (gyroADC[axis]/4 - (<3 loops old>gyroADC[axis]/4)) * dynD8 / 32 -``` - -This can be seen as sum of - - PI controller (handles rcCommand, HORIZON/ANGLE); `Igyro` is only output based on gyroADC - - PD controller(parameters dynP8/dynD8) with zero setpoint acting on gyroADC From bbf994991ba6d98777e89929429df46379fc86e1 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Sat, 5 Sep 2020 10:52:50 +0100 Subject: [PATCH 219/248] add "Building in FreeBSD Guide" --- docs/development/Building in FreeBSD.md | 12 ++++++++++++ 1 file changed, 12 insertions(+) create mode 100644 docs/development/Building in FreeBSD.md diff --git a/docs/development/Building in FreeBSD.md b/docs/development/Building in FreeBSD.md new file mode 100644 index 00000000000..0859ac129f9 --- /dev/null +++ b/docs/development/Building in FreeBSD.md @@ -0,0 +1,12 @@ +# Building in FreeBSD + +In order to build the inav firmware in FreeBSD, it is recommended to install [Linux Binary Emulation](https://www.freebsd.org/doc/handbook/linuxemu.html). This will enable you to use the project recommended ARM cross-compiler. The cross-compiler available in Ports tends to be too old to build inav firmware. + +* Install Linux binary emulation +* Install the following packages (`pkg` provides suitable versions) + - `git` + - `cmake` + - `make` + - `ruby` + +* Follow the [Building in Linux](Building%20in%20Linux.md) guide. From edf94ce7e3173ddf01322d29dcf826c669f7334e Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sat, 5 Sep 2020 13:10:35 +0200 Subject: [PATCH 220/248] Update WSL for cmake --- ...ding in Windows 10 with Linux Subsystem.md | 27 +++++++++++++++---- 1 file changed, 22 insertions(+), 5 deletions(-) diff --git a/docs/development/Building in Windows 10 with Linux Subsystem.md b/docs/development/Building in Windows 10 with Linux Subsystem.md index 39ca71cf9b9..37a2eba7729 100644 --- a/docs/development/Building in Windows 10 with Linux Subsystem.md +++ b/docs/development/Building in Windows 10 with Linux Subsystem.md @@ -25,9 +25,13 @@ Update the repo packages: Install Git, Make, gcc and Ruby 1. `sudo apt-get install git` 1. `sudo apt-get install make` -1. `sudo apt-get install gcc-arm-none-eabi` +1. `sudo apt-get install cmake` 1. `sudo apt-get install ruby` +### CMAKE and Ubuntu 18_04 + +To run `cmake` in the latest version you will need to update from Ubuntu `18_04` to `20_04`. The fastest way to do it is to uninstall current version and install `20_04` for Microsoft Store [https://www.microsoft.com/store/productId/9N6SVWS3RX71](https://www.microsoft.com/store/productId/9N6SVWS3RX71) + ## Downloading the iNav repository (example): Mount MS windows C drive and clone iNav @@ -40,15 +44,28 @@ You now have a folder called inav in the root of C drive that you can edit in wi ## Building (example): +For detailed build instrusctions see [Building in Linux](Building%20in%20Linux.md) + Launch Ubuntu: Click Windows Start button then scroll and lauch "Ubuntu" -Building from Ubunto command line +Building from Ubuntu command line + `cd /mnt/c/inav` -`make clean TARGET=OMNIBUSF4PRO` (as an example) -`make TARGET=MATEKF405` (as an example) +Do it onece to prepare build environment +``` +mkdir build +cd build +cmake .. +``` + +Then to build +``` +cd build +make MATEKF722 +``` ## Flashing: Launch windows configurator GUI and from within the firmware flasher select `Load firmware[Local]` -Hex files can be found in the folder `c:\inav\obj` +Hex files can be found in the folder `c:\inav\build` From c9b71fc4ea17d5fe7583c80176b00f00791f999f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sun, 6 Sep 2020 16:11:46 +0100 Subject: [PATCH 221/248] [CMAKE] Remove BETAFLIGHTF3 target from releases RAM no longer fits --- src/main/target/BETAFLIGHTF3/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/BETAFLIGHTF3/CMakeLists.txt b/src/main/target/BETAFLIGHTF3/CMakeLists.txt index e27e7e5e7ac..79e749481b3 100644 --- a/src/main/target/BETAFLIGHTF3/CMakeLists.txt +++ b/src/main/target/BETAFLIGHTF3/CMakeLists.txt @@ -1 +1 @@ -target_stm32f303xc(BETAFLIGHTF3 COMPILE_DEFINITIONS "SPRACINGF3") +target_stm32f303xc(BETAFLIGHTF3 COMPILE_DEFINITIONS "SPRACINGF3" SKIP_RELEASES) From 728769b5bd939a3b1dd3519b55c2ac5a407766c9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sun, 6 Sep 2020 16:58:25 +0100 Subject: [PATCH 222/248] [DOC] Update build instructions for macOS to use cmake --- docs/development/Building in Mac OS X.md | 95 +++++++++++++++--------- 1 file changed, 58 insertions(+), 37 deletions(-) diff --git a/docs/development/Building in Mac OS X.md b/docs/development/Building in Mac OS X.md index 70364bf7511..ecc1d8ab4a6 100755 --- a/docs/development/Building in Mac OS X.md +++ b/docs/development/Building in Mac OS X.md @@ -3,7 +3,7 @@ Building in Mac OS X can be accomplished in just a few steps: * Install general development tools (clang, make, git) -* Install ARM GCC 7.2 series compiler or higher +* Install cmake * Checkout INAV sourcecode through git * Build the code @@ -35,41 +35,24 @@ installation, open up XCode and enter its preferences menu. Go to the "downloads [from the App Store]: https://itunes.apple.com/us/app/xcode/id497799835 -## Install ARM GCC 7.2 series or higher compiler +## Install cmake -INAV is built using series 7.2 or above GCC compiler provided by the [GNU Tools for ARM Embedded Processors project][]. +The easiest way to install cmake's command line executable is via +[Homebrew](https://brew.sh) (a package manager for macOS). Go to their site +and follow their installation instructions. -Grab the Mac installation tarball for the latest version in the 7.2 series or above (e.g. gcc-arm-none-eabi-7-2017-q4-major-mac.tar.bz2). Move it somewhere useful -such as a `~/development` folder (in your home directory) and double click it to unpack it. You should end up with a -folder with a name similar to `~/development/gcc-arm-none-eabi-7-2017-q4-major/`. +Once Homebrew is installed, type `brew install cmake` in a terminal to install +cmake. -Now you just need to add the `bin/` directory from inside the GCC directory to your system's path. Run `nano ~/.profile`. Add a -new line at the end of the file which adds the path for the `bin/` folder to your path, like so: +Alternatively, cmake binaries for macOS are available from +[cmake.org](https://cmake.org/download/). If you prefer installing it this way, +you'd have to manually add cmake's command line binary to your `$PATH`. Assuming +`CMake.app` has been copied to `/Applications`, adding the following line to +`~/.zshrc` would make the cmake command available. +```sh +export PATH=$PATH:/Applications/CMake.app/Contents/bin ``` -export PATH=$PATH:~/development/gcc-arm-none-eabi-7-2017-q4-major/bin -``` - -Press CTRL+X to exit nano, and answer "y" when prompted to save your changes. - -Now *close this terminal window* and open a new one. Try running: - -``` -arm-none-eabi-gcc --version -``` - -You should get output similar to (in this example compiler series 7.2.1 is used): - -``` -arm-none-eabi-gcc (GNU Tools for Arm Embedded Processors 7-2017-q4-major) 7.2.1 20170904 (release) [ARM/embedded-7-branch revision 255204] -Copyright (C) 2017 Free Software Foundation, Inc. -This is free software; see the source for copying conditions. There is NO -warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. -``` - -If `arm-none-eabi-gcc` couldn't be found, go back and check that you entered the correct path in your `~/.profile` file. - -[GNU Tools for ARM Embedded Processors project]: https://developer.arm.com/open-source/gnu-toolchain/gnu-rm/downloads ## Ruby @@ -90,9 +73,48 @@ This will download the entire INAV repository for you into a new folder called " ## Build the code -Enter the inav directory and run `make TARGET=SPRACINGF3` to build firmware for the SPRacing F3. When the build completes, -the .hex firmware should be available as `obj/inav_x.x.x_SPRACINGF3.hex` for you to flash using the INAV -Configurator. +Assuming you've just cloned the source code, you can switch your current +directory to inav's source try by typing: + +```sh +cd inav +``` + +Inside the inav directory, create a new directory to store the built files. This +helps keeping everything nice and tidy, separating source code from artifacts. By +convention this directory is usually called `build`, but any name would work. Enter +the following command to create it and switch your working directory to it: + +```sh +mkdir -p build && cd build +``` + +Now we need to configure the build by using the following command: + +```sh +cmake .. +``` + +This will automatically download the required compiler for inav, so it +might take a few minutes. Once it's finished without errors, you can +build the target that you want by typing `make target-name`. e.g.: + +```sh +make -j8 MATEKF722 # Will build MATEKF722 target +``` + +A list of all the available targets can be displayed with: + +```sh +make targets +``` + +Once the build completes, the correspondent `.hex` file will be found +in current directory (e.g. `build`) and it will be named as +`inav_x.y.z_TARGET.hex`. `x.y.z` corresponds to the INAV version number +while `TARGET` will be the target name you've just built. e.g. +`inav_2.6.0_MATEKF722.hex`. This is the file that can be flashed using +INAV Configurator. ## Updating to the latest source @@ -100,10 +122,9 @@ If you want to erase your local changes and update to the latest version of the inav directory and run these commands to first erase your local changes, fetch and merge the latest changes from the repository, then rebuild the firmware: -``` +```sh git reset --hard git pull -make clean TARGET=SPRACINGF3 -make TARGET=SPRACINGF3 +make target-name # e.g. make MATEKF722 ``` From ab734d9991c57c0e662c35c0be2f277ecd159a2c Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Sun, 6 Sep 2020 19:23:47 +0100 Subject: [PATCH 223/248] document target format --- docs/development/Cmake usage.md | 67 +++++++++++++++++++++++++++++++++ 1 file changed, 67 insertions(+) create mode 100644 docs/development/Cmake usage.md diff --git a/docs/development/Cmake usage.md b/docs/development/Cmake usage.md new file mode 100644 index 00000000000..ff822c0e4bb --- /dev/null +++ b/docs/development/Cmake usage.md @@ -0,0 +1,67 @@ +# Cmake Usage + +## Introduction + +This guide documents inav usage of the `cmake` build tool. + +## Target Defintion + +A target requires `CMakeLists.txt` file. This file contains one of more lines of the form: + +``` +target_hardware_definition(name optional_parameters) +``` + +For example: + +``` +target_stm32f405xg(QUARKVISION HSE_MHZ 16) +``` + +* The hardware is `stm32f405xg`, a standard F405 +* The name is `QUARKVISION` (a board that never reached production) +* The optional parameter is `HSE_MHZ 16` defining the non-standard high-speed external (HSE) oscillator clock. + +## Hardware names + +As of inav 2.6, the following target hardware platforms are recognised: + +* stm32f303xc +* stm32f405xg +* stm32f411xe +* stm32f427xg +* stm32f722xe +* stm32f745xg +* stm32f765xg +* stm32f765xi + +## Optional Parameters + +The following optional parameters are recognised: + +| Paramater | Usage | +| --------- | ----- | +| `SKIP_RELEASES` | The target is disabled | +| `COMPILE_DEFINITIONS "VAR=[value]"` | Sets a preprocessor define. | +| `HSE_MZ value` | The target uses an non-standard non-standard high-speed external (HSE) oscillator clock. The `value` is the desired clock, for example `HSE_MHZ 24` | + +Multiple optional parameters may be specified, for example `HSE_MHZ 16 SKIP_RELEASES`. + +## Target variations + +A number of targets support multiple variants, either successive versions of the same hardware, or varations that enable different resources (soft serial, leds etc.) This is defined by adding additional `target_` lines to `CMakeLists.txt`. For example, the OMNIBUSF4 and its multiple clones / variations, `src/main/target/OMNIBUSF4/CMakeLists.txt`: + +``` +target_stm32f405xg(DYSF4PRO) +target_stm32f405xg(DYSF4PROV2) +target_stm32f405xg(OMNIBUSF4) +# the OMNIBUSF4SD has an SDCARD instead of flash, a BMP280 baro and therefore a slightly different ppm/pwm and SPI mapping +target_stm32f405xg(OMNIBUSF4PRO) +target_stm32f405xg(OMNIBUSF4PRO_LEDSTRIPM5) +target_stm32f405xg(OMNIBUSF4V3_S5_S6_2SS) +target_stm32f405xg(OMNIBUSF4V3_S5S6_SS) +target_stm32f405xg(OMNIBUSF4V3_S6_SS) +# OMNIBUSF4V3 is a (almost identical) variant of OMNIBUSF4PRO target, +# except for an inverter on UART6. +target_stm32f405xg(OMNIBUSF4V3) +``` From 08874eb94a197e620c8602bba7b051c07ec960a9 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Sun, 6 Sep 2020 19:54:24 +0100 Subject: [PATCH 224/248] clarify cmake usage document / implement review comments --- docs/development/Cmake usage.md | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/docs/development/Cmake usage.md b/docs/development/Cmake usage.md index ff822c0e4bb..da499a59c04 100644 --- a/docs/development/Cmake usage.md +++ b/docs/development/Cmake usage.md @@ -18,9 +18,9 @@ For example: target_stm32f405xg(QUARKVISION HSE_MHZ 16) ``` -* The hardware is `stm32f405xg`, a standard F405 +* The hardware is `stm32f405xg`, a F405 with a 1MiB flash * The name is `QUARKVISION` (a board that never reached production) -* The optional parameter is `HSE_MHZ 16` defining the non-standard high-speed external (HSE) oscillator clock. +* The optional parameter is `HSE_MHZ 16` defining the non-default high-speed external (HSE) oscillator clock. ## Hardware names @@ -35,15 +35,17 @@ As of inav 2.6, the following target hardware platforms are recognised: * stm32f765xg * stm32f765xi +The device characteristics for these names may be found at [stm32-base.org](https://stm32-base.org/cheatsheets/linker-memory-regions/). + ## Optional Parameters The following optional parameters are recognised: | Paramater | Usage | | --------- | ----- | -| `SKIP_RELEASES` | The target is disabled | -| `COMPILE_DEFINITIONS "VAR=[value]"` | Sets a preprocessor define. | -| `HSE_MZ value` | The target uses an non-standard non-standard high-speed external (HSE) oscillator clock. The `value` is the desired clock, for example `HSE_MHZ 24` | +| `SKIP_RELEASES` | The target is disabled for releases and CI. It still may be possible to build the target directly. | +| `COMPILE_DEFINITIONS "VAR[=value]"` | Sets a preprocessor define. | +| `HSE_MZ value` | The target uses a high-speed external crystal (HSE) oscillator clock with a frequency different from the 8MHz default. The `value` is the desired clock, for example `HSE_MHZ 24` | Multiple optional parameters may be specified, for example `HSE_MHZ 16 SKIP_RELEASES`. From 9714f053686bbe50b006992531d93f4ac0488fd5 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 7 Sep 2020 14:39:31 +0200 Subject: [PATCH 225/248] New functions: sin, cos, tan and range scaling --- docs/Programming Framework.md | 58 +++++++++++++++++++++----- src/main/programming/logic_condition.c | 25 +++++++++++ src/main/programming/logic_condition.h | 7 +++- 3 files changed, 79 insertions(+), 11 deletions(-) diff --git a/docs/Programming Framework.md b/docs/Programming Framework.md index 6bbc4ecd76e..ddcb0188634 100644 --- a/docs/Programming Framework.md +++ b/docs/Programming Framework.md @@ -52,17 +52,22 @@ IPF can be edited using INAV Configurator user interface, of via CLI | 19 | GVAR INC | Increase the GVAR indexed by `Operand A` with value from `Operand B` | | 20 | GVAR DEC | Decrease the GVAR indexed by `Operand A` with value from `Operand B` | | 21 | IO PORT SET | Set I2C IO Expander pin `Operand A` to value of `Operand B`. `Operand A` accepts values `0-7` and `Operand B` accepts `0` and `1` | -| 22 | OVERRIDE_ARMING_SAFETY | Allows to arm on any angle even without GPS fix | -| 23 | OVERRIDE_THROTTLE_SCALE | Override throttle scale to the value defined by operand. Operand type `0` and value `50` means throttle will be scaled by 50%. | -| 24 | SWAP_ROLL_YAW | basically, when activated, yaw stick will control roll and roll stick will control yaw. Required for tail-sitters VTOL during vertical-horizonral transition when body frame changes | -| 25 | SET_VTX_POWER_LEVEL | Sets VTX power level. Accepted values are `0-3` for SmartAudio and `0-4` for Tramp protocol | -| 26 | INVERT_ROLL | Inverts ROLL axis input for PID/PIFF controller | -| 27 | INVERT_PITCH | Inverts PITCH axis input for PID/PIFF controller | -| 28 | INVERT_YAW | Inverts YAW axis input for PID/PIFF controller | -| 29 | OVERRIDE_THROTTLE | Override throttle value that is fed to the motors by mixer. Operand is scaled in us. `1000` means throttle cut, `1500` means half throttle | -| 30 | SET_VTX_BAND | Sets VTX band. Accepted values are `1-5` | -| 31 | SET_VTX_CHANNEL | Sets VTX channel. Accepted values are `1-8` | +| 22 | OVERRIDE_ARMING_SAFETY | Allows to arm on any angle even without GPS fix | +| 23 | OVERRIDE_THROTTLE_SCALE | Override throttle scale to the value defined by operand. Operand type `0` and value `50` means throttle will be scaled by 50%. | +| 24 | SWAP_ROLL_YAW | basically, when activated, yaw stick will control roll and roll stick will control yaw. Required for tail-sitters VTOL during vertical-horizonral transition when body frame changes | +| 25 | SET_VTX_POWER_LEVEL | Sets VTX power level. Accepted values are `0-3` for SmartAudio and `0-4` for Tramp protocol | +| 26 | INVERT_ROLL | Inverts ROLL axis input for PID/PIFF controller | +| 27 | INVERT_PITCH | Inverts PITCH axis input for PID/PIFF controller | +| 28 | INVERT_YAW | Inverts YAW axis input for PID/PIFF controller | +| 29 | OVERRIDE_THROTTLE | Override throttle value that is fed to the motors by mixer. Operand is scaled in us. `1000` means throttle cut, `1500` means half throttle | +| 30 | SET_VTX_BAND | Sets VTX band. Accepted values are `1-5` | +| 31 | SET_VTX_CHANNEL | Sets VTX channel. Accepted values are `1-8` | | 32 | SET_OSD_LAYOUT | Sets OSD layout. Accepted values are `0-3` | +| 33 | SIN | Computes SIN of `Operand A` value in degrees. Output is multiplied by `Operand B` value. If `Operand B` is `0`, result is multiplied by `500` | +| 34 | COS | Computes COS of `Operand A` value in degrees. Output is multiplied by `Operand B` value. If `Operand B` is `0`, result is multiplied by `500` | +| 35 | TAN | Computes TAN of `Operand A` value in degrees. Output is multiplied by `Operand B` value. If `Operand B` is `0`, result is multiplied by `500` | +| 36 | MAP_INPUT | Scales `Operand A` from [`0` : `Operand B`] to [`0` : `1000`]. Note: input will be constrained and then scaled | +| 37 | MAP_OUTPUT | Scales `Operand A` from [`0` : `1000`] to [`0` : `Operand B`]. Note: input will be constrained and then scaled | ### Operands @@ -173,3 +178,36 @@ Sets Thhrottle output to about `50%` when Logic Condition `0` evaluates as `true If Logic Condition `0` evaluates as `true`, motor throttle control is bound to RC channel 7 instead of throttle channel +### Set VTX channel with a POT + +Set VTX channel with a POT on the radio assigned to RC channel 6 + +``` +logic 0 1 -1 15 1 6 0 1000 0 +logic 1 1 -1 37 4 0 0 7 0 +logic 2 1 -1 14 4 1 0 1 0 +logic 3 1 -1 31 4 2 0 0 0 +``` + +Steps: +1. Normalize range `[1000:2000]` to `[0:1000]` by substracting `1000` +2. Scale range `[0:1000]` to `[0:7]` +3. Increase range by `1` to have the range of `[1:8]` +4. Assign LC#2 to VTX channel function + +### Set VTX power with a POT + +Set VTX power with a POT on the radio assigned to RC channel 6. In this example we scale POT to 4 power level `[1:4]` + +``` +logic 0 1 -1 15 1 6 0 1000 0 +logic 1 1 -1 37 4 0 0 3 0 +logic 2 1 -1 14 4 1 0 1 0 +logic 3 1 -1 25 4 2 0 0 0 +``` + +Steps: +1. Normalize range [1000:2000] to [0:1000] by substracting `1000` +2. Scale range [0:1000] to [0:3] +3. Increase range by `1` to have the range of [1:4] +4. Assign LC#2 to VTX power function \ No newline at end of file diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index 4184a87ebbc..a35dd32598a 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -277,6 +277,31 @@ static int logicConditionCompute( return operandB; break; #endif + + case LOGIC_CONDITION_SIN: + temporaryValue = (operandB == 0) ? 500 : operandB; + return sin_approx(DEGREES_TO_RADIANS(operandA)) * temporaryValue; + break; + + case LOGIC_CONDITION_COS: + temporaryValue = (operandB == 0) ? 500 : operandB; + return cos_approx(DEGREES_TO_RADIANS(operandA)) * temporaryValue; + break; + break; + + case LOGIC_CONDITION_TAN: + temporaryValue = (operandB == 0) ? 500 : operandB; + return tan_approx(DEGREES_TO_RADIANS(operandA)) * temporaryValue; + break; + + case LOGIC_CONDITION_MAP_INPUT: + return scaleRange(constrain(operandA, 0, operandB), 0, operandB, 0, 1000); + break; + + case LOGIC_CONDITION_MAP_OUTPUT: + return scaleRange(constrain(operandA, 0, 1000), 0, 1000, 0, operandB); + break; + default: return false; break; diff --git a/src/main/programming/logic_condition.h b/src/main/programming/logic_condition.h index fa13d964fd7..628b3b5adb3 100644 --- a/src/main/programming/logic_condition.h +++ b/src/main/programming/logic_condition.h @@ -62,7 +62,12 @@ typedef enum { LOGIC_CONDITION_SET_VTX_BAND = 30, LOGIC_CONDITION_SET_VTX_CHANNEL = 31, LOGIC_CONDITION_SET_OSD_LAYOUT = 32, - LOGIC_CONDITION_LAST = 33, + LOGIC_CONDITION_SIN = 33, + LOGIC_CONDITION_COS = 34, + LOGIC_CONDITION_TAN = 35, + LOGIC_CONDITION_MAP_INPUT = 36, + LOGIC_CONDITION_MAP_OUTPUT = 37, + LOGIC_CONDITION_LAST = 38, } logicOperation_e; typedef enum logicOperandType_s { From 08636297c2ebd79382bf5acc4e049967e8e1718b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 7 Sep 2020 21:49:00 +0100 Subject: [PATCH 226/248] [BOOTLOADER] Fix compilation with cmake The MCU preprocessor defines are slightly different, so these needed some small tweaking since the page layout selection is MCU-dependant. --- src/bl/bl_main.c | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/src/bl/bl_main.c b/src/bl/bl_main.c index b1a75170afc..b52b9b78129 100644 --- a/src/bl/bl_main.c +++ b/src/bl/bl_main.c @@ -42,10 +42,6 @@ #include "io/asyncfatfs/asyncfatfs.h" -#if !(defined(STM32F405xx) || defined(STM32F722xx) || defined(STM32F765XG) || defined(STM32F7X5XI)) -#error Unsupported MCU -#endif - #if !(defined(USE_FLASHFS) || defined(USE_SDCARD)) #error No storage backend available #endif @@ -64,14 +60,16 @@ flashSectorDef_t flashSectors[] = { { 16, 4 }, { 64, 1 }, { 128, 7 }, { 0, 0 } } #define SECTOR_COUNT 8 flashSectorDef_t flashSectors[] = { { 16, 4 }, { 64, 1 }, { 128, 3 }, { 0, 0 } }; -#elif defined(STM32F765XG) +#elif defined(STM32F745xG) || defined(STM32F765xG) #define SECTOR_COUNT 8 flashSectorDef_t flashSectors[] = { { 32, 4 }, { 128, 1 }, { 256, 3 }, { 0, 0 } }; -#elif defined(STM32F7X5XI) +#elif defined(STM32F765xI) #define SECTOR_COUNT 8 flashSectorDef_t flashSectors[] = { { 32, 4 }, { 128, 1 }, { 256, 7 }, { 0, 0 } }; +#else +#error Unsupported MCU #endif #if defined(STM32F4) From 03098fa18a7c17a58e53e74c97dd1ea38907480c Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Tue, 8 Sep 2020 15:47:50 -0400 Subject: [PATCH 227/248] Changed SNR default to 5 to match TBS settings --- src/main/fc/settings.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index b99c7185bb7..bae14049976 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1665,7 +1665,7 @@ groups: max: 100 - name: nav_mc_vel_xy_dterm_attenuation_end description: "A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation reaches maximum" - default_value: "60" + default_value: "60" field: navVelXyDtermAttenuationEnd min: 0 max: 100 @@ -2712,7 +2712,7 @@ groups: max: 1250 - name: osd_snr_alarm description: "Value below which Crossfire SNR Alarm pops-up. (dB)" - default_value: "8" + default_value: "5" field: snr_alarm min: -12 max: 8 From b0c0b5110c0074b0d587ee01a53a49dfb4a4946a Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Tue, 8 Sep 2020 23:03:39 -0400 Subject: [PATCH 228/248] Update to SNR This update hides the SNR and dB symbols when not in use and shows a preview inside the CMS. --- src/main/io/osd.c | 15 ++++++++++----- 1 file changed, 10 insertions(+), 5 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 8513ed5bb93..d7a7aa682bf 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1660,16 +1660,21 @@ static bool osdDrawSingleElement(uint8_t item) break; case OSD_CRSF_SNR_DB: { - const char* hidesnr = " "; + const char* showsnr = " -12"; + const char* hidesnr = " "; int16_t osdSNR_Alarm = rxLinkStatistics.uplinkSNR; if (osdSNR_Alarm <= osdConfig()->snr_alarm) { buff[0] = SYM_SRN; tfp_sprintf(buff + 1, "%4d%c", rxLinkStatistics.uplinkSNR, SYM_DB); } else if (osdSNR_Alarm > osdConfig()->snr_alarm) { - //displayWrite(osdDisplayPort, elemPosX, elemPosY, " "); - buff[0] = SYM_SRN; - tfp_sprintf(buff + 1, "%s%c", hidesnr, SYM_DB); + if (cmsInMenu) { + buff[0] = SYM_SRN; + tfp_sprintf(buff + 1, "%s%c", showsnr, SYM_DB); + } else { + buff[0] = SYM_BLANK; + tfp_sprintf(buff + 1, "%s%c", hidesnr); + } } break; } @@ -3223,7 +3228,7 @@ void osdUpdate(timeUs_t currentTimeUs) else #ifdef USE_PROGRAMMING_FRAMEWORK if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT)) - activeLayout = constrain(logicConditionValuesByType[LOGIC_CONDITION_SET_OSD_LAYOUT], 0, OSD_ALTERNATE_LAYOUT_COUNT); + activeLayout = constrain(logicConditionValuesByType[LOGIC_CONDITION_SET_OSD_LAYOUT], 0, OSD_ALTERNATE_LAYOUT_COUNT); else #endif activeLayout = 0; From d4073dc2ca4fd3c5d47b4985a8d3be94feb78b03 Mon Sep 17 00:00:00 2001 From: user Date: Wed, 9 Sep 2020 19:19:13 +0300 Subject: [PATCH 229/248] Enable internal pull-up for bidir (half duplex) UARTs by default --- src/main/drivers/io.h | 3 +++ src/main/drivers/serial.h | 1 + src/main/drivers/serial_uart_stm32f4xx.c | 9 ++++++--- 3 files changed, 10 insertions(+), 3 deletions(-) diff --git a/src/main/drivers/io.h b/src/main/drivers/io.h index bc888ccef9c..cb35859aaea 100644 --- a/src/main/drivers/io.h +++ b/src/main/drivers/io.h @@ -46,6 +46,7 @@ #define IOCFG_AF_PP_PD IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_LOW, GPIO_PULLDOWN) #define IOCFG_AF_PP_UP IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_LOW, GPIO_PULLUP) #define IOCFG_AF_OD IO_CONFIG(GPIO_MODE_AF_OD, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL) +#define IOCFG_AF_OD_UP IO_CONFIG(GPIO_MODE_AF_OD, GPIO_SPEED_FREQ_LOW, GPIO_PULLUP) #define IOCFG_IPD IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_LOW, GPIO_PULLDOWN) #define IOCFG_IPU IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_LOW, GPIO_PULLUP) #define IOCFG_IN_FLOATING IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL) @@ -63,6 +64,7 @@ #define IOCFG_AF_PP_PD IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_DOWN) #define IOCFG_AF_PP_UP IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_UP) #define IOCFG_AF_OD IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL) +#define IOCFG_AF_OD_UP IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_OD, GPIO_PuPd_UP) #define IOCFG_IPD IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_DOWN) #define IOCFG_IPU IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_UP) #define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_NOPULL) @@ -74,6 +76,7 @@ # define IOCFG_OUT_OD 0 # define IOCFG_AF_PP 0 # define IOCFG_AF_OD 0 +# define IOCFG_AF_OD_UP 0 # define IOCFG_IPD 0 # define IOCFG_IPU 0 # define IOCFG_IN_FLOATING 0 diff --git a/src/main/drivers/serial.h b/src/main/drivers/serial.h index c908fd0c035..f9a5b263fa1 100644 --- a/src/main/drivers/serial.h +++ b/src/main/drivers/serial.h @@ -49,6 +49,7 @@ typedef enum portOptions_t { SERIAL_BIDIR_OD = 0 << 4, SERIAL_BIDIR_PP = 1 << 4, SERIAL_BIDIR_NOPULL = 1 << 5, // disable pulls in BIDIR RX mode + SERIAL_BIDIR_UP = 0 << 5, // enable pullup in BIDIR mode } portOptions_t; typedef void (*serialReceiveCallbackPtr)(uint16_t data, void *rxCallbackData); // used by serial drivers to return frames to app diff --git a/src/main/drivers/serial_uart_stm32f4xx.c b/src/main/drivers/serial_uart_stm32f4xx.c index 98e37ec0040..0f54fb69142 100644 --- a/src/main/drivers/serial_uart_stm32f4xx.c +++ b/src/main/drivers/serial_uart_stm32f4xx.c @@ -292,10 +292,13 @@ uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_t mode, if (options & SERIAL_BIDIR) { IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, RESOURCE_INDEX(device)); - if (options & SERIAL_BIDIR_PP) + if (options & SERIAL_BIDIR_PP) { IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af); - else - IOConfigGPIOAF(tx, IOCFG_AF_OD, uart->af); + } else { + IOConfigGPIOAF(tx, + (options & SERIAL_BIDIR_NOPULL) ? IOCFG_AF_OD : IOCFG_AF_OD_UP, + uart->af); + } } else { if (mode & MODE_TX) { From cb9364c207834e7b8cd278c619b1c709bad72c6e Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Wed, 9 Sep 2020 19:57:50 -0400 Subject: [PATCH 230/248] Added blinking to LQ Based on regular RSSI alarm number --- src/main/io/osd.c | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index d7a7aa682bf..ad7a6004776 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1656,7 +1656,9 @@ static bool osdDrawSingleElement(uint8_t item) tfp_sprintf(buff + 1, "%d:%3d%s", rxLinkStatistics.rfMode, rxLinkStatistics.uplinkLQ, "%"); if (!failsafeIsReceivingRxData()){ TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } + } else if (rxLinkStatistics.uplinkLQ < osdConfig()->rssi_alarm) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } break; case OSD_CRSF_SNR_DB: { @@ -1673,7 +1675,7 @@ static bool osdDrawSingleElement(uint8_t item) tfp_sprintf(buff + 1, "%s%c", showsnr, SYM_DB); } else { buff[0] = SYM_BLANK; - tfp_sprintf(buff + 1, "%s%c", hidesnr); + tfp_sprintf(buff + 1, "%s%c", hidesnr, SYM_BLANK); } } break; From f5242534d9f7dc11127a0e310cda57df04200c1c Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Wed, 9 Sep 2020 21:21:48 -0400 Subject: [PATCH 231/248] Added LQ/RSSI alarm level to menu Should be set to 70 for LQ --- src/main/cms/cms_menu_osd.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/cms/cms_menu_osd.c b/src/main/cms/cms_menu_osd.c index bcebb7071bb..69c45d62170 100755 --- a/src/main/cms/cms_menu_osd.c +++ b/src/main/cms/cms_menu_osd.c @@ -144,6 +144,7 @@ static const OSD_Entry menuCrsfRxEntries[]= OSD_LABEL_ENTRY("-- CRSF RX --"), OSD_SETTING_ENTRY("CRSF SNR LEVEL", SETTING_OSD_SNR_ALARM), + OSD_SETTING_ENTRY("LQ ALARM LEVEL", SETTING_OSD_RSSI_ALARM), OSD_ELEMENT_ENTRY("RX RSSI DBM", OSD_CRSF_RSSI_DBM), OSD_ELEMENT_ENTRY("RX LQ", OSD_CRSF_LQ), OSD_ELEMENT_ENTRY("RX SNR ALARM", OSD_CRSF_SNR_DB), From 80b44010773dbc18a6031851ae785a32468dde37 Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Wed, 9 Sep 2020 22:21:10 -0400 Subject: [PATCH 232/248] More spacing updates Spacing updates to use less characters and match configurator --- src/main/io/osd.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index ad7a6004776..1caef99090e 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1653,12 +1653,12 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_CRSF_LQ: buff[0] = SYM_BLANK; - tfp_sprintf(buff + 1, "%d:%3d%s", rxLinkStatistics.rfMode, rxLinkStatistics.uplinkLQ, "%"); + tfp_sprintf(buff, "%d:%3d%s", rxLinkStatistics.rfMode, rxLinkStatistics.uplinkLQ, "%"); if (!failsafeIsReceivingRxData()){ TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); } else if (rxLinkStatistics.uplinkLQ < osdConfig()->rssi_alarm) { TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); - } + } break; case OSD_CRSF_SNR_DB: { @@ -1667,7 +1667,7 @@ static bool osdDrawSingleElement(uint8_t item) int16_t osdSNR_Alarm = rxLinkStatistics.uplinkSNR; if (osdSNR_Alarm <= osdConfig()->snr_alarm) { buff[0] = SYM_SRN; - tfp_sprintf(buff + 1, "%4d%c", rxLinkStatistics.uplinkSNR, SYM_DB); + tfp_sprintf(buff + 1, "%3d%c", rxLinkStatistics.uplinkSNR, SYM_DB); } else if (osdSNR_Alarm > osdConfig()->snr_alarm) { if (cmsInMenu) { From 5ea3bf31d2f06c91bb8d65ce71f3c085e7aa9fc7 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Thu, 10 Sep 2020 12:25:01 +0200 Subject: [PATCH 233/248] [FPORT2] add settings to OTA start frame (#6118) --- src/main/rx/fport2.c | 28 +++++++++++++++++++++++----- 1 file changed, 23 insertions(+), 5 deletions(-) diff --git a/src/main/rx/fport2.c b/src/main/rx/fport2.c index 93dbe104f9e..de2b7d7062f 100644 --- a/src/main/rx/fport2.c +++ b/src/main/rx/fport2.c @@ -53,9 +53,10 @@ #include "rx/fport2.h" -#define FPORT2_MAX_TELEMETRY_RESPONSE_DELAY_US 3000 #define FPORT2_MIN_TELEMETRY_RESPONSE_DELAY_US 500 -#define FPORT2_MIN_OTA_RESPONSE_DELAY_US 50 +#define FPORT2_MAX_TELEMETRY_RESPONSE_DELAY_US 3000 +#define FPORT2_OTA_MAX_RESPONSE_TIME_US_DEFAULT 200 +#define FPORT2_OTA_MIN_RESPONSE_DELAY_US_DEFAULT 50 #define FPORT2_MAX_TELEMETRY_AGE_MS 500 #define FPORT2_FC_COMMON_ID 0x1B #define FPORT2_FC_MSP_ID 0x0D @@ -180,6 +181,8 @@ static const smartPortPayload_t emptySmartPortFrame = { .frameId = 0, .valueId = static smartPortPayload_t *otaResponsePayload = NULL; static bool otaMode = false; static bool otaDataNeedsProcessing = false; +static uint16_t otaMinResponseDelay = FPORT2_OTA_MIN_RESPONSE_DELAY_US_DEFAULT; +static uint16_t otaMaxResponseTime = FPORT2_OTA_MAX_RESPONSE_TIME_US_DEFAULT; static uint32_t otaDataAddress; static uint8_t otaDataBuffer[FPORT2_OTA_DATA_FRAME_BYTES]; static timeUs_t otaFrameEndTimestamp = 0; @@ -380,9 +383,24 @@ static uint8_t frameStatus(rxRuntimeConfig_t *rxRuntimeConfig) break; #if defined(USE_TELEMETRY_SMARTPORT) - case CFT_OTA_START: + case CFT_OTA_START: { + uint8_t otaMinResponseDelayByte = frame->control.ota[0]; + if ((otaMinResponseDelayByte > 0) && (otaMinResponseDelayByte <= 4)) { + otaMinResponseDelay = otaMinResponseDelayByte * 100; + } else { + otaMinResponseDelay = FPORT2_OTA_MIN_RESPONSE_DELAY_US_DEFAULT; + } + + uint8_t otaMaxResponseTimeByte = frame->control.ota[1]; + if (otaMaxResponseTimeByte > 0) { + otaMaxResponseTime = otaMaxResponseTimeByte * 100; + } else { + otaMaxResponseTime = FPORT2_OTA_MAX_RESPONSE_TIME_US_DEFAULT; + } + otaMode = true; break; + } case CFT_OTA_DATA: if (otaMode) { @@ -506,7 +524,7 @@ static uint8_t frameStatus(rxRuntimeConfig_t *rxRuntimeConfig) #if defined(USE_TELEMETRY_SMARTPORT) if (((mspPayload || hasTelemetryRequest) && cmpTimeUs(currentTimeUs, lastTelemetryFrameReceivedUs) >= FPORT2_MIN_TELEMETRY_RESPONSE_DELAY_US) - || (otaResponsePayload && cmpTimeUs(currentTimeUs, lastTelemetryFrameReceivedUs) >= FPORT2_MIN_OTA_RESPONSE_DELAY_US)) { + || (otaResponsePayload && cmpTimeUs(currentTimeUs, lastTelemetryFrameReceivedUs) >= otaMinResponseDelay)) { hasTelemetryRequest = false; clearToSend = true; result |= RX_FRAME_PROCESSING_REQUIRED; @@ -576,7 +594,7 @@ static bool processFrame(const rxRuntimeConfig_t *rxRuntimeConfig) } timeUs_t otaResponseTime = cmpTimeUs(micros(), otaFrameEndTimestamp); - if (!firmwareUpdateError && (otaResponseTime < 400)) { // We can answer in time (firmwareUpdateStore can take time because it might need to erase flash) + if (!firmwareUpdateError && (otaResponseTime <= otaMaxResponseTime)) { // We can answer in time (firmwareUpdateStore can take time because it might need to erase flash) writeUplinkFramePhyID(downlinkPhyID, otaResponsePayload); DEBUG_SET(DEBUG_FPORT, DEBUG_FPORT2_OTA_FRAME_RESPONSE_TIME, otaResponseTime); } From 2096bab0468e8d04bb7425c58e29c3100a772793 Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Fri, 11 Sep 2020 09:10:33 -0400 Subject: [PATCH 234/248] Spacing fix To use less characters match configurator and cms spacing --- src/main/io/osd.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 1caef99090e..f069f209ea6 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1662,7 +1662,7 @@ static bool osdDrawSingleElement(uint8_t item) break; case OSD_CRSF_SNR_DB: { - const char* showsnr = " -12"; + const char* showsnr = "-12"; const char* hidesnr = " "; int16_t osdSNR_Alarm = rxLinkStatistics.uplinkSNR; if (osdSNR_Alarm <= osdConfig()->snr_alarm) { From 9a1de747ab4096060686c5f375970988fe3427d9 Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Mon, 14 Sep 2020 15:59:27 -0400 Subject: [PATCH 235/248] Adds 250mW to TXPower TBS added 250mW to the full TX on Crossfire v4.0 --- src/main/rx/crsf.c | 4 ++-- src/main/telemetry/crsf.c | 3 ++- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/src/main/rx/crsf.c b/src/main/rx/crsf.c index 73ce42b02f7..8af07bce1c5 100755 --- a/src/main/rx/crsf.c +++ b/src/main/rx/crsf.c @@ -58,8 +58,8 @@ static timeUs_t crsfFrameStartAt = 0; static uint8_t telemetryBuf[CRSF_FRAME_SIZE_MAX]; static uint8_t telemetryBufLen = 0; -// The power levels represented by uplinkTXPower above in mW (Is 250 missing? Check TX lite powers) -const uint16_t crsfPowerStates[] = {0, 10, 25, 100, 500, 1000, 2000}; +// The power levels represented by uplinkTXPower above in mW (250mW added to full TX in v4.00 firmware) +const uint16_t crsfPowerStates[] = {0, 10, 25, 100, 500, 1000, 2000, 250}; /* * CRSF protocol diff --git a/src/main/telemetry/crsf.c b/src/main/telemetry/crsf.c index 4f8f2107072..8ac00c39f93 100755 --- a/src/main/telemetry/crsf.c +++ b/src/main/telemetry/crsf.c @@ -273,7 +273,8 @@ typedef enum { CRSF_RF_POWER_100_mW = 3, CRSF_RF_POWER_500_mW = 4, CRSF_RF_POWER_1000_mW = 5, - CRSF_RF_POWER_2000_mW = 6 + CRSF_RF_POWER_2000_mW = 6, + CRSF_RF_POWER_250_mW = 7 } crsrRfPower_e; /* From 427933c5ad1c8351f03d9e3548755892f08de063 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 14 Sep 2020 22:27:29 +0100 Subject: [PATCH 236/248] [CMAKE] Make the with_bl targets depend on targets instead of files While depending in the output files of other targets work fine with cmake 3.17+ and/or ninja, it fails with cmake 3.14 and make. This way works fine with all the combinations of cmake+backend we do care about. --- cmake/stm32.cmake | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake index 7338a105016..760c92ade26 100644 --- a/cmake/stm32.cmake +++ b/cmake/stm32.cmake @@ -404,11 +404,12 @@ function(target_stm32) # Combined with bootloader and main firmware set(with_bl_suffix _with_bl) set(combined_hex ${CMAKE_BINARY_DIR}/${binary_name}${with_bl_suffix}.hex) - add_custom_target(${name}${with_bl_suffix} + set(with_bl_target ${name}${with_bl_suffix}) + add_custom_target(${with_bl_target} ${CMAKE_SOURCE_DIR}/src/utils/combine_tool ${bl_bin_filename} ${for_bl_bin_filename} ${combined_hex} - DEPENDS ${bl_bin_filename} ${for_bl_bin_filename} BYPRODUCTS ${combined_hex} ) + add_dependencies(${with_bl_target} ${bl_target_name} ${for_bl_target_name}) endif() # clean_ From 23b31a9ee3840839ebc8e32a6a7148f3c7a8122d Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Tue, 15 Sep 2020 15:05:07 +0200 Subject: [PATCH 237/248] Do not allow for Blackbox to work faster than 1kHz --- src/main/fc/fc_init.c | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index 9903614af6d..36b17ec055c 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -599,6 +599,15 @@ void init(void) #endif #ifdef USE_BLACKBOX + + //Do not allow blackbox to be run faster that 1kHz. It can cause UAV to drop dead when digital ESC protocol is used + const uint32_t blackboxLooptime = getLooptime() * blackboxConfig()->rate_denom / blackboxConfig()->rate_num; + + if (blackboxLooptime < 1000) { + blackboxConfigMutable()->rate_num = 1; + blackboxConfigMutable()->rate_denom = ceil(1000 / getLooptime()); + } + // SDCARD and FLASHFS are used only for blackbox // Make sure we only init what's necessary for blackbox switch (blackboxConfig()->device) { From ffb782bd924cde4ccf0ceeddef602e81b80a6105 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Wed, 16 Sep 2020 13:34:55 +0200 Subject: [PATCH 238/248] [FRSKYPILOT] Fix UART number for OSD, should be 6, not 5 (#6130) --- src/main/target/FRSKYPILOT/config.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/target/FRSKYPILOT/config.c b/src/main/target/FRSKYPILOT/config.c index 2545ff06035..05ec1b5a85c 100644 --- a/src/main/target/FRSKYPILOT/config.c +++ b/src/main/target/FRSKYPILOT/config.c @@ -26,7 +26,7 @@ void targetConfiguration(void) { serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART1)].functionMask = FUNCTION_TELEMETRY_SMARTPORT_MASTER; - serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART5)].functionMask = FUNCTION_FRSKY_OSD; + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART6)].functionMask = FUNCTION_FRSKY_OSD; rxConfigMutable()->serialrx_inverted = 1; } From 68db45c3b0428ffd74462643c60f34f0e5d01baf Mon Sep 17 00:00:00 2001 From: LinJieqiang <517503838@qq.com> Date: Wed, 16 Sep 2020 23:52:55 +0800 Subject: [PATCH 239/248] Fix acceleration accTmp[] errors. --- src/main/sensors/acceleration.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 015d55f3597..9ff00c45297 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -462,7 +462,7 @@ static void performAcclerationCalibration(void) if (!sensorCalibrationSolveForOffset(&calState, accTmp)) { accTmp[0] = 0.0f; accTmp[1] = 0.0f; - accTmp[1] = 0.0f; + accTmp[2] = 0.0f; calFailed = true; } @@ -486,7 +486,7 @@ static void performAcclerationCalibration(void) if (!sensorCalibrationSolveForScale(&calState, accTmp)) { accTmp[0] = 1.0f; accTmp[1] = 1.0f; - accTmp[1] = 1.0f; + accTmp[2] = 1.0f; calFailed = true; } From 40e3b260ca334f3e51590a07dc1de1674a5b6007 Mon Sep 17 00:00:00 2001 From: LinJieqiang <517503838@qq.com> Date: Wed, 16 Sep 2020 23:53:07 +0800 Subject: [PATCH 240/248] Fix pos_estimator errors. --- src/main/navigation/navigation_pos_estimator.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c index ddaa1b8f4f0..94f612afa58 100755 --- a/src/main/navigation/navigation_pos_estimator.c +++ b/src/main/navigation/navigation_pos_estimator.c @@ -618,7 +618,7 @@ static bool estimationCalculateCorrection_XY_GPS(estimationContext_t * ctx) ctx->estPosCorr.y += posEstimator.gps.pos.y - posEstimator.est.pos.y; ctx->estVelCorr.x += posEstimator.gps.vel.x - posEstimator.est.vel.x; ctx->estVelCorr.y += posEstimator.gps.vel.y - posEstimator.est.vel.y; - ctx->newEPH = posEstimator.gps.epv; + ctx->newEPH = posEstimator.gps.eph; } else { const float gpsPosXResidual = posEstimator.gps.pos.x - posEstimator.est.pos.x; From 0ba91601ad7924580b9b6cfc6936f62d4a282804 Mon Sep 17 00:00:00 2001 From: Arvid Stenberg Date: Thu, 17 Sep 2020 08:49:15 +0200 Subject: [PATCH 241/248] Added tz_automatic_dst to MSP2_COMMON_TZ and MSP2_COMMON_SET_TZ (#6115) * Added tz_automatic_dst to MSP2_COMMON_TZ and MSP2_COMMON_SET_TZ * Added logic to handle 2 vs 3 bytes in MSP2_COMMON_SET_TZ --- src/main/fc/fc_msp.c | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index a5586aa3b62..16999bd0579 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -1404,6 +1404,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF case MSP2_COMMON_TZ: sbufWriteU16(dst, (uint16_t)timeConfig()->tz_offset); + sbufWriteU8(dst, (uint8_t)timeConfig()->tz_automatic_dst); break; case MSP2_INAV_AIR_SPEED: @@ -2726,7 +2727,10 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) case MSP2_COMMON_SET_TZ: if (dataSize == 2) timeConfigMutable()->tz_offset = (int16_t)sbufReadU16(src); - else + else if (dataSize == 3) { + timeConfigMutable()->tz_offset = (int16_t)sbufReadU16(src); + timeConfigMutable()->tz_automatic_dst = (uint8_t)sbufReadU8(src); + } else return MSP_RESULT_ERROR; break; From 93f637313ad635ae97f5f5e78402c800de8d3393 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Fri, 18 Sep 2020 19:07:14 +0100 Subject: [PATCH 242/248] [CMAKE] Remove old Makefile based build system --- Makefile | 549 ------------------ make/gdb.mk | 17 - make/mcu/STM32.mk | 1 - make/mcu/STM32F3.mk | 82 --- make/mcu/STM32F4.mk | 227 -------- make/mcu/STM32F7.mk | 212 ------- make/openocd.mk | 49 -- make/release.mk | 43 -- make/settings.mk | 26 - make/source.mk | 315 ---------- make/stamp.mk | 7 - make/svd.mk | 32 - make/system-id.mk | 53 -- make/targets.mk | 125 ---- make/tools.mk | 93 --- make/version.mk | 18 - src/main/target/AIKONF4/target.mk | 18 - src/main/target/AIRBOTF4/target.mk | 19 - src/main/target/AIRBOTF7/OMNIBUSF7NANOV7.mk | 0 src/main/target/AIRBOTF7/target.mk | 16 - src/main/target/AIRHEROF3/AIRHEROF3_QUAD.mk | 1 - src/main/target/AIRHEROF3/target.mk | 17 - src/main/target/ALIENFLIGHTNGF7/target.mk | 18 - src/main/target/ANYFC/target.mk | 14 - .../target/ANYFCF7/ANYFCF7_EXTERNAL_BARO.mk | 0 src/main/target/ANYFCF7/target.mk | 17 - src/main/target/ASGARD32F4/target.mk | 17 - src/main/target/ASGARD32F7/target.mk | 17 - src/main/target/BEEROTORF4/target.mk | 18 - src/main/target/BETAFLIGHTF3/target.mk | 18 - src/main/target/BETAFLIGHTF4/target.mk | 22 - src/main/target/BLUEJAYF4/target.mk | 16 - .../target/CLRACINGF4AIR/CLRACINGF4AIRV2.mk | 1 - .../target/CLRACINGF4AIR/CLRACINGF4AIRV3.mk | 1 - src/main/target/CLRACINGF4AIR/target.mk | 13 - src/main/target/COLIBRI/QUANTON.mk | 0 src/main/target/COLIBRI/target.mk | 13 - src/main/target/DALRCF405/target.mk | 19 - src/main/target/DALRCF722DUAL/target.mk | 18 - src/main/target/F4BY/target.mk | 15 - src/main/target/FALCORE/target.mk | 15 - src/main/target/FF_F35_LIGHTNING/WINGFC.mk | 1 - src/main/target/FF_F35_LIGHTNING/target.mk | 17 - src/main/target/FF_FORTINIF4/target.mk | 7 - src/main/target/FF_PIKOF4/FF_PIKOF4OSD.mk | 0 src/main/target/FF_PIKOF4/target.mk | 8 - src/main/target/FIREWORKSV2/OMNIBUSF4V6.mk | 1 - src/main/target/FIREWORKSV2/target.mk | 17 - src/main/target/FISHDRONEF4/target.mk | 17 - src/main/target/FLYWOOF411/target.mk | 19 - src/main/target/FLYWOOF7DUAL/target.mk | 19 - src/main/target/FOXEERF405/target.mk | 15 - .../target/FOXEERF722DUAL/FOXEERF722V2.mk | 1 - src/main/target/FOXEERF722DUAL/target.mk | 14 - src/main/target/FRSKYF3/target.mk | 13 - src/main/target/FRSKYF4/target.mk | 13 - src/main/target/FRSKYPILOT/target.mk | 14 - src/main/target/FRSKY_ROVERF7/target.mk | 17 - src/main/target/FURYF4OSD/MAMBAF405.mk | 1 - src/main/target/FURYF4OSD/target.mk | 21 - src/main/target/HGLRCF722/target.mk | 19 - src/main/target/IFLIGHTF4_SUCCEXD/target.mk | 17 - src/main/target/IFLIGHTF4_TWING/target.mk | 16 - src/main/target/IFLIGHTF7_TWING/target.mk | 15 - src/main/target/KAKUTEF4/KAKUTEF4V2.mk | 1 - src/main/target/KAKUTEF4/target.mk | 16 - src/main/target/KAKUTEF7/KAKUTEF7HDV.mk | 1 - src/main/target/KAKUTEF7/KAKUTEF7MINI.mk | 1 - src/main/target/KAKUTEF7/target.mk | 20 - src/main/target/LUX_RACE/target.mk | 10 - src/main/target/MAMBAF405US/target.mk | 13 - src/main/target/MAMBAF722/target.mk | 14 - src/main/target/MATEKF405/MATEKF405OSD.mk | 0 .../target/MATEKF405/MATEKF405_SERVOS6.mk | 0 src/main/target/MATEKF405/target.mk | 21 - src/main/target/MATEKF405SE/target.mk | 19 - .../target/MATEKF411/MATEKF411_FD_SFTSRL.mk | 1 - src/main/target/MATEKF411/MATEKF411_RSSI.mk | 0 .../target/MATEKF411/MATEKF411_SFTSRL2.mk | 0 src/main/target/MATEKF411/target.mk | 18 - src/main/target/MATEKF411SE/target.mk | 19 - .../target/MATEKF722/MATEKF722_HEXSERVO.mk | 0 src/main/target/MATEKF722/target.mk | 18 - src/main/target/MATEKF722PX/target.mk | 17 - src/main/target/MATEKF722SE/MATEKF722MINI.mk | 0 src/main/target/MATEKF722SE/target.mk | 20 - src/main/target/MATEKF765/target.mk | 19 - src/main/target/MOTOLAB/target.mk | 17 - src/main/target/NOX/target.mk | 9 - src/main/target/OMNIBUSF4/DYSF4PRO.mk | 1 - src/main/target/OMNIBUSF4/DYSF4PROV2.mk | 1 - src/main/target/OMNIBUSF4/OMNIBUSF4PRO.mk | 2 - .../OMNIBUSF4/OMNIBUSF4PRO_LEDSTRIPM5.mk | 2 - src/main/target/OMNIBUSF4/OMNIBUSF4V3.mk | 3 - .../target/OMNIBUSF4/OMNIBUSF4V3_S5S6_SS.mk | 1 - .../target/OMNIBUSF4/OMNIBUSF4V3_S5_S6_2SS.mk | 1 - .../target/OMNIBUSF4/OMNIBUSF4V3_S6_SS.mk | 1 - src/main/target/OMNIBUSF4/target.mk | 19 - src/main/target/OMNIBUSF7/OMNIBUSF7V2.mk | 0 src/main/target/OMNIBUSF7/target.mk | 18 - src/main/target/OMNIBUSF7NXT/target.mk | 14 - src/main/target/PIKOBLX/target.mk | 14 - src/main/target/PIXRACER/target.mk | 18 - src/main/target/RCEXPLORERF3/target.mk | 17 - src/main/target/REVO/target.mk | 17 - src/main/target/RMDO/target.mk | 21 - src/main/target/SPARKY/target.mk | 17 - src/main/target/SPARKY2/target.mk | 17 - .../target/SPEEDYBEEF4/SPEEDYBEEF4_SFTSRL1.mk | 1 - .../target/SPEEDYBEEF4/SPEEDYBEEF4_SFTSRL2.mk | 1 - src/main/target/SPEEDYBEEF4/target.mk | 17 - src/main/target/SPEEDYBEEF7/target.mk | 17 - src/main/target/SPRACINGF3/target.mk | 17 - src/main/target/SPRACINGF3MINI/target.mk | 20 - src/main/target/SPRACINGF4EVO/target.mk | 17 - src/main/target/SPRACINGF7DUAL/target.mk | 18 - src/main/target/YUPIF7/target.mk | 17 - src/main/target/ZEEZF7/target.mk | 7 - 118 files changed, 3024 deletions(-) delete mode 100644 Makefile delete mode 100644 make/gdb.mk delete mode 100644 make/mcu/STM32.mk delete mode 100644 make/mcu/STM32F3.mk delete mode 100644 make/mcu/STM32F4.mk delete mode 100644 make/mcu/STM32F7.mk delete mode 100644 make/openocd.mk delete mode 100644 make/release.mk delete mode 100644 make/settings.mk delete mode 100644 make/source.mk delete mode 100644 make/stamp.mk delete mode 100644 make/svd.mk delete mode 100644 make/system-id.mk delete mode 100644 make/targets.mk delete mode 100644 make/tools.mk delete mode 100644 make/version.mk delete mode 100644 src/main/target/AIKONF4/target.mk delete mode 100644 src/main/target/AIRBOTF4/target.mk delete mode 100644 src/main/target/AIRBOTF7/OMNIBUSF7NANOV7.mk delete mode 100644 src/main/target/AIRBOTF7/target.mk delete mode 100755 src/main/target/AIRHEROF3/AIRHEROF3_QUAD.mk delete mode 100755 src/main/target/AIRHEROF3/target.mk delete mode 100644 src/main/target/ALIENFLIGHTNGF7/target.mk delete mode 100644 src/main/target/ANYFC/target.mk delete mode 100644 src/main/target/ANYFCF7/ANYFCF7_EXTERNAL_BARO.mk delete mode 100644 src/main/target/ANYFCF7/target.mk delete mode 100644 src/main/target/ASGARD32F4/target.mk delete mode 100644 src/main/target/ASGARD32F7/target.mk delete mode 100644 src/main/target/BEEROTORF4/target.mk delete mode 100755 src/main/target/BETAFLIGHTF3/target.mk delete mode 100755 src/main/target/BETAFLIGHTF4/target.mk delete mode 100644 src/main/target/BLUEJAYF4/target.mk delete mode 100644 src/main/target/CLRACINGF4AIR/CLRACINGF4AIRV2.mk delete mode 100644 src/main/target/CLRACINGF4AIR/CLRACINGF4AIRV3.mk delete mode 100644 src/main/target/CLRACINGF4AIR/target.mk delete mode 100755 src/main/target/COLIBRI/QUANTON.mk delete mode 100755 src/main/target/COLIBRI/target.mk delete mode 100644 src/main/target/DALRCF405/target.mk delete mode 100644 src/main/target/DALRCF722DUAL/target.mk delete mode 100644 src/main/target/F4BY/target.mk delete mode 100755 src/main/target/FALCORE/target.mk delete mode 100644 src/main/target/FF_F35_LIGHTNING/WINGFC.mk delete mode 100644 src/main/target/FF_F35_LIGHTNING/target.mk delete mode 100644 src/main/target/FF_FORTINIF4/target.mk delete mode 100644 src/main/target/FF_PIKOF4/FF_PIKOF4OSD.mk delete mode 100644 src/main/target/FF_PIKOF4/target.mk delete mode 100644 src/main/target/FIREWORKSV2/OMNIBUSF4V6.mk delete mode 100644 src/main/target/FIREWORKSV2/target.mk delete mode 100644 src/main/target/FISHDRONEF4/target.mk delete mode 100644 src/main/target/FLYWOOF411/target.mk delete mode 100644 src/main/target/FLYWOOF7DUAL/target.mk delete mode 100644 src/main/target/FOXEERF405/target.mk delete mode 100644 src/main/target/FOXEERF722DUAL/FOXEERF722V2.mk delete mode 100644 src/main/target/FOXEERF722DUAL/target.mk delete mode 100644 src/main/target/FRSKYF3/target.mk delete mode 100755 src/main/target/FRSKYF4/target.mk delete mode 100644 src/main/target/FRSKYPILOT/target.mk delete mode 100755 src/main/target/FRSKY_ROVERF7/target.mk delete mode 100644 src/main/target/FURYF4OSD/MAMBAF405.mk delete mode 100644 src/main/target/FURYF4OSD/target.mk delete mode 100644 src/main/target/HGLRCF722/target.mk delete mode 100644 src/main/target/IFLIGHTF4_SUCCEXD/target.mk delete mode 100644 src/main/target/IFLIGHTF4_TWING/target.mk delete mode 100644 src/main/target/IFLIGHTF7_TWING/target.mk delete mode 100755 src/main/target/KAKUTEF4/KAKUTEF4V2.mk delete mode 100755 src/main/target/KAKUTEF4/target.mk delete mode 100644 src/main/target/KAKUTEF7/KAKUTEF7HDV.mk delete mode 100644 src/main/target/KAKUTEF7/KAKUTEF7MINI.mk delete mode 100755 src/main/target/KAKUTEF7/target.mk delete mode 100644 src/main/target/LUX_RACE/target.mk delete mode 100644 src/main/target/MAMBAF405US/target.mk delete mode 100644 src/main/target/MAMBAF722/target.mk delete mode 100755 src/main/target/MATEKF405/MATEKF405OSD.mk delete mode 100755 src/main/target/MATEKF405/MATEKF405_SERVOS6.mk delete mode 100755 src/main/target/MATEKF405/target.mk delete mode 100644 src/main/target/MATEKF405SE/target.mk delete mode 100644 src/main/target/MATEKF411/MATEKF411_FD_SFTSRL.mk delete mode 100644 src/main/target/MATEKF411/MATEKF411_RSSI.mk delete mode 100644 src/main/target/MATEKF411/MATEKF411_SFTSRL2.mk delete mode 100755 src/main/target/MATEKF411/target.mk delete mode 100755 src/main/target/MATEKF411SE/target.mk delete mode 100644 src/main/target/MATEKF722/MATEKF722_HEXSERVO.mk delete mode 100755 src/main/target/MATEKF722/target.mk delete mode 100755 src/main/target/MATEKF722PX/target.mk delete mode 100644 src/main/target/MATEKF722SE/MATEKF722MINI.mk delete mode 100644 src/main/target/MATEKF722SE/target.mk delete mode 100644 src/main/target/MATEKF765/target.mk delete mode 100644 src/main/target/MOTOLAB/target.mk delete mode 100755 src/main/target/NOX/target.mk delete mode 100755 src/main/target/OMNIBUSF4/DYSF4PRO.mk delete mode 100755 src/main/target/OMNIBUSF4/DYSF4PROV2.mk delete mode 100755 src/main/target/OMNIBUSF4/OMNIBUSF4PRO.mk delete mode 100755 src/main/target/OMNIBUSF4/OMNIBUSF4PRO_LEDSTRIPM5.mk delete mode 100755 src/main/target/OMNIBUSF4/OMNIBUSF4V3.mk delete mode 100644 src/main/target/OMNIBUSF4/OMNIBUSF4V3_S5S6_SS.mk delete mode 100644 src/main/target/OMNIBUSF4/OMNIBUSF4V3_S5_S6_2SS.mk delete mode 100644 src/main/target/OMNIBUSF4/OMNIBUSF4V3_S6_SS.mk delete mode 100644 src/main/target/OMNIBUSF4/target.mk delete mode 100755 src/main/target/OMNIBUSF7/OMNIBUSF7V2.mk delete mode 100644 src/main/target/OMNIBUSF7/target.mk delete mode 100644 src/main/target/OMNIBUSF7NXT/target.mk delete mode 100644 src/main/target/PIKOBLX/target.mk delete mode 100755 src/main/target/PIXRACER/target.mk delete mode 100644 src/main/target/RCEXPLORERF3/target.mk delete mode 100644 src/main/target/REVO/target.mk delete mode 100644 src/main/target/RMDO/target.mk delete mode 100644 src/main/target/SPARKY/target.mk delete mode 100644 src/main/target/SPARKY2/target.mk delete mode 100644 src/main/target/SPEEDYBEEF4/SPEEDYBEEF4_SFTSRL1.mk delete mode 100644 src/main/target/SPEEDYBEEF4/SPEEDYBEEF4_SFTSRL2.mk delete mode 100644 src/main/target/SPEEDYBEEF4/target.mk delete mode 100644 src/main/target/SPEEDYBEEF7/target.mk delete mode 100644 src/main/target/SPRACINGF3/target.mk delete mode 100644 src/main/target/SPRACINGF3MINI/target.mk delete mode 100755 src/main/target/SPRACINGF4EVO/target.mk delete mode 100644 src/main/target/SPRACINGF7DUAL/target.mk delete mode 100644 src/main/target/YUPIF7/target.mk delete mode 100755 src/main/target/ZEEZF7/target.mk diff --git a/Makefile b/Makefile deleted file mode 100644 index 5b95e5a6acb..00000000000 --- a/Makefile +++ /dev/null @@ -1,549 +0,0 @@ -############################################################################### -# "THE BEER-WARE LICENSE" (Revision 42): -# wrote this file. As long as you retain this notice you -# can do whatever you want with this stuff. If we meet some day, and you think -# this stuff is worth it, you can buy me a beer in return -############################################################################### -# -# Makefile for building the iNav firmware. -# -# Invoke this with 'make help' to see the list of supported targets. -# -############################################################################### - -# Root directory -ROOT := $(patsubst %/,%,$(dir $(lastword $(MAKEFILE_LIST)))) - -# developer preferences, edit these at will, they'll be gitignored --include $(ROOT)/make/local.mk - -# Things that the user might override on the commandline -# - -# The target to build, see VALID_TARGETS below -TARGET ?= REVO - -# Compile-time options -OPTIONS ?= - -# Debugger optons, must be empty or GDB -DEBUG ?= - -SEMIHOSTING ?= - -# Build suffix -BUILD_SUFFIX ?= - -# Serial port/Device for flashing -SERIAL_DEVICE ?= $(firstword $(wildcard /dev/ttyUSB*) no-port-found) - -# Flash size (KB). Some low-end chips actually have more flash than advertised, use this to override. -FLASH_SIZE ?= - -## V : Set verbosity level based on the V= parameter -## V=0 Low -## V=1 High -export AT := @ - -ifndef V -export V0 := -export V1 := $(AT) -export STDOUT := -else ifeq ($(V), 0) -export V0 := $(AT) -export V1 := $(AT) -export STDOUT:= "> /dev/null" -export MAKE := $(MAKE) --no-print-directory -else ifeq ($(V), 1) -export V0 := -export V1 := -export STDOUT := -endif - -############################################################################### -# Things that need to be maintained as the source changes -# - -# Working directories -SRC_DIR := $(ROOT)/src/main -BL_SRC_DIR := $(ROOT)/src/bl -OBJECT_DIR := $(ROOT)/obj/main -BL_OBJECT_DIR := $(ROOT)/obj/bl -BIN_DIR := $(ROOT)/obj -CMSIS_DIR := $(ROOT)/lib/main/CMSIS -INCLUDE_DIRS := $(SRC_DIR) \ - $(ROOT)/src/main/target -LINKER_DIR := $(ROOT)/src/main/target/link - -# import macros common to all supported build systems -include $(ROOT)/make/system-id.mk - -# default xtal value for F4 targets -HSE_VALUE = 8000000 -MHZ_VALUE ?= - -# used for turning on features like VCP and SDCARD -FEATURES = - -include $(ROOT)/make/version.mk -include $(ROOT)/make/targets.mk - -BUILD_DATE = $(shell date +%Y%m%d) - -# Search path for sources -FATFS_DIR = $(ROOT)/lib/main/FatFS -FATFS_SRC = $(notdir $(wildcard $(FATFS_DIR)/*.c)) - -VPATH := $(SRC_DIR):$(SRC_DIR)/startup -VPATH := $(VPATH):$(ROOT)/make/mcu -VPATH := $(VPATH):$(ROOT)/make -VPATH := $(VPATH):$(BL_SRC_DIR) - -CSOURCES := $(shell find $(SRC_DIR) -name '*.c') - -# start specific includes -include $(ROOT)/make/mcu/STM32.mk -include $(ROOT)/make/mcu/$(TARGET_MCU_GROUP).mk - -BL_LD_SCRIPT := $(basename $(LD_SCRIPT))_bl.ld - -ifneq ($(FOR_BL),) - LD_SCRIPT := $(basename $(LD_SCRIPT))_for_bl.ld -endif - -# Configure default flash sizes for the targets (largest size specified gets hit first) if flash not specified already. -ifeq ($(FLASH_SIZE),) -ifneq ($(TARGET_FLASH),) -FLASH_SIZE := $(TARGET_FLASH) -else -$(error FLASH_SIZE not configured for target $(TARGET)) -endif -endif - -# Configure devide and target-specific defines and compiler flags -DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE) -TARGET_FLAGS := $(TARGET_FLAGS) -D$(TARGET_MCU) -D$(TARGET_MCU_GROUP) -D$(TARGET) - -ifneq ($(HSE_VALUE),) -DEVICE_FLAGS := $(DEVICE_FLAGS) -DHSE_VALUE=$(HSE_VALUE) -endif - -ifneq ($(MHZ_VALUE),) -DEVICE_FLAGS := $(DEVICE_FLAGS) -DMHZ_VALUE=$(MHZ_VALUE) -endif - -ifneq ($(BASE_TARGET), $(TARGET)) -TARGET_FLAGS := $(TARGET_FLAGS) -D$(BASE_TARGET) -endif - -TARGET_DIR = $(ROOT)/src/main/target/$(BASE_TARGET) -TARGET_DIR_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c)) - -INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(ROOT)/lib/main/MAVLink - -INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(TARGET_DIR) - -VPATH := $(VPATH):$(TARGET_DIR) - -.DEFAULT_GOAL := hex - -include $(ROOT)/make/source.mk -include $(ROOT)/make/release.mk - -############################################################################### -# -# Toolchain installer -# - -TOOLS_DIR := $(ROOT)/tools -DL_DIR := $(ROOT)/downloads - -include $(ROOT)/make/tools.mk - -# -# Tool names -# -CROSS_CC = $(ARM_SDK_PREFIX)gcc -OBJCOPY = $(ARM_SDK_PREFIX)objcopy -SIZE = $(ARM_SDK_PREFIX)size -COMBINE_TOOL := src/utils/combine_tool - -# -# Tool options. -# - -# Save original CFLAGS before modifying them, so we don't -# add them twice when calling this Makefile recursively -# for each target -SAVED_CFLAGS := $(CFLAGS) - -ifeq ($(DEBUG),GDB) -LTO_FLAGS = -else -LTO_FLAGS = -flto -fuse-linker-plugin -endif - -ifneq ($(SEMIHOSTING),) -SEMIHOSTING_CFLAGS = -DSEMIHOSTING -SEMIHOSTING_LDFLAGS = --specs=rdimon.specs -lc -lrdimon -SYSLIB := -else -SEMIHOSTING_CFLAGS = -SEMIHOSTING_LDFLAGS = -SYSLIB := -lnosys -endif - -DEBUG_FLAGS = -ggdb3 -DDEBUG - -CFLAGS += $(ARCH_FLAGS) \ - $(LTO_FLAGS) \ - $(addprefix -D,$(OPTIONS)) \ - $(addprefix -I,$(INCLUDE_DIRS)) \ - $(DEBUG_FLAGS) \ - $(SEMIHOSTING_CFLAGS) \ - -std=gnu99 \ - -Wall -Wextra -Wunsafe-loop-optimizations -Wdouble-promotion \ - -Wstrict-prototypes \ - -Werror=switch \ - -ffunction-sections \ - -fdata-sections \ - -fno-common \ - $(DEVICE_FLAGS) \ - -DUSE_STDPERIPH_DRIVER \ - $(TARGET_FLAGS) \ - -D'__FORKNAME__="$(FORKNAME)"' \ - -D'__TARGET__="$(TARGET)"' \ - -D'__REVISION__="$(REVISION)"' \ - -save-temps=obj \ - -MMD -MP - -BL_CFLAGS = -DMSP_FIRMWARE_UPDATE -DBOOTLOADER - -ifneq ($(FOR_BL),) - CFLAGS += -DMSP_FIRMWARE_UPDATE -endif - -ASFLAGS = $(ARCH_FLAGS) \ - -x assembler-with-cpp \ - $(addprefix -I,$(INCLUDE_DIRS)) \ - -D$(TARGET) \ - -MMD -MP - -LDFLAGS = -lm \ - -nostartfiles \ - --specs=nano.specs \ - -lc \ - $(SYSLIB) \ - $(ARCH_FLAGS) \ - $(LTO_FLAGS) \ - $(DEBUG_FLAGS) \ - $(SEMIHOSTING_LDFLAGS) \ - -static \ - -Wl,-gc-sections,-Map,$(TARGET_MAP) \ - -Wl,-L$(LINKER_DIR) \ - -Wl,--cref \ - -Wl,--no-wchar-size-warning \ - -Wl,--print-memory-usage \ - -T$(LD_SCRIPT) - -BL_LDFLAGS = -lm \ - -nostartfiles \ - --specs=nano.specs \ - -lc \ - $(SYSLIB) \ - $(ARCH_FLAGS) \ - $(LTO_FLAGS) \ - $(DEBUG_FLAGS) \ - $(SEMIHOSTING_LDFLAGS) \ - -static \ - -Wl,-gc-sections,-Map,$(TARGET_BL_MAP) \ - -Wl,-L$(LINKER_DIR) \ - -Wl,--cref \ - -Wl,--no-wchar-size-warning \ - -Wl,--print-memory-usage \ - -T$(BL_LD_SCRIPT) - -############################################################################### -# No user-serviceable parts below -############################################################################### - -CPPCHECK = cppcheck $(CSOURCES) --enable=all --platform=unix64 \ - --std=c99 --inline-suppr --quiet --force \ - $(addprefix -I,$(INCLUDE_DIRS)) \ - -I/usr/include -I/usr/include/linux - -# -# Things we will build -# -TARGET_BIN := $(BIN_DIR)/$(FORKNAME)_$(FC_VER) -TARGET_BIN := $(TARGET_BIN)_$(TARGET) -TARGET_BL_BIN := $(TARGET_BIN)_bl -ifneq ($(BUILD_SUFFIX),) - TARGET_BIN := $(TARGET_BIN)_$(BUILD_SUFFIX) - TARGET_BL_BIN := $(TARGET_BL_BIN)_$(BUILD_SUFFIX) -endif -TARGET_BIN := $(TARGET_BIN).bin -TARGET_BL_BIN := $(TARGET_BL_BIN).bin -TARGET_HEX = $(TARGET_BIN:.bin=.hex) -TARGET_BL_HEX = $(TARGET_BL_BIN:.bin=.hex) -TARGET_COMBINED_HEX = $(basename $(TARGET_HEX))_combined.hex - -TARGET_OBJ_DIR = $(OBJECT_DIR)/$(TARGET) -TARGET_BL_OBJ_DIR = $(BL_OBJECT_DIR)/$(TARGET) -TARGET_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).elf -TARGET_BL_ELF = $(BL_OBJECT_DIR)/$(FORKNAME)_$(TARGET).elf -TARGET_OBJS = $(addsuffix .o,$(addprefix $(TARGET_OBJ_DIR)/,$(basename $(TARGET_SRC)))) -TARGET_BL_OBJS = $(addsuffix .o,$(addprefix $(TARGET_BL_OBJ_DIR)/,$(basename $(TARGET_BL_SRC)))) -TARGET_DEPS = $(addsuffix .d,$(addprefix $(TARGET_OBJ_DIR)/,$(basename $(TARGET_SRC)))) -TARGET_BL_DEPS = $(addsuffix .d,$(addprefix $(TARGET_BL_OBJ_DIR)/,$(basename $(TARGET_BL_SRC)))) -TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map -TARGET_BL_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET)_bl.map - - -CLEAN_ARTIFACTS := $(TARGET_BIN) -CLEAN_ARTIFACTS += $(TARGET_HEX) -CLEAN_ARTIFACTS += $(TARGET_ELF) -CLEAN_ARTIFACTS += $(TARGET_OBJS) $(TARGET_MAP) -CLEAN_ARTIFACTS += $(TARGET_BL_BIN) $(TARGET_BL_HEX) $(TARGET_BL_ELF) $(TARGET_BL_OBJS) $(TARGET_BL_MAP) - -include $(ROOT)/make/stamp.mk -include $(ROOT)/make/settings.mk -include $(ROOT)/make/svd.mk - -# Make sure build date and revision is updated on every incremental build -$(TARGET_OBJ_DIR)/build/version.o $(TARGET_BL_OBJ_DIR)/build/version.o: $(TARGET_SRC) - -# CFLAGS used for ASM generation. These can't include the LTO related options -# since they prevent proper ASM generation. Since $(LTO_FLAGS) includes the -# optization level, we have to add it back. -g is required to make interleaved -# source/ASM work. -ASM_CFLAGS=-g $(OPTIMZE) $(filter-out $(LTO_FLAGS) -save-temps=obj, $(CFLAGS)) - -# List of buildable ELF files and their object dependencies. -# It would be nice to compute these lists, but that seems to be just beyond make. - -$(TARGET_HEX): $(TARGET_ELF) - $(V0) $(OBJCOPY) -O ihex --set-start $(FLASH_ORIGIN) $< $@ - -$(TARGET_BIN): $(TARGET_ELF) - $(V0) $(OBJCOPY) -O binary $< $@ - -$(TARGET_ELF): $(TARGET_OBJS) - $(V1) echo Linking $(TARGET) - $(V1) $(CROSS_CC) -o $@ $(filter %.o, $^) $(LDFLAGS) - $(V0) $(SIZE) $(TARGET_ELF) - -$(TARGET_BL_HEX): $(TARGET_BL_ELF) - $(V0) $(OBJCOPY) -O ihex --set-start $(FLASH_ORIGIN) $< $@ - -$(TARGET_BL_BIN): $(TARGET_BL_ELF) - $(V0) $(OBJCOPY) -O binary $< $@ - -$(TARGET_BL_ELF): $(TARGET_BL_OBJS) - $(V1) echo Linking $(TARGET) bl - $(V1) $(CROSS_CC) -o $@ $(filter %.o, $^) $(BL_LDFLAGS) - $(V0) $(SIZE) $(TARGET_BL_ELF) - -OPTIMIZE_FLAG_SPEED := "-Os" -OPTIMIZE_FLAG_SIZE := "-Os" -OPTIMIZE_FLAG_NORMAL := "-Os" - -ifneq ($(TARGET_MCU_GROUP), STM32F3) - OPTIMIZE_FLAG_SPEED := "-Ofast" - OPTIMIZE_FLAG_SIZE := "-Os" - OPTIMIZE_FLAG_NORMAL := "-O2" -endif - -define compile_file - echo "%% $(1) $(2) $<" "$(STDOUT)" && \ - $(CROSS_CC) -c -o $@ $(CFLAGS) $(2) $< -endef - -define compile_bl_file - echo "%% $(1) $(2) $<" "$(STDOUT)" && \ - $(CROSS_CC) -c -o $@ $(CFLAGS) $(BL_CFLAGS) $(2) $< -endef - -# Compile -$(TARGET_OBJ_DIR)/%.o: %.c - $(V1) mkdir -p $(dir $@) - - $(V1) $(if $(findstring $<,$(SIZE_OPTIMISED_SRC)), \ - $(call compile_file,(size),$(OPTIMIZE_FLAG_SIZE)) \ - , \ - $(if $(findstring $<,$(SPEED_OPTIMISED_SRC)), \ - $(call compile_file,(speed),$(OPTIMIZE_FLAG_SPEED)) \ - , \ - $(call compile_file,(normal),$(OPTIMIZE_FLAG_NORMAL)) \ - ) \ - ) -ifeq ($(GENERATE_ASM), 1) - $(V1) $(CROSS_CC) -S -fverbose-asm -Wa,-aslh -o $(patsubst %.o,%.txt.S,$@) -g $(ASM_CFLAGS) $< -endif - -$(TARGET_BL_OBJ_DIR)/%.o: %.c - $(V1) mkdir -p $(dir $@) - - $(V1) $(if $(findstring $<,$(SIZE_OPTIMISED_SRC)), \ - $(call compile_bl_file,(size),$(OPTIMIZE_FLAG_SIZE)) \ - , \ - $(if $(findstring $<,$(SPEED_OPTIMISED_SRC)), \ - $(call compile_bl_file,(speed),$(OPTIMIZE_FLAG_SPEED)) \ - , \ - $(call compile_bl_file,(normal),$(OPTIMIZE_FLAG_NORMAL)) \ - ) \ - ) -ifeq ($(GENERATE_ASM), 1) - $(V1) $(CROSS_CC) -S -fverbose-asm -Wa,-aslh -o $(patsubst %.o,%.txt.S,$@) -g $(ASM_CFLAGS) $(BL_CFLAGS) $< -endif - -# Assemble -$(TARGET_OBJ_DIR)/%.o $(TARGET_BL_OBJ_DIR)/%.o: %.s - $(V1) mkdir -p $(dir $@) - $(V1) echo %% $(notdir $<) "$(STDOUT)" - $(V1) $(CROSS_CC) -c -o $@ $(ASFLAGS) $< - -$(TARGET_OBJ_DIR)/%.o $(TARGET_BL_OBJ_DIR)/%.o: %.S - $(V1) mkdir -p $(dir $@) - $(V1) echo %% $(notdir $<) "$(STDOUT)" - $(V1) $(CROSS_CC) -c -o $@ $(ASFLAGS) $< - - -# mkdirs -$(DL_DIR): - mkdir -p $@ - -$(TOOLS_DIR): - mkdir -p $@ - - -## all : Build all valid targets -all: $(VALID_TARGETS) - -## targets-group-rest: build targets specified in release-targets list -release: $(RELEASE_TARGETS) - -$(VALID_TARGETS): - $(V0) echo "" && \ - echo "Building $@" && \ - CFLAGS=$(SAVED_CFLAGS) $(MAKE) -j 8 TARGET=$@ && \ - echo "Building $@ succeeded." - -$(VALID_BL_TARGETS): - $(V0) echo "" && \ - echo "Building $@" && \ - CFLAGS=$(SAVED_CFLAGS) $(MAKE) -j 8 TARGET=$(@:%_bl=%) bl_binary bl_hex && \ - echo "Building $(@:%_bl=%) bl succeeded." - -$(VALID_TARGETS_FOR_BL): - $(V0) echo "" && \ - echo "Building $@" && \ - CFLAGS=$(SAVED_CFLAGS) $(MAKE) -j 8 TARGET=$(@:%_for_bl=%) FOR_BL=1 binary hex && \ - echo "Building $(@:%_for_bl=%) for bl succeeded." - -$(VALID_TARGETS_WITH_BL): - $(V0) echo "" && \ - echo "Building $@ with bl" && \ - CFLAGS=$(SAVED_CFLAGS) $(MAKE) TARGET=$(@:%_with_bl=%) combined_hex && \ - echo "Building $(@:%_with_bl=%) with bl succeeded." - -combined_hex: - $(V1) echo "Building combined BL+MAIN hex" && \ - CFLAGS=$(SAVED_CFLAGS) $(MAKE) -j 8 TARGET=$(TARGET) bl_binary && \ - CFLAGS=$(SAVED_CFLAGS) $(MAKE) -j 8 TARGET=$(TARGET) binary FOR_BL=1 && \ - echo "Combining MAIN+BL in $(TARGET_COMBINED_HEX)" && \ - $(COMBINE_TOOL) $(TARGET_BL_BIN) $(TARGET_BIN) $(TARGET_COMBINED_HEX) - -## clean : clean up all temporary / machine-generated files -clean: - $(V0) echo "Cleaning $(TARGET)" - $(V0) rm -f $(CLEAN_ARTIFACTS) - $(V0) rm -rf $(TARGET_OBJ_DIR) - $(V0) echo "Cleaning $(TARGET) succeeded." - -## clean_test : clean up all temporary / machine-generated files (tests) -clean_test: - $(V0) $(RM) -r src/test/build - -## clean_ : clean up one specific target -$(CLEAN_TARGETS) : - $(V0) $(MAKE) -j 8 TARGET=$(subst clean_,,$@) clean - -## _clean : clean up one specific target (alias for above) -$(TARGETS_CLEAN) : - $(V0) $(MAKE) -j 8 TARGET=$(subst _clean,,$@) clean - -## clean_all : clean all valid targets -clean_all:$(CLEAN_TARGETS) - -## all_clean : clean all valid targets (alias for above) -all_clean:$(TARGETS_CLEAN) - -flash_$(TARGET): $(TARGET_HEX) - $(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon - $(V0) echo -n 'R' >$(SERIAL_DEVICE) - $(V0) stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) - -## flash : flash firmware (.hex) onto flight controller -flash: flash_$(TARGET) - -$(STFLASH_TARGETS) : - $(V0) $(MAKE) -j 8 TARGET=$(subst st-flash_,,$@) st-flash - -## st-flash : flash firmware (.bin) onto flight controller -st-flash: $(TARGET_BIN) - $(V0) st-flash --reset write $< $(FLASH_ORIGIN) - -elf: $(TARGET_ELF) -binary: $(TARGET_BIN) -hex: $(TARGET_HEX) -bl_elf: $(TARGET_BL_ELF) -bl_binary: $(TARGET_BL_BIN) -bl_hex: $(TARGET_BL_HEX) - -unbrick_$(TARGET): $(TARGET_HEX) - $(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon - $(V0) stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) - -## unbrick : unbrick flight controller -unbrick: unbrick_$(TARGET) - -## cppcheck : run static analysis on C source code -cppcheck: $(CSOURCES) - $(V0) $(CPPCHECK) - -cppcheck-result.xml: $(CSOURCES) - $(V0) $(CPPCHECK) --xml-version=2 2> cppcheck-result.xml - -## help : print this help message and exit -help: Makefile - $(V0) @echo "" - $(V0) @echo "Makefile for the $(FORKNAME) firmware" - $(V0) @echo "" - $(V0) @echo "Usage:" - $(V0) @echo " make [TARGET=] [OPTIONS=\"\"]" - $(V0) @echo "Or:" - $(V0) @echo " make [OPTIONS=\"\"]" - $(V0) @echo "" - $(V0) @echo "Valid TARGET values are: $(VALID_TARGETS)" - $(V0) @echo "" - $(V0) @sed -n 's/^## //p' $< - -## test : run the cleanflight test suite -test: - $(V0) mkdir -p src/test/build && cd src/test/build && cmake .. && $(MAKE) check - -# rebuild everything when makefile changes -# Make the generated files and the build stamp order only prerequisites, -# so they will be generated before TARGET_OBJS but regenerating them -# won't cause all TARGET_OBJS to be rebuilt. -$(TARGET_OBJS) : Makefile | $(GENERATED_FILES) $(STAMP) - -# include auto-generated dependencies --include $(TARGET_DEPS) - -# Developer tools -include $(ROOT)/make/openocd.mk -include $(ROOT)/make/gdb.mk diff --git a/make/gdb.mk b/make/gdb.mk deleted file mode 100644 index aeb29b38daa..00000000000 --- a/make/gdb.mk +++ /dev/null @@ -1,17 +0,0 @@ -GDB ?= $(ARM_SDK_PREFIX)gdb -GDB_REMOTE ?= localhost:3333 - -GDB_OPENOCD_INIT_CMDS ?= -GDB_OPENOCD_INIT_CMDS += -ex "monitor reset halt" -ifneq ($(LOAD),) -GDB_OPENOCD_INIT_CMDS += -ex load -endif -ifneq ($(SEMIHOSTING),) -GDB_OPENOCD_INIT_CMDS += -ex "monitor arm semihosting enable" -endif - -gdb-openocd: $(TARGET_ELF) - $(GDB) $< -ex "target remote $(GDB_REMOTE)" $(GDB_OPENOCD_INIT_CMDS) - -gdb-openocd-bl: $(TARGET_BL_ELF) - $(GDB) $< -ex "target remote $(GDB_REMOTE)" $(GDB_OPENOCD_INIT_CMDS) diff --git a/make/mcu/STM32.mk b/make/mcu/STM32.mk deleted file mode 100644 index 2c1636561ef..00000000000 --- a/make/mcu/STM32.mk +++ /dev/null @@ -1 +0,0 @@ -FLASH_ORIGIN ?= 0x08000000 diff --git a/make/mcu/STM32F3.mk b/make/mcu/STM32F3.mk deleted file mode 100644 index b7b05eff3b3..00000000000 --- a/make/mcu/STM32F3.mk +++ /dev/null @@ -1,82 +0,0 @@ -# -# F3 Make file include -# - -ifeq ($(OPBL),yes) -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F303_$(FLASH_SIZE)k_opbl.ld -endif - -TARGET_FLASH := 256 -MCU_COMMON_SRC = startup_stm32f30x_md_gcc.S - -STDPERIPH_DIR = $(ROOT)/lib/main/STM32F3/Drivers/STM32F30x_StdPeriph_Driver -STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) -EXCLUDES = stm32f30x_crc.c \ - stm32f30x_can.c -STARTUP_SRC = startup_stm32f30x_md_gcc.S - -STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) -DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC) - -VPATH := $(VPATH):$(CMSIS_DIR)/Core/Include -CMSIS_SRC = $(notdir $(wildcard $(ROOT)/lib/main/STM32F3/Drivers/CMSIS/Device/ST/STM32F30x/*.c)) - -INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(STDPERIPH_DIR)/inc \ - $(CMSIS_DIR)/Core/Include \ - $(ROOT)/lib/main/STM32F3/Drivers/CMSIS/Device/ST/STM32F30x - -ifneq ($(filter VCP, $(FEATURES)),) -USBFS_DIR = $(ROOT)/lib/main/STM32_USB-FS-Device_Driver -USBPERIPH_SRC = $(notdir $(wildcard $(USBFS_DIR)/src/*.c)) - -INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(USBFS_DIR)/inc \ - $(ROOT)/src/main/vcp - -VPATH := $(VPATH):$(USBFS_DIR)/src - -DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC)\ - $(USBPERIPH_SRC) -endif - -ifneq ($(filter SDCARD, $(FEATURES)),) -INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(FATFS_DIR) \ - -VPATH := $(VPATH):$(FATFS_DIR) -endif - -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F303_$(FLASH_SIZE)k.ld - -ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion -DEVICE_FLAGS = -DSTM32F303xC -DSTM32F303 - -VCP_SRC = \ - vcp/hw_config.c \ - vcp/stm32_it.c \ - vcp/usb_desc.c \ - vcp/usb_endp.c \ - vcp/usb_istr.c \ - vcp/usb_prop.c \ - vcp/usb_pwr.c \ - drivers/serial_usb_vcp.c \ - drivers/usb_io.c - - -MCU_COMMON_SRC = \ - startup_stm32f30x_md_gcc.S \ - target/system_stm32f30x.c \ - drivers/accgyro/accgyro.c \ - drivers/adc_stm32f30x.c \ - drivers/bus_i2c_stm32f30x.c \ - drivers/dma_stm32f3xx.c \ - drivers/serial_uart_stm32f30x.c \ - drivers/system_stm32f30x.c \ - drivers/timer_impl_stdperiph.c \ - drivers/timer_stm32f30x.c \ - src/main/drivers/bus_spi.c - - -DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP -DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM4 diff --git a/make/mcu/STM32F4.mk b/make/mcu/STM32F4.mk deleted file mode 100644 index 2216605fee4..00000000000 --- a/make/mcu/STM32F4.mk +++ /dev/null @@ -1,227 +0,0 @@ -# -# F4 Make file include -# - -#CMSIS -ifeq ($(PERIPH_DRIVER), HAL) -CMSIS_DIR := $(ROOT)/lib/main/STM32F4/Drivers/CMSIS -STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4/Drivers/STM32F4xx_HAL_Driver -STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/Src/*.c)) -EXCLUDES = -else -USBFS_DIR = $(ROOT)/lib/main/STM32_USB-FS-Device_Driver -USBPERIPH_SRC = $(notdir $(wildcard $(USBFS_DIR)/src/*.c)) -CMSIS_DIR := $(ROOT)/lib/main/CMSIS -STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver -STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) -EXCLUDES = stm32f4xx_crc.c \ - stm32f4xx_can.c \ - stm32f4xx_fmc.c \ - stm32f4xx_sai.c \ - stm32f4xx_cec.c \ - stm32f4xx_dsi.c \ - stm32f4xx_flash_ramfunc.c \ - stm32f4xx_fmpi2c.c \ - stm32f4xx_lptim.c \ - stm32f4xx_qspi.c \ - stm32f4xx_spdifrx.c \ - stm32f4xx_cryp.c \ - stm32f4xx_cryp_aes.c \ - stm32f4xx_hash_md5.c \ - stm32f4xx_cryp_des.c \ - stm32f4xx_hash.c \ - stm32f4xx_dbgmcu.c \ - stm32f4xx_cryp_tdes.c \ - stm32f4xx_hash_sha1.c -endif - -ifeq ($(TARGET),$(filter $(TARGET), $(F411_TARGETS))) -EXCLUDES += stm32f4xx_fsmc.c -TARGET_FLASH := 512 -else ifeq ($(TARGET),$(filter $(TARGET), $(F446_TARGETS))) -EXCLUDES += stm32f4xx_fsmc.c -TARGET_FLASH := 512 -else ifeq ($(TARGET),$(filter $(TARGET), $(F427_TARGETS))) -EXCLUDES += stm32f4xx_fsmc.c -TARGET_FLASH := 1024 -else -TARGET_FLASH := 1024 -endif - -STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) - -ifeq ($(PERIPH_DRIVER), HAL) -#USB -USBCORE_DIR = $(ROOT)/lib/main/STM32F4/Middlewares/ST/STM32_USB_Device_Library/Core -USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/Src/*.c)) -EXCLUDES = usbd_conf_template.c -USBCORE_SRC := $(filter-out ${EXCLUDES}, $(USBCORE_SRC)) - -USBCDC_DIR = $(ROOT)/lib/main/STM32F4/Middlewares/ST/STM32_USB_Device_Library/Class/CDC -USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/Src/*.c)) -EXCLUDES = usbd_cdc_if_template.c -USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC)) - -VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src - -DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \ - $(USBCORE_SRC) \ - $(USBCDC_SRC) -else -USBCORE_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Core -USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/src/*.c)) -USBOTG_DIR = $(ROOT)/lib/main/STM32_USB_OTG_Driver -USBOTG_SRC = $(notdir $(wildcard $(USBOTG_DIR)/src/*.c)) -EXCLUDES = usb_bsp_template.c \ - usb_conf_template.c \ - usb_hcd_int.c \ - usb_hcd.c \ - usb_otg.c - -USBOTG_SRC := $(filter-out ${EXCLUDES}, $(USBOTG_SRC)) -USBCDC_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/cdc -USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/src/*.c)) -EXCLUDES = usbd_cdc_if_template.c -USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC)) -USBMSC_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/msc -USBMSC_SRC = $(notdir $(wildcard $(USBMSC_DIR)/src/*.c)) -EXCLUDES = usbd_storage_template.c -USBMSC_SRC := $(filter-out ${EXCLUDES}, $(USBMSC_SRC)) -USBHID_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/hid -USBHID_SRC = $(notdir $(wildcard $(USBHID_DIR)/src/*.c)) -USBWRAPPER_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/hid_cdc_wrapper -USBWRAPPER_SRC = $(notdir $(wildcard $(USBWRAPPER_DIR)/src/*.c)) -VPATH := $(VPATH):$(USBOTG_DIR)/src:$(USBCORE_DIR)/src:$(USBCDC_DIR)/src:$(USBMSC_DIR)/src:$(USBHID_DIR)/src:$(USBWRAPPER_DIR)/src - -DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \ - $(USBOTG_SRC) \ - $(USBCORE_SRC) \ - $(USBCDC_SRC) \ - $(USBHID_SRC) \ - $(USBWRAPPER_SRC) \ - $(USBMSC_SRC) -endif - -#CMSIS -VPATH := $(VPATH):$(CMSIS_DIR)/Core/Include:$(ROOT)/lib/main/STM32F4/Drivers/CMSIS/Device/ST/STM32F4xx - -ifeq ($(PERIPH_DRIVER), HAL) -CMSIS_SRC := -INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(STDPERIPH_DIR)/Inc \ - $(USBCORE_DIR)/Inc \ - $(USBCDC_DIR)/Inc \ - $(CMSIS_DIR)/Include \ - $(CMSIS_DIR)/Device/ST/STM32F4xx/Include \ - $(ROOT)/src/main/vcp_hal -else -CMSIS_SRC := $(notdir $(wildcard $(CMSIS_DIR)/CoreSupport/*.c \ - $(ROOT)/lib/main/STM32F4/Drivers/CMSIS/Device/ST/STM32F4xx/*.c)) -INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(STDPERIPH_DIR)/inc \ - $(USBOTG_DIR)/inc \ - $(USBCORE_DIR)/inc \ - $(USBCDC_DIR)/inc \ - $(USBHID_DIR)/inc \ - $(USBWRAPPER_DIR)/inc \ - $(USBMSC_DIR)/inc \ - $(USBFS_DIR)/inc \ - $(CMSIS_DIR)/Core/Include \ - $(ROOT)/lib/main/STM32F4/Drivers/CMSIS/Device/ST/STM32F4xx \ - $(ROOT)/src/main/vcpf4 -endif - -ifneq ($(filter SDCARD,$(FEATURES)),) -INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(FATFS_DIR) -VPATH := $(VPATH):$(FATFS_DIR) -endif - -#Flags -ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion - -ifeq ($(TARGET),$(filter $(TARGET),$(F411_TARGETS))) - DEVICE_FLAGS := -DSTM32F411xE - LD_SCRIPT := $(LINKER_DIR)/stm32_flash_F411.ld - STARTUP_SRC := startup_stm32f411xe.s -else ifeq ($(TARGET),$(filter $(TARGET),$(F405_TARGETS))) - DEVICE_FLAGS := -DSTM32F40_41xxx -DSTM32F405xx - LD_SCRIPT := $(LINKER_DIR)/stm32_flash_F405.ld - STARTUP_SRC := startup_stm32f40xx.s -else ifeq ($(TARGET),$(filter $(TARGET),$(F446_TARGETS))) - DEVICE_FLAGS := -DSTM32F446xx - LD_SCRIPT := $(LINKER_DIR)/stm32_flash_F446.ld - STARTUP_SRC := startup_stm32f446xx.s -else ifeq ($(TARGET),$(filter $(TARGET),$(F427_TARGETS))) - DEVICE_FLAGS := -DSTM32F427_437xx - LD_SCRIPT := $(LINKER_DIR)/stm32_flash_F427.ld - STARTUP_SRC := startup_stm32f427xx.s -else - $(error Unknown MCU for F4 target) -endif - -DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) - -MCU_COMMON_SRC = \ - target/system_stm32f4xx.c \ - drivers/accgyro/accgyro.c \ - drivers/accgyro/accgyro_mpu.c \ - drivers/adc_stm32f4xx.c \ - drivers/adc_stm32f4xx.c \ - drivers/bus_i2c_stm32f40x.c \ - drivers/bus_spi.c \ - drivers/serial_softserial.c \ - drivers/serial_uart_stm32f4xx.c \ - drivers/system_stm32f4xx.c \ - drivers/timer.c \ - drivers/timer_impl_stdperiph.c \ - drivers/timer_stm32f4xx.c \ - drivers/uart_inverter.c \ - drivers/dma_stm32f4xx.c \ - drivers/sdcard/sdmmc_sdio_f4xx.c - -ifeq ($(PERIPH_DRIVER), HAL) -VCP_SRC = \ - vcp_hal/usbd_desc.c \ - vcp_hal/usbd_conf.c \ - vcp_hal/usbd_cdc_interface.c \ - drivers/serial_usb_vcp.c \ - drivers/usb_io.c -else -VCP_SRC = \ - vcpf4/stm32f4xx_it.c \ - vcpf4/usb_bsp.c \ - vcpf4/usbd_desc.c \ - vcpf4/usbd_usr.c \ - vcpf4/usbd_cdc_vcp.c \ - drivers/serial_usb_vcp.c \ - drivers/usb_io.c -endif - -MSC_SRC = \ - drivers/usb_msc_f4xx.c \ - msc/usbd_msc_desc.c \ - msc/usbd_storage.c - -ifneq ($(filter SDCARD,$(FEATURES)),) -MSC_SRC += \ - msc/usbd_storage_sd_spi.c -endif - -ifneq ($(filter SDIO,$(FEATURES)),) -MSC_SRC += \ - msc/usbd_storage_sdio.c -MCU_COMMON_SRC += \ - drivers/sdio_f4xx.c -endif - -ifneq ($(filter ONBOARDFLASH,$(FEATURES)),) -MSC_SRC += \ - msc/usbd_storage_emfat.c \ - msc/emfat.c \ - msc/emfat_file.c -endif - -DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP - -DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM4 diff --git a/make/mcu/STM32F7.mk b/make/mcu/STM32F7.mk deleted file mode 100644 index 2f88a33007f..00000000000 --- a/make/mcu/STM32F7.mk +++ /dev/null @@ -1,212 +0,0 @@ -# -# F7 Make file include -# - -#CMSIS -CMSIS_DIR := $(ROOT)/lib/main/CMSIS - -#STDPERIPH -STDPERIPH_DIR = $(ROOT)/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver -STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/Src/*.c)) -EXCLUDES = stm32f7xx_hal_can.c \ - stm32f7xx_hal_cec.c \ - stm32f7xx_hal_crc.c \ - stm32f7xx_hal_crc_ex.c \ - stm32f7xx_hal_cryp.c \ - stm32f7xx_hal_cryp_ex.c \ - stm32f7xx_hal_dcmi.c \ - stm32f7xx_hal_dcmi_ex.c \ - stm32f7xx_hal_dfsdm.c \ - stm32f7xx_hal_dma2d.c \ - stm32f7xx_hal_dsi.c \ - stm32f7xx_hal_eth.c \ - stm32f7xx_hal_hash.c \ - stm32f7xx_hal_hash_ex.c \ - stm32f7xx_hal_hcd.c \ - stm32f7xx_hal_i2s.c \ - stm32f7xx_hal_irda.c \ - stm32f7xx_hal_iwdg.c \ - stm32f7xx_hal_jpeg.c \ - stm32f7xx_hal_lptim.c \ - stm32f7xx_hal_ltdc.c \ - stm32f7xx_hal_ltdc_ex.c \ - stm32f7xx_hal_mdios.c \ - stm32f7xx_hal_mmc.c \ - stm32f7xx_hal_msp_template.c \ - stm32f7xx_hal_nand.c \ - stm32f7xx_hal_nor.c \ - stm32f7xx_hal_qspi.c \ - stm32f7xx_hal_rng.c \ - stm32f7xx_hal_sai.c \ - stm32f7xx_hal_sai_ex.c \ - stm32f7xx_hal_sd.c \ - stm32f7xx_hal_sdram.c \ - stm32f7xx_hal_smartcard.c \ - stm32f7xx_hal_smartcard_ex.c \ - stm32f7xx_hal_smbus.c \ - stm32f7xx_hal_spdifrx.c \ - stm32f7xx_hal_sram.c \ - stm32f7xx_hal_timebase_rtc_alarm_template.c \ - stm32f7xx_hal_timebase_rtc_wakeup_template.c \ - stm32f7xx_hal_timebase_tim_template.c \ - stm32f7xx_hal_wwdg.c \ - stm32f7xx_ll_adc.c \ - stm32f7xx_ll_crc.c \ - stm32f7xx_ll_dac.c \ - stm32f7xx_ll_exti.c \ - stm32f7xx_ll_fmc.c \ - stm32f7xx_ll_i2c.c \ - stm32f7xx_ll_lptim.c \ - stm32f7xx_ll_pwr.c \ - stm32f7xx_ll_rng.c \ - stm32f7xx_ll_rtc.c \ - stm32f7xx_ll_sdmmc.c \ - stm32f7xx_ll_usart.c - -STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) - -#USB -USBCORE_DIR = $(ROOT)/lib/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Core -USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/Src/*.c)) -EXCLUDES = usbd_conf_template.c -USBCORE_SRC := $(filter-out ${EXCLUDES}, $(USBCORE_SRC)) - -USBCDC_DIR = $(ROOT)/lib/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC -USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/Src/*.c)) -EXCLUDES = usbd_cdc_if_template.c -USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC)) - -USBHID_DIR = $(ROOT)/lib/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/HID -USBHID_SRC = $(notdir $(wildcard $(USBHID_DIR)/Src/*.c)) - -USBHIDCDC_DIR = $(ROOT)/lib/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC_HID -USBHIDCDC_SRC = $(notdir $(wildcard $(USBHIDCDC_DIR)/Src/*.c)) - -USBMSC_DIR = $(ROOT)/lib/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC -USBMSC_SRC = $(notdir $(wildcard $(USBMSC_DIR)/Src/*.c)) -EXCLUDES = usbd_msc_storage_template.c -USBMSC_SRC := $(filter-out ${EXCLUDES}, $(USBMSC_SRC)) - -VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBHID_DIR)/Src:$(USBHIDCDC_DIR)/Src:$(USBMSC_DIR)/Src - -DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \ - $(USBCORE_SRC) \ - $(USBCDC_SRC) \ - $(USBHID_SRC) \ - $(USBHIDCDC_SRC) \ - $(USBMSC_SRC) - -#CMSIS -VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32F7xx -VPATH := $(VPATH):$(STDPERIPH_DIR)/Src -CMSIS_SRC := -INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(STDPERIPH_DIR)/Inc \ - $(USBCORE_DIR)/Inc \ - $(USBCDC_DIR)/Inc \ - $(USBHID_DIR)/Inc \ - $(USBHIDCDC_DIR)/Inc \ - $(USBMSC_DIR)/Inc \ - $(CMSIS_DIR)/Core/Include \ - $(ROOT)/lib/main/STM32F7/Drivers/CMSIS/Device/ST/STM32F7xx/Include \ - $(ROOT)/src/main/vcp_hal - -ifneq ($(filter SDCARD,$(FEATURES)),) -INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(FATFS_DIR) -VPATH := $(VPATH):$(FATFS_DIR) -endif - -#Flags -ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant -Wdouble-promotion - -DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER -ifeq ($(TARGET),$(filter $(TARGET),$(F765XI_TARGETS))) -DEVICE_FLAGS += -DSTM32F765xx -DSTM32F765xI -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f765xi.ld -STARTUP_SRC = startup_stm32f765xx.s -TARGET_FLASH := 2048 -else ifeq ($(TARGET),$(filter $(TARGET),$(F765XG_TARGETS))) -DEVICE_FLAGS += -DSTM32F765xx -DSTM32F765xG -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F7x5xG.ld -STARTUP_SRC = startup_stm32f765xx.s -TARGET_FLASH := 1024 -else ifeq ($(TARGET),$(filter $(TARGET),$(F745XG_TARGETS))) -DEVICE_FLAGS += -DSTM32F745xx -DSTM32F745xG -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F7x5xG.ld -STARTUP_SRC = startup_stm32f745xx.s -TARGET_FLASH := 1024 -else ifeq ($(TARGET),$(filter $(TARGET),$(F7X6XG_TARGETS))) -DEVICE_FLAGS += -DSTM32F746xx -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F746.ld -STARTUP_SRC = startup_stm32f746xx.s -TARGET_FLASH := 2048 -else ifeq ($(TARGET),$(filter $(TARGET),$(F7X2RE_TARGETS))) -DEVICE_FLAGS += -DSTM32F722xx -ifndef LD_SCRIPT -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F7x2.ld -endif -STARTUP_SRC = startup_stm32f722xx.s -TARGET_FLASH := 512 -else -$(error Unknown MCU for F7 target) -endif -DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) - -TARGET_FLAGS = -D$(TARGET) - -VCP_SRC = \ - vcp_hal/usbd_desc.c \ - vcp_hal/usbd_conf.c \ - vcp_hal/usbd_cdc_interface.c \ - drivers/serial_usb_vcp.c \ - drivers/usb_io.c - -MCU_COMMON_SRC = \ - target/system_stm32f7xx.c \ - drivers/accgyro/accgyro.c \ - drivers/accgyro/accgyro_mpu.c \ - drivers/adc_stm32f7xx.c \ - drivers/bus_i2c_hal.c \ - drivers/dma_stm32f7xx.c \ - drivers/bus_spi_hal.c \ - drivers/timer.c \ - drivers/timer_impl_hal.c \ - drivers/timer_stm32f7xx.c \ - drivers/uart_inverter.c \ - drivers/system_stm32f7xx.c \ - drivers/serial_uart_stm32f7xx.c \ - drivers/serial_softserial.c \ - drivers/serial_uart_hal.c \ - drivers/sdcard/sdmmc_sdio_f7xx.c - -MCU_EXCLUDES = \ - drivers/bus_spi.c \ - drivers/bus_i2c.c \ - drivers/serial_uart.c - -MSC_SRC = \ - drivers/usb_msc_f7xx.c \ - msc/usbd_storage.c - -ifneq ($(filter SDIO,$(FEATURES)),) -MCU_COMMON_SRC += \ - drivers/sdio_f7xx.c -MSC_SRC += \ - msc/usbd_storage_sdio.c -endif - -ifneq ($(filter SDCARD,$(FEATURES)),) -MSC_SRC += \ - msc/usbd_storage_sd_spi.c -endif - -ifneq ($(filter ONBOARDFLASH,$(FEATURES)),) -MSC_SRC += \ - msc/usbd_storage_emfat.c \ - msc/emfat.c \ - msc/emfat_file.c -endif - -DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP -DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM7 diff --git a/make/openocd.mk b/make/openocd.mk deleted file mode 100644 index 3a8317ea95a..00000000000 --- a/make/openocd.mk +++ /dev/null @@ -1,49 +0,0 @@ -.PHONY: .FORCE openocd-cfg $(OPENOCD_CFG) openocd-run openocd-flash - -OPENOCD_CFG ?= $(TARGET_OBJ_DIR)/openocd.cfg -CLEAN_ARTIFACTS += $(OPENOCD_CFG) -OPENOCD_CMD ?= openocd - -STLINK ?= 2 - -ifeq ($(OPENOCD_INTERFACE),) -ifeq ($(STLINK),1) -OPENOCD_INTERFACE := stlink-v1 -else ifeq ($(STLINK),2) -OPENOCD_INTERFACE := stlink-v2 -else ifeq ($(STLINK),2.1) -OPENOCD_INTERFACE := stlink-v2-1 -else -$(error Uknown ST Link version $(STLINK)) -endif -endif - -ifeq ($(OPENOCD_TARGET),) -ifeq ($(TARGET_MCU_GROUP),STM32F3) -OPENOCD_TARGET := stm32f3x -else ifeq ($(TARGET_MCU_GROUP),STM32F4) -OPENOCD_TARGET := stm32f4x -else ifeq ($(TARGET_MCU_GROUP),STM32F7) -OPENOCD_TARGET := stm32f7x -endif -endif - -ifeq ($(OPENOCD_TARGET),) -$(warning Unknown OPENOCD_TARGET) -endif - -OPENOCD_CMDLINE := $(OPENOCD_CMD) -f $(OPENOCD_CFG) - -openocd-cfg: $(OPENOCD_CFG) - -$(OPENOCD_CFG): .FORCE - $(V1) mkdir -p $(dir $@) - $(V1) echo "source [find interface/$(OPENOCD_INTERFACE).cfg]" > $@ - $(V1) echo "source [find target/$(OPENOCD_TARGET).cfg]" >> $@ - -openocd-run: $(OPENOCD_CFG) - $(OPENOCD_CMDLINE) - -openocd-flash: $(TARGET_ELF) $(OPENOCD_CFG) - (echo "halt; program $(realpath $<) verify reset" | nc -4 localhost 4444 2>/dev/null) || \ - $(OPENOCD_CMDLINE) -c "program $< verify reset exit" diff --git a/make/release.mk b/make/release.mk deleted file mode 100644 index ecc5955e0cb..00000000000 --- a/make/release.mk +++ /dev/null @@ -1,43 +0,0 @@ -RELEASE_TARGETS = AIRHEROF3 AIRHEROF3_QUAD - -RELEASE_TARGETS += LUX_RACE RCEXPLORERF3 RMDO SPARKY FALCORE MOTOLAB ANYFC BLUEJAYF4 COLIBRI F4BY DALRCF405 DALRCF722DUAL -RELEASE_TARGETS += QUANTON REVO SPARKY2 PIKOBLX CLRACINGF4AIR CLRACINGF4AIRV2 PIXRACER BEEROTORF4 ANYFCF7 ANYFCF7_EXTERNAL_BARO -RELEASE_TARGETS += ALIENFLIGHTNGF7 - -RELEASE_TARGETS += BETAFLIGHTF3 BETAFLIGHTF4 -RELEASE_TARGETS += FF_F35_LIGHTNING FF_FORTINIF4 -RELEASE_TARGETS += KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KAKUTEF7HDV - -RELEASE_TARGETS += SPRACINGF3 SPRACINGF3MINI SPRACINGF4EVO SPRACINGF7DUAL - -RELEASE_TARGETS += AIRBOTF4 ASGARD32F4 ASGARD32F7 FIREWORKSV2 AIRBOTF7 OMNIBUSF7NANOV7 -RELEASE_TARGETS += OMNIBUSF4 OMNIBUSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 DYSF4PRO DYSF4PROV2 -RELEASE_TARGETS += OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS -RELEASE_TARGETS += OMNIBUSF7 OMNIBUSF7V2 OMNIBUSF7NXT YUPIF7 - -# MATEK targets -RELEASE_TARGETS += MATEKF405 MATEKF405_SERVOS6 MATEKF405OSD MATEKF722 MATEKF722_HEXSERVO MATEKF722SE MATEKF722MINI MATEKF405SE MATEKF411 MATEKF411_SFTSRL2 MATEKF411_FD_SFTSRL MATEKF411_RSSI MATEKF411SE MATEKF765 MATEKF722PX -RELEASE_TARGETS += MATEKF765 - -RELEASE_TARGETS += FOXEERF405 FOXEERF722DUAL FOXEERF722V2 - -RELEASE_TARGETS += SPEEDYBEEF4 SPEEDYBEEF7 FRSKYF3 FRSKYF4 - -RELEASE_TARGETS += NOX WINGFC - -RELEASE_TARGETS += OMNIBUSF4V6 - -RELEASE_TARGETS += MAMBAF405 MAMBAF405US MAMBAF722 - -# IFLIGHT targets -RELEASE_TARGETS += IFLIGHTF7_TWING IFLIGHTF4_TWING IFLIGHTF4_SUCCEXD - -RELEASE_TARGETS += AIKONF4 - -RELEASE_TARGETS += ZEEZF7 HGLRCF722 - -RELEASE_TARGETS += FLYWOOF7DUAL FLYWOOF411 - -RELEASE_TARGETS += ZEEZF7 - -RELEASE_TARGETS += FRSKYPILOT FRSKY_ROVERF7 diff --git a/make/settings.mk b/make/settings.mk deleted file mode 100644 index c73ff2e690a..00000000000 --- a/make/settings.mk +++ /dev/null @@ -1,26 +0,0 @@ -# Settings generator -.PHONY: settings clean-settings -UTILS_DIR = $(ROOT)/src/utils -SETTINGS_GENERATOR = $(UTILS_DIR)/settings.rb - -GENERATED_SETTINGS = $(TARGET_OBJ_DIR)/settings_generated.h $(TARGET_OBJ_DIR)/settings_generated.c -SETTINGS_FILE = $(SRC_DIR)/fc/settings.yaml -GENERATED_FILES = $(GENERATED_SETTINGS) -$(GENERATED_SETTINGS): $(SETTINGS_GENERATOR) $(SETTINGS_FILE) $(STAMP) - -CLEAN_ARTIFACTS += $(GENERATED_SETTINGS) - -# Make sure the generated files are in the include path -CFLAGS += -I$(TARGET_OBJ_DIR) - -# Use a pattern rule, since they're different than normal rules. -# See https://www.gnu.org/software/make/manual/make.html#Pattern-Examples -%generated.h %generated.c: - $(V1) echo "settings.yaml -> settings_generated.h, settings_generated.c" "$(STDOUT)" - $(V1) CPP_PATH="$(ARM_SDK_DIR)/bin" CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(SETTINGS_GENERATOR) . $(SETTINGS_FILE) -o $(TARGET_OBJ_DIR) - -settings-json: - $(V0) CPP_PATH="$(ARM_SDK_DIR)/bin" CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(SETTINGS_GENERATOR) . $(SETTINGS_FILE) --json settings.json - -clean-settings: - $(V1) $(RM) $(GENERATED_SETTINGS) diff --git a/make/source.mk b/make/source.mk deleted file mode 100644 index e9e3a33e5be..00000000000 --- a/make/source.mk +++ /dev/null @@ -1,315 +0,0 @@ -COMMON_SRC = \ - common/log.c \ - common/printf.c \ - common/string_light.c \ - common/typeconversion.c \ - drivers/bus.c \ - drivers/bus_busdev_i2c.c \ - drivers/bus_busdev_spi.c \ - drivers/bus_i2c_soft.c \ - drivers/io.c \ - drivers/persistent.c \ - drivers/light_led.c \ - drivers/rcc.c \ - drivers/serial.c \ - drivers/system.c \ - drivers/time.c \ - fc/firmware_update_common.c \ - target/common_hardware.c - -MAIN_SRC = \ - $(TARGET_DIR_SRC) \ - main.c \ - build/assert.c \ - build/build_config.c \ - build/debug.c \ - build/version.c \ - common/bitarray.c \ - common/calibration.c \ - common/colorconversion.c \ - common/crc.c \ - common/encoding.c \ - common/filter.c \ - common/gps_conversion.c \ - common/maths.c \ - common/memory.c \ - common/olc.c \ - common/streambuf.c \ - common/time.c \ - common/uvarint.c \ - programming/logic_condition.c \ - programming/global_variables.c \ - programming/programming_task.c \ - config/config_eeprom.c \ - config/config_streamer.c \ - config/feature.c \ - config/parameter_group.c \ - config/general_settings.c \ - drivers/adc.c \ - drivers/buf_writer.c \ - drivers/display.c \ - drivers/display_canvas.c \ - drivers/display_font_metadata.c \ - drivers/display_widgets.c \ - drivers/exti.c \ - drivers/io_pca9685.c \ - drivers/io_pcf8574.c \ - drivers/io_port_expander.c \ - drivers/osd.c \ - drivers/resource.c \ - drivers/rx_nrf24l01.c \ - drivers/rx_spi.c \ - drivers/rx_xn297.c \ - drivers/pitotmeter_adc.c \ - drivers/pitotmeter_virtual.c \ - drivers/pwm_esc_detect.c \ - drivers/pwm_mapping.c \ - drivers/pwm_output.c \ - drivers/pinio.c \ - drivers/rx_pwm.c \ - drivers/serial_uart.c \ - drivers/sound_beeper.c \ - drivers/stack_check.c \ - drivers/timer.c \ - drivers/usb_msc.c \ - drivers/lights_io.c \ - drivers/1-wire.c \ - drivers/1-wire/ds_crc.c \ - drivers/1-wire/ds2482.c \ - drivers/temperature/ds18b20.c \ - drivers/temperature/lm75.c \ - drivers/pitotmeter_ms4525.c \ - fc/cli.c \ - fc/config.c \ - fc/controlrate_profile.c \ - fc/fc_core.c \ - fc/fc_init.c \ - fc/fc_tasks.c \ - fc/fc_hardfaults.c \ - fc/fc_msp.c \ - fc/fc_msp_box.c \ - fc/firmware_update.c \ - fc/rc_smoothing.c \ - fc/rc_adjustments.c \ - fc/rc_controls.c \ - fc/rc_curves.c \ - fc/rc_modes.c \ - fc/runtime_config.c \ - fc/settings.c \ - fc/stats.c \ - flight/failsafe.c \ - flight/hil.c \ - flight/imu.c \ - flight/mixer.c \ - flight/pid.c \ - flight/pid_autotune.c \ - flight/rth_estimator.c \ - flight/servos.c \ - flight/wind_estimator.c \ - flight/gyroanalyse.c \ - flight/rpm_filter.c \ - flight/dynamic_gyro_notch.c \ - flight/kalman.c \ - io/beeper.c \ - io/esc_serialshot.c \ - io/servo_sbus.c \ - io/frsky_osd.c \ - io/osd_dji_hd.c \ - io/lights.c \ - io/piniobox.c \ - io/pwmdriver_i2c.c \ - io/serial.c \ - io/serial_4way.c \ - io/serial_4way_avrootloader.c \ - io/serial_4way_stk500v2.c \ - io/statusindicator.c \ - io/rcdevice.c \ - io/rcdevice_cam.c \ - msp/msp_serial.c \ - rx/crsf.c \ - rx/eleres.c \ - rx/fport.c \ - rx/fport2.c \ - rx/ibus.c \ - rx/jetiexbus.c \ - rx/msp.c \ - rx/msp_override.c \ - rx/nrf24_cx10.c \ - rx/nrf24_inav.c \ - rx/nrf24_h8_3d.c \ - rx/nrf24_syma.c \ - rx/nrf24_v202.c \ - rx/pwm.c \ - rx/frsky_crc.c \ - rx/rx.c \ - rx/rx_spi.c \ - rx/sbus.c \ - rx/sbus_channels.c \ - rx/spektrum.c \ - rx/sumd.c \ - rx/sumh.c \ - rx/uib_rx.c \ - rx/xbus.c \ - scheduler/scheduler.c \ - sensors/acceleration.c \ - sensors/battery.c \ - sensors/boardalignment.c \ - sensors/compass.c \ - sensors/diagnostics.c \ - sensors/gyro.c \ - sensors/initialisation.c \ - sensors/esc_sensor.c \ - sensors/irlock.c \ - sensors/temperature.c \ - uav_interconnect/uav_interconnect_bus.c \ - uav_interconnect/uav_interconnect_rangefinder.c \ - blackbox/blackbox.c \ - blackbox/blackbox_encoding.c \ - blackbox/blackbox_io.c \ - cms/cms.c \ - cms/cms_menu_battery.c \ - cms/cms_menu_blackbox.c \ - cms/cms_menu_builtin.c \ - cms/cms_menu_imu.c \ - cms/cms_menu_ledstrip.c \ - cms/cms_menu_misc.c \ - cms/cms_menu_mixer_servo.c \ - cms/cms_menu_navigation.c \ - cms/cms_menu_osd.c \ - cms/cms_menu_saveexit.c \ - cms/cms_menu_vtx.c \ - drivers/display_ug2864hsweg01.c \ - drivers/rangefinder/rangefinder_hcsr04.c \ - drivers/rangefinder/rangefinder_hcsr04_i2c.c \ - drivers/rangefinder/rangefinder_srf10.c \ - drivers/rangefinder/rangefinder_vl53l0x.c \ - drivers/rangefinder/rangefinder_virtual.c \ - drivers/opflow/opflow_fake.c \ - drivers/opflow/opflow_virtual.c \ - drivers/vtx_common.c \ - io/rangefinder_msp.c \ - io/rangefinder_benewake.c \ - io/opflow_cxof.c \ - io/opflow_msp.c \ - io/dashboard.c \ - io/displayport_frsky_osd.c \ - io/displayport_max7456.c \ - io/displayport_msp.c \ - io/displayport_oled.c \ - io/displayport_hott.c \ - io/gps.c \ - io/gps_ublox.c \ - io/gps_nmea.c \ - io/gps_naza.c \ - io/ledstrip.c \ - io/osd.c \ - io/osd_canvas.c \ - io/osd_common.c \ - io/osd_grid.c \ - io/osd_hud.c \ - io/smartport_master.c \ - navigation/navigation.c \ - navigation/navigation_fixedwing.c \ - navigation/navigation_fw_launch.c \ - navigation/navigation_geo.c \ - navigation/navigation_multicopter.c \ - navigation/navigation_pos_estimator.c \ - navigation/navigation_pos_estimator_agl.c \ - navigation/navigation_pos_estimator_flow.c \ - navigation/navigation_rover_boat.c \ - sensors/barometer.c \ - sensors/pitotmeter.c \ - sensors/rangefinder.c \ - sensors/opflow.c \ - telemetry/crsf.c \ - telemetry/frsky.c \ - telemetry/frsky_d.c \ - telemetry/hott.c \ - telemetry/ibus_shared.c \ - telemetry/ibus.c \ - telemetry/ltm.c \ - telemetry/mavlink.c \ - telemetry/msp_shared.c \ - telemetry/smartport.c \ - telemetry/sim.c \ - telemetry/telemetry.c \ - io/vtx.c \ - io/vtx_string.c \ - io/vtx_smartaudio.c \ - io/vtx_tramp.c \ - io/vtx_ffpv24g.c \ - io/vtx_control.c - -BL_SRC = \ - bl_main.c - -COMMON_DEVICE_SRC = \ - $(CMSIS_SRC) \ - $(DEVICE_STDPERIPH_SRC) - -TARGET_SRC := $(STARTUP_SRC) $(COMMON_DEVICE_SRC) $(MAIN_SRC) $(COMMON_SRC) $(MCU_COMMON_SRC) $(TARGET_SRC) -TARGET_BL_SRC := $(STARTUP_SRC) $(COMMON_DEVICE_SRC) $(BL_SRC) $(COMMON_SRC) $(MCU_COMMON_SRC) - -#excludes -TARGET_SRC := $(filter-out $(MCU_EXCLUDES), $(TARGET_SRC)) - -ifneq ($(filter ONBOARDFLASH,$(FEATURES)),) -FLASH_SRC += \ - drivers/flash.c \ - drivers/flash_m25p16.c \ - io/flashfs.c \ - $(MSC_SRC) -TARGET_SRC += $(FLASH_SRC) -TARGET_BL_SRC += $(FLASH_SRC) -endif - -ifneq ($(filter SDCARD,$(FEATURES)),) -SDCARD_SRC += \ - drivers/sdcard/sdcard.c \ - drivers/sdcard/sdcard_spi.c \ - drivers/sdcard/sdcard_sdio.c \ - drivers/sdcard/sdcard_standard.c \ - io/asyncfatfs/asyncfatfs.c \ - io/asyncfatfs/fat_standard.c \ - $(MSC_SRC) -TARGET_SRC += $(SDCARD_SRC) -TARGET_BL_SRC += $(SDCARD_SRC) -endif - -ifneq ($(filter VCP,$(FEATURES)),) -TARGET_SRC += $(VCP_SRC) -endif - -ifneq ($(filter MSC,$(FEATURES)),) -TARGET_SRC += $(MSC_SRC) -endif - -ifneq ($(DSP_LIB),) - -INCLUDE_DIRS += $(DSP_LIB)/Include - -TARGET_SRC += $(DSP_LIB)/Source/BasicMathFunctions/arm_mult_f32.c -TARGET_SRC += $(DSP_LIB)/Source/TransformFunctions/arm_rfft_fast_f32.c -TARGET_SRC += $(DSP_LIB)/Source/TransformFunctions/arm_cfft_f32.c -TARGET_SRC += $(DSP_LIB)/Source/TransformFunctions/arm_rfft_fast_init_f32.c -TARGET_SRC += $(DSP_LIB)/Source/TransformFunctions/arm_cfft_radix8_f32.c -TARGET_SRC += $(DSP_LIB)/Source/CommonTables/arm_common_tables.c -TARGET_SRC += $(DSP_LIB)/Source/ComplexMathFunctions/arm_cmplx_mag_f32.c -TARGET_SRC += $(DSP_LIB)/Source/StatisticsFunctions/arm_max_f32.c - -TARGET_SRC += $(wildcard $(DSP_LIB)/Source/*/*.S) -endif - -# Search path and source files for the ST stdperiph library -VPATH := $(VPATH):$(STDPERIPH_DIR)/src - -SIZE_OPTIMISED_SRC := "" -SPEED_OPTIMISED_SRC := "" -ifneq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) -# SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \ - # ./src/main/common/filter.c \ - -# SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \ - # ./src/main/common/maths.c \ - -endif #!F3 diff --git a/make/stamp.mk b/make/stamp.mk deleted file mode 100644 index f68f68d2ae0..00000000000 --- a/make/stamp.mk +++ /dev/null @@ -1,7 +0,0 @@ -.PHONY: .FORCE - -BUILD_STAMP = $(UTILS_DIR)/build_stamp.rb -STAMP = $(TARGET_OBJ_DIR)/build.stamp - -$(STAMP): .FORCE - $(V1) CPP_PATH="$(ARM_SDK_DIR)/bin" CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(BUILD_STAMP) $(SETTINGS_FILE) $(STAMP) diff --git a/make/svd.mk b/make/svd.mk deleted file mode 100644 index 6f749b17ae7..00000000000 --- a/make/svd.mk +++ /dev/null @@ -1,32 +0,0 @@ - -SVDFILE := $(TARGET_OBJ_DIR)/svd.svd -CLEAN_ARTIFACTS += $(SVDFILE) - -.PHONY: $(SVDFILE) - -ifeq ($(TARGET_MCU),STM32F303) -SVD := STM32F303 -else ifeq ($(TARGET_MCU),STM32F405) -SVD := STM32F405 -else ifeq ($(TARGET_MCU),STM32F411) -SVD := STM32F411 -else ifeq ($(TARGET_MCU),STM32F427) -SVD := STM32F427 -else ifeq ($(TARGET_MCU),STM32F446) -SVD := STM32F446 -else ifeq ($(TARGET_MCU),STM32F7X2RE) -SVD := STM32F7x2 -else ifeq ($(TARGET_MCU),STM32F7X5XE) -SVD := STM32F7x5 -else ifeq ($(TARGET_MCU),STM32F7X5XG) -SVD := STM32F7x5 -else ifeq ($(TARGET_MCU),STM32F7X5XI) -SVD := STM32F7x5 -else ifeq ($(TARGET_MCU),STM32F7X6XG) -SVD := STM32F7x6 -endif - -svd: .FORCE $(SVDFILE) -$(SVDFILE): $(ROOT)/dev/svd/$(SVD).svd - $(V1) mkdir -p $(dir $@) - $(V1) cat $< > $@ diff --git a/make/system-id.mk b/make/system-id.mk deleted file mode 100644 index c4c2d817296..00000000000 --- a/make/system-id.mk +++ /dev/null @@ -1,53 +0,0 @@ -# Make sure we know a few things about the architecture -UNAME := $(shell uname) -ARCH := $(shell uname -m) -ifneq (,$(filter $(ARCH), x86_64 amd64)) - X86-64 := 1 - X86_64 := 1 - AMD64 := 1 - ARCHFAMILY := x86_64 -else - ARCHFAMILY := $(ARCH) -endif - -# configure some variables dependent upon what type of system this is - -# Linux -ifeq ($(UNAME), Linux) - OSFAMILY := linux - LINUX := 1 -endif - -# FreeBSD -ifeq ($(UNAME), FreeBSD) - OSFAMILY := linux - LINUX := 1 -endif - - -# Mac OSX -ifeq ($(UNAME), Darwin) - OSFAMILY := macosx - MACOSX := 1 -endif - -# Windows using MinGW shell -ifeq (MINGW, $(findstring MINGW,$(UNAME))) - OSFAMILY := windows - MINGW := 1 - WINDOWS := 1 -endif - -# Windows using Cygwin shell -ifeq (CYGWIN ,$(findstring CYGWIN,$(UNAME))) - OSFAMILY := windows - WINDOWS := 1 - CYGWIN := 1 -endif - -# report an error if we couldn't work out what OS this is running on -ifndef OSFAMILY - $(info uname reports $(UNAME)) - $(info uname -m reports $(ARCH)) - $(error failed to detect operating system) -endif \ No newline at end of file diff --git a/make/targets.mk b/make/targets.mk deleted file mode 100644 index f3150c9c7b2..00000000000 --- a/make/targets.mk +++ /dev/null @@ -1,125 +0,0 @@ -ALT_TARGETS = $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.mk))))) - -VALID_TARGETS = $(dir $(wildcard $(ROOT)/src/main/target/*/target.mk)) -VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS))) -VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS) -VALID_TARGETS := $(sort $(VALID_TARGETS)) - -VALID_BL_TARGETS := $(addsuffix _bl,$(VALID_TARGETS)) -VALID_TARGETS_FOR_BL := $(addsuffix _for_bl,$(VALID_TARGETS)) -VALID_TARGETS_WITH_BL := $(addsuffix _with_bl,$(VALID_TARGETS)) - -CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) ) -TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) ) -STFLASH_TARGETS = $(addprefix st-flash_,$(VALID_TARGETS) ) - -ifeq ($(filter $(TARGET),$(ALT_TARGETS)), $(TARGET)) -BASE_TARGET := $(firstword $(subst /,, $(subst ./src/main/target/,, $(dir $(wildcard $(ROOT)/src/main/target/*/$(TARGET).mk))))) --include $(ROOT)/src/main/target/$(BASE_TARGET)/$(TARGET).mk -else -BASE_TARGET := $(TARGET) -endif - -# silently ignore if the file is not present. Allows for target specific. --include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk - -F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) $(F427_TARGETS) $(F446_TARGETS) -F7_TARGETS = $(F7X2RE_TARGETS) $(F7X5XE_TARGETS) $(F745XG_TARGETS) $(F765XG_TARGETS) $(F765XI_TARGETS) $(F7X6XG_TARGETS) - -ifeq ($(filter $(TARGET),$(VALID_TARGETS)),) -$(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?) -endif - -ifeq ($(filter $(TARGET),$(F3_TARGETS) $(F4_TARGETS) $(F7_TARGETS)),) -$(error Target '$(TARGET)' has not specified a valid STM group, must be one of F3, F405, F411, F427 or F7x. Have you prepared a valid target.mk?) -endif - -ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) -TARGET_MCU := STM32F303 -TARGET_MCU_GROUP := STM32F3 -else ifeq ($(TARGET),$(filter $(TARGET), $(F405_TARGETS))) -TARGET_MCU := STM32F405 -TARGET_MCU_GROUP := STM32F4 -else ifeq ($(TARGET),$(filter $(TARGET), $(F411_TARGETS))) -TARGET_MCU := STM32F411 -TARGET_MCU_GROUP := STM32F4 -else ifeq ($(TARGET),$(filter $(TARGET), $(F427_TARGETS))) -TARGET_MCU := STM32F427 -TARGET_MCU_GROUP := STM32F4 -else ifeq ($(TARGET),$(filter $(TARGET), $(F446_TARGETS))) -TARGET_MCU := STM32F446 -TARGET_MCU_GROUP := STM32F4 -else ifeq ($(TARGET),$(filter $(TARGET), $(F7X2RE_TARGETS))) -TARGET_MCU := STM32F7X2RE -TARGET_MCU_GROUP := STM32F7 -else ifeq ($(TARGET),$(filter $(TARGET), $(F7X5XE_TARGETS))) -TARGET_MCU := STM32F7X5XE -TARGET_MCU_GROUP := STM32F7 -else ifeq ($(TARGET),$(filter $(TARGET), $(F745XG_TARGETS))) -TARGET_MCU := STM32F745XG -TARGET_MCU_GROUP := STM32F7 -else ifeq ($(TARGET),$(filter $(TARGET), $(F765XG_TARGETS))) -TARGET_MCU := STM32F765XG -TARGET_MCU_GROUP := STM32F7 -else ifeq ($(TARGET),$(filter $(TARGET), $(F765XI_TARGETS))) -TARGET_MCU := STM32F765XI -TARGET_MCU_GROUP := STM32F7 -else ifeq ($(TARGET),$(filter $(TARGET), $(F7X6XG_TARGETS))) -TARGET_MCU := STM32F7X6XG -TARGET_MCU_GROUP := STM32F7 -else -$(error Unknown target MCU specified.) -endif - -GROUP_1_TARGETS := AIRHEROF3 AIRHEROF3_QUAD LUX_RACE SPARKY REVO SPARKY2 COLIBRI FALCORE FF_F35_LIGHTNING FF_FORTINIF4 FF_PIKOF4 FF_PIKOF4OSD -GROUP_2_TARGETS := SPRACINGF3 SPRACINGF3MINI SPRACINGF4EVO CLRACINGF4AIR CLRACINGF4AIRV2 BEEROTORF4 BETAFLIGHTF3 BETAFLIGHTF4 PIKOBLX -GROUP_3_TARGETS := AIRBOTF4 BLUEJAYF4 OMNIBUSF4 OMNIBUSF4PRO FIREWORKSV2 SPARKY2 MATEKF405 OMNIBUSF7 DYSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 OMNIBUSF7NXT OMNIBUSF7V2 ASGARD32F4 -GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ALIENFLIGHTNGF7 PIXRACER YUPIF7 MATEKF405SE MATEKF411 MATEKF722 MATEKF405OSD MATEKF405_SERVOS6 NOX -GROUP_5_TARGETS := ASGARD32F7 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF4OSD -GROUP_6_TARGETS := MAMBAF405 OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS AIKONF4 -GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO -GROUP_8_TARGETS := MATEKF765 MATEKF722PX KAKUTEF7HDV ZEEZF7 FOXEERF722V2 FRSKYPILOT FRSKY_ROVERF7 -GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS) $(GROUP_3_TARGETS) $(GROUP_4_TARGETS) $(GROUP_5_TARGETS) $(GROUP_6_TARGETS) $(GROUP_7_TARGETS) $(GROUP_8_TARGETS), $(VALID_TARGETS)) - -## targets-group-1 : build some targets -targets-group-1: $(GROUP_1_TARGETS) - -## targets-group-2 : build some targets -targets-group-2: $(GROUP_2_TARGETS) - -## targets-group-3 : build some targets -targets-group-3: $(GROUP_3_TARGETS) - -## targets-group-4 : build some targets -targets-group-4: $(GROUP_4_TARGETS) - -## targets-group-5 : build some targets -targets-group-5: $(GROUP_5_TARGETS) - -## targets-group-6 : build some targets -targets-group-6: $(GROUP_6_TARGETS) - -## targets-group-7 : build some targets -targets-group-7: $(GROUP_7_TARGETS) - -## targets-group-8 : build some targets -targets-group-8: $(GROUP_8_TARGETS) - -## targets-group-rest: build the rest of the targets (not listed in group 1, 2 or 3) -targets-group-rest: $(GROUP_OTHER_TARGETS) - -## targets : print a list of all valid target platforms (for consumption by scripts) -targets: - $(V0) @echo "Valid targets: $(VALID_TARGETS)" - $(V0) @echo "Target: $(TARGET)" - $(V0) @echo "Base target: $(BASE_TARGET)" - $(V0) @echo "targets-group-1: $(GROUP_1_TARGETS)" - $(V0) @echo "targets-group-2: $(GROUP_2_TARGETS)" - $(V0) @echo "targets-group-3: $(GROUP_3_TARGETS)" - $(V0) @echo "targets-group-4: $(GROUP_4_TARGETS)" - $(V0) @echo "targets-group-5: $(GROUP_5_TARGETS)" - $(V0) @echo "targets-group-6: $(GROUP_6_TARGETS)" - $(V0) @echo "targets-group-7: $(GROUP_7_TARGETS)" - $(V0) @echo "targets-group-8: $(GROUP_8_TARGETS)" - $(V0) @echo "targets-group-rest: $(GROUP_OTHER_TARGETS)" - $(V0) @echo "Release targets: $(RELEASE_TARGETS)" diff --git a/make/tools.mk b/make/tools.mk deleted file mode 100644 index dd56b7a286e..00000000000 --- a/make/tools.mk +++ /dev/null @@ -1,93 +0,0 @@ -############################################################### -# -# Installers for tools -# -# NOTE: These are not tied to the default goals -# and must be invoked manually -# -############################################################### - -GCC_REQUIRED_VERSION ?= 9.2.1 -ARM_SDK_DIR ?= $(TOOLS_DIR)/gcc-arm-none-eabi-9-2019-q4-major -ARM_SDK_URL_BASE := https://armkeil.blob.core.windows.net/developer/Files/downloads/gnu-rm/9-2019q4/gcc-arm-none-eabi-9-2019-q4-major - -.PHONY: arm_sdk_version - -arm_sdk_version: - $(V1) $(ARM_SDK_PREFIX)gcc --version - -.PHONY: arm_sdk_install - -# source: https://developer.arm.com/open-source/gnu-toolchain/gnu-rm/downloads -ifdef LINUX - ARM_SDK_URL := $(ARM_SDK_URL_BASE)-x86_64-linux.tar.bz2 -endif - -ifdef MACOSX - ARM_SDK_URL := $(ARM_SDK_URL_BASE)-mac.tar.bz2 -endif - -ifdef WINDOWS - ARM_SDK_URL := $(ARM_SDK_URL_BASE)-win32.zip -endif - -ARM_SDK_FILE := $(notdir $(ARM_SDK_URL)) -ARM_SDK_DOWNLOAD_PATH := $(DL_DIR)/$(ARM_SDK_FILE) - -SDK_INSTALL_MARKER := $(ARM_SDK_DIR)/bin/arm-none-eabi-gcc-$(GCC_REQUIRED_VERSION) - -.PHONY: arm_sdk_print_filename - -arm_sdk_print_filename: - @echo $(ARM_SDK_FILE) - -.PHONY: arm_sdk_print_download_path - -arm_sdk_print_download_path: - @echo $(ARM_SDK_DOWNLOAD_PATH) - -arm_sdk_install: | $(TOOLS_DIR) - -arm_sdk_install: arm_sdk_download $(SDK_INSTALL_MARKER) - -$(SDK_INSTALL_MARKER): -ifneq ($(OSFAMILY), windows) - # binary only release so just extract it - $(V1) tar -C $(TOOLS_DIR) -xjf "$(ARM_SDK_DOWNLOAD_PATH)" -else - $(V1) unzip -q -d $(ARM_SDK_DIR) "$(ARM_SDK_DOWNLOAD_PATH)" -endif - -.PHONY: arm_sdk_download -arm_sdk_download: | $(DL_DIR) -arm_sdk_download: $(ARM_SDK_DOWNLOAD_PATH) -$(ARM_SDK_DOWNLOAD_PATH): - # download the source only if it's newer than what we already have - $(V1) curl -L -k -o "$(ARM_SDK_DOWNLOAD_PATH)" -z "$(ARM_SDK_DOWNLOAD_PATH)" "$(ARM_SDK_URL)" - - -## arm_sdk_clean : Uninstall Arm SDK -.PHONY: arm_sdk_clean -arm_sdk_clean: - $(V1) [ ! -d "$(ARM_SDK_DIR)" ] || $(RM) -r $(ARM_SDK_DIR) - $(V1) [ ! -d "$(DL_DIR)" ] || $(RM) -r $(DL_DIR) - -############################## -# -# Set up paths to tools -# -############################## - -ifeq ($(shell [ -d "$(ARM_SDK_DIR)" ] && echo "exists"), exists) - ARM_SDK_PREFIX := $(ARM_SDK_DIR)/bin/arm-none-eabi- -else ifeq (,$(findstring print_,$(MAKECMDGOALS))$(filter targets,$(MAKECMDGOALS))$(findstring arm_sdk,$(MAKECMDGOALS))) - GCC_VERSION = $(shell arm-none-eabi-gcc -dumpversion) - ifeq ($(GCC_VERSION),) - $(error **ERROR** arm-none-eabi-gcc not in the PATH. Run 'make arm_sdk_install' to install automatically in the tools folder of this repo) - else ifneq ($(GCC_VERSION), $(GCC_REQUIRED_VERSION)) - $(error **ERROR** your arm-none-eabi-gcc is '$(GCC_VERSION)', but '$(GCC_REQUIRED_VERSION)' is expected. Override with 'GCC_REQUIRED_VERSION' in make/local.mk or run 'make arm_sdk_install' to install the right version automatically in the tools folder of this repo) - endif - - # ARM tookchain is in the path, and the version is what's required. - ARM_SDK_PREFIX ?= arm-none-eabi- -endif diff --git a/make/version.mk b/make/version.mk deleted file mode 100644 index 729979023ae..00000000000 --- a/make/version.mk +++ /dev/null @@ -1,18 +0,0 @@ -FORKNAME := inav - -FC_VER_MAJOR := $(shell grep " FC_VERSION_MAJOR" src/main/build/version.h | awk '{print $$3}' ) -FC_VER_MINOR := $(shell grep " FC_VERSION_MINOR" src/main/build/version.h | awk '{print $$3}' ) -FC_VER_PATCH := $(shell grep " FC_VERSION_PATCH" src/main/build/version.h | awk '{print $$3}' ) -FC_VER := $(FC_VER_MAJOR).$(FC_VER_MINOR).$(FC_VER_PATCH) - -FC_VER_SUFFIX ?= -ifneq ($(FC_VER_SUFFIX),) - FC_VER += -$(FC_VER_SUFFIX) -endif - -REVISION := $(shell git rev-parse --short HEAD) - -.PHONY: print_version - -print_version: - @echo $(FC_VER) diff --git a/src/main/target/AIKONF4/target.mk b/src/main/target/AIKONF4/target.mk deleted file mode 100644 index a8604c383d1..00000000000 --- a/src/main/target/AIKONF4/target.mk +++ /dev/null @@ -1,18 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES = VCP ONBOARDFLASH MSC -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_ak8963.c \ - drivers/compass/compass_ak8975.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/AIRBOTF4/target.mk b/src/main/target/AIRBOTF4/target.mk deleted file mode 100644 index 8c881ea99f8..00000000000 --- a/src/main/target/AIRBOTF4/target.mk +++ /dev/null @@ -1,19 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_ak8963.c \ - drivers/compass/compass_ak8975.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/pitotmeter_adc.c \ - drivers/light_ws2811strip.c diff --git a/src/main/target/AIRBOTF7/OMNIBUSF7NANOV7.mk b/src/main/target/AIRBOTF7/OMNIBUSF7NANOV7.mk deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/src/main/target/AIRBOTF7/target.mk b/src/main/target/AIRBOTF7/target.mk deleted file mode 100644 index 24cc94224d5..00000000000 --- a/src/main/target/AIRBOTF7/target.mk +++ /dev/null @@ -1,16 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/AIRHEROF3/AIRHEROF3_QUAD.mk b/src/main/target/AIRHEROF3/AIRHEROF3_QUAD.mk deleted file mode 100755 index 8b137891791..00000000000 --- a/src/main/target/AIRHEROF3/AIRHEROF3_QUAD.mk +++ /dev/null @@ -1 +0,0 @@ - diff --git a/src/main/target/AIRHEROF3/target.mk b/src/main/target/AIRHEROF3/target.mk deleted file mode 100755 index 05892f19d09..00000000000 --- a/src/main/target/AIRHEROF3/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F3_TARGETS += $(TARGET) -HSE_VALUE = 12000000 - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/rangefinder/rangefinder_hcsr04.c \ - drivers/light_ws2811strip.c \ - drivers/serial_softserial.c \ - drivers/pitotmeter_adc.c diff --git a/src/main/target/ALIENFLIGHTNGF7/target.mk b/src/main/target/ALIENFLIGHTNGF7/target.mk deleted file mode 100644 index 7f806ad190c..00000000000 --- a/src/main/target/ALIENFLIGHTNGF7/target.mk +++ /dev/null @@ -1,18 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += SDCARD VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu9250.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_ak8963.c \ - drivers/compass/compass_mpu9250.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/max7456.c \ - drivers/light_ws2811strip.c diff --git a/src/main/target/ANYFC/target.mk b/src/main/target/ANYFC/target.mk deleted file mode 100644 index b36cf4f4c5c..00000000000 --- a/src/main/target/ANYFC/target.mk +++ /dev/null @@ -1,14 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - diff --git a/src/main/target/ANYFCF7/ANYFCF7_EXTERNAL_BARO.mk b/src/main/target/ANYFCF7/ANYFCF7_EXTERNAL_BARO.mk deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/src/main/target/ANYFCF7/target.mk b/src/main/target/ANYFCF7/target.mk deleted file mode 100644 index 35d30f5bd73..00000000000 --- a/src/main/target/ANYFCF7/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F765XG_TARGETS += $(TARGET) -FEATURES += SDCARD VCP MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/ASGARD32F4/target.mk b/src/main/target/ASGARD32F4/target.mk deleted file mode 100644 index 481f0495d8e..00000000000 --- a/src/main/target/ASGARD32F4/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/pitotmeter_adc.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/ASGARD32F7/target.mk b/src/main/target/ASGARD32F7/target.mk deleted file mode 100644 index 2859009996d..00000000000 --- a/src/main/target/ASGARD32F7/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/pitotmeter_adc.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/BEEROTORF4/target.mk b/src/main/target/BEEROTORF4/target.mk deleted file mode 100644 index 71ba33ec56d..00000000000 --- a/src/main/target/BEEROTORF4/target.mk +++ /dev/null @@ -1,18 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP SDCARD HIGHEND MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6050.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/compass/compass_ak8963.c \ - drivers/compass/compass_ak8975.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/max7456.c \ - drivers/light_ws2811strip.c diff --git a/src/main/target/BETAFLIGHTF3/target.mk b/src/main/target/BETAFLIGHTF3/target.mk deleted file mode 100755 index 78a16c69e4b..00000000000 --- a/src/main/target/BETAFLIGHTF3/target.mk +++ /dev/null @@ -1,18 +0,0 @@ - -F3_TARGETS += $(TARGET) -FEATURES = VCP SDCARD -TARGET_FLAGS = -DSPRACINGF3 - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/compass/compass_ak8975.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_mag3110.c \ - drivers/display_ug2864hsweg01.h \ - drivers/flash_m25p16.c \ - drivers/max7456.c \ - drivers/serial_softserial.c \ - io/osd.c diff --git a/src/main/target/BETAFLIGHTF4/target.mk b/src/main/target/BETAFLIGHTF4/target.mk deleted file mode 100755 index b1dfa5e503d..00000000000 --- a/src/main/target/BETAFLIGHTF4/target.mk +++ /dev/null @@ -1,22 +0,0 @@ - -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_ak8963.c \ - drivers/compass/compass_ak8975.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/pitotmeter_adc.c \ - drivers/max7456.c \ - drivers/light_ws2811strip.c diff --git a/src/main/target/BLUEJAYF4/target.mk b/src/main/target/BLUEJAYF4/target.mk deleted file mode 100644 index 9244b2aeec6..00000000000 --- a/src/main/target/BLUEJAYF4/target.mk +++ /dev/null @@ -1,16 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += SDCARD VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu9250.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c diff --git a/src/main/target/CLRACINGF4AIR/CLRACINGF4AIRV2.mk b/src/main/target/CLRACINGF4AIR/CLRACINGF4AIRV2.mk deleted file mode 100644 index ef49d797088..00000000000 --- a/src/main/target/CLRACINGF4AIR/CLRACINGF4AIRV2.mk +++ /dev/null @@ -1 +0,0 @@ -#CLRACINGF4AIRV2 \ No newline at end of file diff --git a/src/main/target/CLRACINGF4AIR/CLRACINGF4AIRV3.mk b/src/main/target/CLRACINGF4AIR/CLRACINGF4AIRV3.mk deleted file mode 100644 index c604c0b302d..00000000000 --- a/src/main/target/CLRACINGF4AIR/CLRACINGF4AIRV3.mk +++ /dev/null @@ -1 +0,0 @@ -#CLRACINGF4AIRV3 \ No newline at end of file diff --git a/src/main/target/CLRACINGF4AIR/target.mk b/src/main/target/CLRACINGF4AIR/target.mk deleted file mode 100644 index 416569f682c..00000000000 --- a/src/main/target/CLRACINGF4AIR/target.mk +++ /dev/null @@ -1,13 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES = VCP - -TARGET_SRC = \ - io/osd.c \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_fake.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu9250.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/compass/compass_mpu9250.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/COLIBRI/QUANTON.mk b/src/main/target/COLIBRI/QUANTON.mk deleted file mode 100755 index e69de29bb2d..00000000000 diff --git a/src/main/target/COLIBRI/target.mk b/src/main/target/COLIBRI/target.mk deleted file mode 100755 index 133b6f3eb5d..00000000000 --- a/src/main/target/COLIBRI/target.mk +++ /dev/null @@ -1,13 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC -HSE_VALUE = 16000000 - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c diff --git a/src/main/target/DALRCF405/target.mk b/src/main/target/DALRCF405/target.mk deleted file mode 100644 index 28cba8a0f1f..00000000000 --- a/src/main/target/DALRCF405/target.mk +++ /dev/null @@ -1,19 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_ak8963.c \ - drivers/compass/compass_ak8975.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/pitotmeter_adc.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/DALRCF722DUAL/target.mk b/src/main/target/DALRCF722DUAL/target.mk deleted file mode 100644 index 565e12230b3..00000000000 --- a/src/main/target/DALRCF722DUAL/target.mk +++ /dev/null @@ -1,18 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c \ - drivers/pitotmeter_adc.c \ diff --git a/src/main/target/F4BY/target.mk b/src/main/target/F4BY/target.mk deleted file mode 100644 index 0b69d551705..00000000000 --- a/src/main/target/F4BY/target.mk +++ /dev/null @@ -1,15 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += SDCARD VCP MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/accgyro/accgyro_icm20689.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/rangefinder/rangefinder_hcsr04.c \ - drivers/max7456.c diff --git a/src/main/target/FALCORE/target.mk b/src/main/target/FALCORE/target.mk deleted file mode 100755 index 087ec3e13f4..00000000000 --- a/src/main/target/FALCORE/target.mk +++ /dev/null @@ -1,15 +0,0 @@ -F3_TARGETS += $(TARGET) -HSE_VALUE = 12000000 -FEATURES = VCP ONBOARDFLASH - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/light_ws2811strip.c \ No newline at end of file diff --git a/src/main/target/FF_F35_LIGHTNING/WINGFC.mk b/src/main/target/FF_F35_LIGHTNING/WINGFC.mk deleted file mode 100644 index 4f5f1f6f0e8..00000000000 --- a/src/main/target/FF_F35_LIGHTNING/WINGFC.mk +++ /dev/null @@ -1 +0,0 @@ -#WINGFC diff --git a/src/main/target/FF_F35_LIGHTNING/target.mk b/src/main/target/FF_F35_LIGHTNING/target.mk deleted file mode 100644 index 8162b1f3a9c..00000000000 --- a/src/main/target/FF_F35_LIGHTNING/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu9250.c \ - drivers/compass/compass_mpu9250.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_mag3110.c \ - drivers/rangefinder/rangefinder_hcsr04.c \ - drivers/serial_softserial.c \ - drivers/serial_usb_vcp.c \ - drivers/max7456.c - diff --git a/src/main/target/FF_FORTINIF4/target.mk b/src/main/target/FF_FORTINIF4/target.mk deleted file mode 100644 index 4faee84af70..00000000000 --- a/src/main/target/FF_FORTINIF4/target.mk +++ /dev/null @@ -1,7 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/max7456.c \ - drivers/light_ws2811strip.c diff --git a/src/main/target/FF_PIKOF4/FF_PIKOF4OSD.mk b/src/main/target/FF_PIKOF4/FF_PIKOF4OSD.mk deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/src/main/target/FF_PIKOF4/target.mk b/src/main/target/FF_PIKOF4/target.mk deleted file mode 100644 index b268ca55885..00000000000 --- a/src/main/target/FF_PIKOF4/target.mk +++ /dev/null @@ -1,8 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/max7456.c \ - drivers/light_ws2811strip.c diff --git a/src/main/target/FIREWORKSV2/OMNIBUSF4V6.mk b/src/main/target/FIREWORKSV2/OMNIBUSF4V6.mk deleted file mode 100644 index b47e4817c22..00000000000 --- a/src/main/target/FIREWORKSV2/OMNIBUSF4V6.mk +++ /dev/null @@ -1 +0,0 @@ -#OMNIBUSF4V6 diff --git a/src/main/target/FIREWORKSV2/target.mk b/src/main/target/FIREWORKSV2/target.mk deleted file mode 100644 index 7d8a5945de4..00000000000 --- a/src/main/target/FIREWORKSV2/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/pitotmeter_adc.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/FISHDRONEF4/target.mk b/src/main/target/FISHDRONEF4/target.mk deleted file mode 100644 index 5583e8d0b93..00000000000 --- a/src/main/target/FISHDRONEF4/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += SDCARD VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu9250.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_mpu9250.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/FLYWOOF411/target.mk b/src/main/target/FLYWOOF411/target.mk deleted file mode 100644 index e6cb4cec024..00000000000 --- a/src/main/target/FLYWOOF411/target.mk +++ /dev/null @@ -1,19 +0,0 @@ -F411_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_icm20689.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/flash_m25p16.c \ - drivers/max7456.c diff --git a/src/main/target/FLYWOOF7DUAL/target.mk b/src/main/target/FLYWOOF7DUAL/target.mk deleted file mode 100644 index 2cadc1ff2f8..00000000000 --- a/src/main/target/FLYWOOF7DUAL/target.mk +++ /dev/null @@ -1,19 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_icm20689.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/flash_m25p16.c \ - drivers/max7456.c diff --git a/src/main/target/FOXEERF405/target.mk b/src/main/target/FOXEERF405/target.mk deleted file mode 100644 index 86025b89c11..00000000000 --- a/src/main/target/FOXEERF405/target.mk +++ /dev/null @@ -1,15 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/FOXEERF722DUAL/FOXEERF722V2.mk b/src/main/target/FOXEERF722DUAL/FOXEERF722V2.mk deleted file mode 100644 index 2effcd76873..00000000000 --- a/src/main/target/FOXEERF722DUAL/FOXEERF722V2.mk +++ /dev/null @@ -1 +0,0 @@ -#FOXEERF722V2 \ No newline at end of file diff --git a/src/main/target/FOXEERF722DUAL/target.mk b/src/main/target/FOXEERF722DUAL/target.mk deleted file mode 100644 index 30faa4e33cf..00000000000 --- a/src/main/target/FOXEERF722DUAL/target.mk +++ /dev/null @@ -1,14 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/FRSKYF3/target.mk b/src/main/target/FRSKYF3/target.mk deleted file mode 100644 index fc7dfefad94..00000000000 --- a/src/main/target/FRSKYF3/target.mk +++ /dev/null @@ -1,13 +0,0 @@ -F3_TARGETS += $(TARGET) -FEATURES = VCP SDCARD - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_mag3110.c \ - drivers/accgyro/accgyro_mpu6050.c \ - drivers/max7456.c diff --git a/src/main/target/FRSKYF4/target.mk b/src/main/target/FRSKYF4/target.mk deleted file mode 100755 index 43d1b37fe9b..00000000000 --- a/src/main/target/FRSKYF4/target.mk +++ /dev/null @@ -1,13 +0,0 @@ -F405_TARGETS += $(TARGET) - -FEATURES = VCP SDCARD MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_mag3110.c \ - drivers/max7456.c diff --git a/src/main/target/FRSKYPILOT/target.mk b/src/main/target/FRSKYPILOT/target.mk deleted file mode 100644 index 8147748f123..00000000000 --- a/src/main/target/FRSKYPILOT/target.mk +++ /dev/null @@ -1,14 +0,0 @@ -F765XG_TARGETS += $(TARGET) -FEATURES += SDCARD VCP - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_spl06.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/pitotmeter_adc.c diff --git a/src/main/target/FRSKY_ROVERF7/target.mk b/src/main/target/FRSKY_ROVERF7/target.mk deleted file mode 100755 index b1677ea5fdc..00000000000 --- a/src/main/target/FRSKY_ROVERF7/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_ak8975.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/max7456.c \ - drivers/light_ws2811strip.c \ diff --git a/src/main/target/FURYF4OSD/MAMBAF405.mk b/src/main/target/FURYF4OSD/MAMBAF405.mk deleted file mode 100644 index 50a56f6187e..00000000000 --- a/src/main/target/FURYF4OSD/MAMBAF405.mk +++ /dev/null @@ -1 +0,0 @@ -# MAMBAF405 diff --git a/src/main/target/FURYF4OSD/target.mk b/src/main/target/FURYF4OSD/target.mk deleted file mode 100644 index 272b981bb73..00000000000 --- a/src/main/target/FURYF4OSD/target.mk +++ /dev/null @@ -1,21 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/barometer/barometer_dps310.c \ - drivers/compass/compass_ak8963.c \ - drivers/compass/compass_ak8975.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/pitotmeter_adc.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/HGLRCF722/target.mk b/src/main/target/HGLRCF722/target.mk deleted file mode 100644 index ee06f7a49ce..00000000000 --- a/src/main/target/HGLRCF722/target.mk +++ /dev/null @@ -1,19 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/barometer/barometer_dps310.c \ - drivers/compass/compass_ak8975.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c \ - drivers/pitotmeter_adc.c \ diff --git a/src/main/target/IFLIGHTF4_SUCCEXD/target.mk b/src/main/target/IFLIGHTF4_SUCCEXD/target.mk deleted file mode 100644 index ff3c58d4a0f..00000000000 --- a/src/main/target/IFLIGHTF4_SUCCEXD/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F411_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/compass/compass_ak8975.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/IFLIGHTF4_TWING/target.mk b/src/main/target/IFLIGHTF4_TWING/target.mk deleted file mode 100644 index b4c202b347d..00000000000 --- a/src/main/target/IFLIGHTF4_TWING/target.mk +++ /dev/null @@ -1,16 +0,0 @@ - -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_dps310.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/IFLIGHTF7_TWING/target.mk b/src/main/target/IFLIGHTF7_TWING/target.mk deleted file mode 100644 index 77545402ae2..00000000000 --- a/src/main/target/IFLIGHTF7_TWING/target.mk +++ /dev/null @@ -1,15 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += ONBOARDFLASH VCP MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_dps310.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/KAKUTEF4/KAKUTEF4V2.mk b/src/main/target/KAKUTEF4/KAKUTEF4V2.mk deleted file mode 100755 index 2e11618003f..00000000000 --- a/src/main/target/KAKUTEF4/KAKUTEF4V2.mk +++ /dev/null @@ -1 +0,0 @@ -#KAKUTEF4V2.mk file diff --git a/src/main/target/KAKUTEF4/target.mk b/src/main/target/KAKUTEF4/target.mk deleted file mode 100755 index 37de6e063eb..00000000000 --- a/src/main/target/KAKUTEF4/target.mk +++ /dev/null @@ -1,16 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_ak8963.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/KAKUTEF7/KAKUTEF7HDV.mk b/src/main/target/KAKUTEF7/KAKUTEF7HDV.mk deleted file mode 100644 index d99ea879d89..00000000000 --- a/src/main/target/KAKUTEF7/KAKUTEF7HDV.mk +++ /dev/null @@ -1 +0,0 @@ -#KAKUTEF7HDV.mk file \ No newline at end of file diff --git a/src/main/target/KAKUTEF7/KAKUTEF7MINI.mk b/src/main/target/KAKUTEF7/KAKUTEF7MINI.mk deleted file mode 100644 index f5763af08d9..00000000000 --- a/src/main/target/KAKUTEF7/KAKUTEF7MINI.mk +++ /dev/null @@ -1 +0,0 @@ -#KAKUTEF7MINI.mk file diff --git a/src/main/target/KAKUTEF7/target.mk b/src/main/target/KAKUTEF7/target.mk deleted file mode 100755 index 8709f1ebcf8..00000000000 --- a/src/main/target/KAKUTEF7/target.mk +++ /dev/null @@ -1,20 +0,0 @@ -F765XG_TARGETS += $(TARGET) -ifeq ($(TARGET), KAKUTEF7MINI) -FEATURES += VCP ONBOARDFLASH -else -FEATURES += SDCARD VCP MSC -endif - -TARGET_SRC = \ - drivers/accgyro/accgyro_icm20689.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/compass/compass_ak8963.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/LUX_RACE/target.mk b/src/main/target/LUX_RACE/target.mk deleted file mode 100644 index 67886273cb8..00000000000 --- a/src/main/target/LUX_RACE/target.mk +++ /dev/null @@ -1,10 +0,0 @@ -F3_TARGETS += $(TARGET) -FEATURES = VCP - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu9250.c \ - drivers/light_ws2811strip.c \ - drivers/serial_usb_vcp.c \ - diff --git a/src/main/target/MAMBAF405US/target.mk b/src/main/target/MAMBAF405US/target.mk deleted file mode 100644 index 9600e1937b8..00000000000 --- a/src/main/target/MAMBAF405US/target.mk +++ /dev/null @@ -1,13 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/MAMBAF722/target.mk b/src/main/target/MAMBAF722/target.mk deleted file mode 100644 index 5a3023d0843..00000000000 --- a/src/main/target/MAMBAF722/target.mk +++ /dev/null @@ -1,14 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/MATEKF405/MATEKF405OSD.mk b/src/main/target/MATEKF405/MATEKF405OSD.mk deleted file mode 100755 index e69de29bb2d..00000000000 diff --git a/src/main/target/MATEKF405/MATEKF405_SERVOS6.mk b/src/main/target/MATEKF405/MATEKF405_SERVOS6.mk deleted file mode 100755 index e69de29bb2d..00000000000 diff --git a/src/main/target/MATEKF405/target.mk b/src/main/target/MATEKF405/target.mk deleted file mode 100755 index 62dd163f0c4..00000000000 --- a/src/main/target/MATEKF405/target.mk +++ /dev/null @@ -1,21 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += SDCARD VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/barometer/barometer_dps310.c \ - drivers/compass/compass_ak8963.c \ - drivers/compass/compass_ak8975.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/pitotmeter_adc.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/MATEKF405SE/target.mk b/src/main/target/MATEKF405SE/target.mk deleted file mode 100644 index 13886f855eb..00000000000 --- a/src/main/target/MATEKF405SE/target.mk +++ /dev/null @@ -1,19 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += SDCARD VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/barometer/barometer_dps310.c \ - drivers/compass/compass_ak8963.c \ - drivers/compass/compass_ak8975.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/pitotmeter_adc.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/MATEKF411/MATEKF411_FD_SFTSRL.mk b/src/main/target/MATEKF411/MATEKF411_FD_SFTSRL.mk deleted file mode 100644 index 2f32a7c73b4..00000000000 --- a/src/main/target/MATEKF411/MATEKF411_FD_SFTSRL.mk +++ /dev/null @@ -1 +0,0 @@ -# MATEKF411_FD_SFTSRL diff --git a/src/main/target/MATEKF411/MATEKF411_RSSI.mk b/src/main/target/MATEKF411/MATEKF411_RSSI.mk deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/src/main/target/MATEKF411/MATEKF411_SFTSRL2.mk b/src/main/target/MATEKF411/MATEKF411_SFTSRL2.mk deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/src/main/target/MATEKF411/target.mk b/src/main/target/MATEKF411/target.mk deleted file mode 100755 index 1ea03d20db7..00000000000 --- a/src/main/target/MATEKF411/target.mk +++ /dev/null @@ -1,18 +0,0 @@ -F411_TARGETS += $(TARGET) -FEATURES += VCP - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/barometer/barometer_dps310.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/pitotmeter_adc.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/MATEKF411SE/target.mk b/src/main/target/MATEKF411SE/target.mk deleted file mode 100755 index 94819998682..00000000000 --- a/src/main/target/MATEKF411SE/target.mk +++ /dev/null @@ -1,19 +0,0 @@ -F411_TARGETS += $(TARGET) -FEATURES += VCP - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/barometer/barometer_dps310.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/compass/compass_ak8975.c \ - drivers/pitotmeter_adc.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/MATEKF722/MATEKF722_HEXSERVO.mk b/src/main/target/MATEKF722/MATEKF722_HEXSERVO.mk deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/src/main/target/MATEKF722/target.mk b/src/main/target/MATEKF722/target.mk deleted file mode 100755 index a62d66f5322..00000000000 --- a/src/main/target/MATEKF722/target.mk +++ /dev/null @@ -1,18 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += SDCARD VCP MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_dps310.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c \ - drivers/pitotmeter_adc.c \ diff --git a/src/main/target/MATEKF722PX/target.mk b/src/main/target/MATEKF722PX/target.mk deleted file mode 100755 index 3b7c3615dd1..00000000000 --- a/src/main/target/MATEKF722PX/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/barometer/barometer_dps310.c \ - drivers/compass/compass_ak8975.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/pitotmeter_adc.c \ diff --git a/src/main/target/MATEKF722SE/MATEKF722MINI.mk b/src/main/target/MATEKF722SE/MATEKF722MINI.mk deleted file mode 100644 index e69de29bb2d..00000000000 diff --git a/src/main/target/MATEKF722SE/target.mk b/src/main/target/MATEKF722SE/target.mk deleted file mode 100644 index 19ae98915c2..00000000000 --- a/src/main/target/MATEKF722SE/target.mk +++ /dev/null @@ -1,20 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += SDCARD VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/barometer/barometer_dps310.c \ - drivers/compass/compass_ak8975.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c \ - drivers/pitotmeter_adc.c \ diff --git a/src/main/target/MATEKF765/target.mk b/src/main/target/MATEKF765/target.mk deleted file mode 100644 index 52b7bf2ef39..00000000000 --- a/src/main/target/MATEKF765/target.mk +++ /dev/null @@ -1,19 +0,0 @@ -F765XI_TARGETS += $(TARGET) -FEATURES += SDCARD VCP MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/barometer/barometer_dps310.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c \ - drivers/pitotmeter_adc.c \ diff --git a/src/main/target/MOTOLAB/target.mk b/src/main/target/MOTOLAB/target.mk deleted file mode 100644 index e9d744c1420..00000000000 --- a/src/main/target/MOTOLAB/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F3_TARGETS += $(TARGET) -FEATURES = VCP ONBOARDFLASH - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6050.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/serial_softserial.c - diff --git a/src/main/target/NOX/target.mk b/src/main/target/NOX/target.mk deleted file mode 100755 index 913dfd86a72..00000000000 --- a/src/main/target/NOX/target.mk +++ /dev/null @@ -1,9 +0,0 @@ -F411_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/light_ws2811strip.c \ - drivers/flash_m25p16.c \ - drivers/max7456.c diff --git a/src/main/target/OMNIBUSF4/DYSF4PRO.mk b/src/main/target/OMNIBUSF4/DYSF4PRO.mk deleted file mode 100755 index 4e7c3736ef8..00000000000 --- a/src/main/target/OMNIBUSF4/DYSF4PRO.mk +++ /dev/null @@ -1 +0,0 @@ -#DYSF4PRO diff --git a/src/main/target/OMNIBUSF4/DYSF4PROV2.mk b/src/main/target/OMNIBUSF4/DYSF4PROV2.mk deleted file mode 100755 index f1b5bb0faf4..00000000000 --- a/src/main/target/OMNIBUSF4/DYSF4PROV2.mk +++ /dev/null @@ -1 +0,0 @@ -#DYSF4PROV2 diff --git a/src/main/target/OMNIBUSF4/OMNIBUSF4PRO.mk b/src/main/target/OMNIBUSF4/OMNIBUSF4PRO.mk deleted file mode 100755 index 277ca008108..00000000000 --- a/src/main/target/OMNIBUSF4/OMNIBUSF4PRO.mk +++ /dev/null @@ -1,2 +0,0 @@ -# the OMNIBUSF4SD has an SDCARD instead of flash, a BMP280 baro and therefore a slightly different ppm/pwm and SPI mapping -FEATURES = VCP SDCARD MSC diff --git a/src/main/target/OMNIBUSF4/OMNIBUSF4PRO_LEDSTRIPM5.mk b/src/main/target/OMNIBUSF4/OMNIBUSF4PRO_LEDSTRIPM5.mk deleted file mode 100755 index 3947ddaa4fb..00000000000 --- a/src/main/target/OMNIBUSF4/OMNIBUSF4PRO_LEDSTRIPM5.mk +++ /dev/null @@ -1,2 +0,0 @@ -# the OMNIBUSF4SD has an SDCARD instead of flash, a BMP280 baro and therefore a slightly different ppm/pwm and SPI mapping -FEATURES = VCP SDCARD MSC diff --git a/src/main/target/OMNIBUSF4/OMNIBUSF4V3.mk b/src/main/target/OMNIBUSF4/OMNIBUSF4V3.mk deleted file mode 100755 index 18df391c675..00000000000 --- a/src/main/target/OMNIBUSF4/OMNIBUSF4V3.mk +++ /dev/null @@ -1,3 +0,0 @@ -# OMNIBUSF4V3 is a (almost identical) variant of OMNIBUSF4PRO target, -# except for an inverter on UART6. -FEATURES = VCP SDCARD MSC diff --git a/src/main/target/OMNIBUSF4/OMNIBUSF4V3_S5S6_SS.mk b/src/main/target/OMNIBUSF4/OMNIBUSF4V3_S5S6_SS.mk deleted file mode 100644 index b455b4036bd..00000000000 --- a/src/main/target/OMNIBUSF4/OMNIBUSF4V3_S5S6_SS.mk +++ /dev/null @@ -1 +0,0 @@ -# OMNIBUSF4V3_S5S6_SS diff --git a/src/main/target/OMNIBUSF4/OMNIBUSF4V3_S5_S6_2SS.mk b/src/main/target/OMNIBUSF4/OMNIBUSF4V3_S5_S6_2SS.mk deleted file mode 100644 index f07faf414ce..00000000000 --- a/src/main/target/OMNIBUSF4/OMNIBUSF4V3_S5_S6_2SS.mk +++ /dev/null @@ -1 +0,0 @@ -# OMNIBUSF4V3_S5_S6_2SS diff --git a/src/main/target/OMNIBUSF4/OMNIBUSF4V3_S6_SS.mk b/src/main/target/OMNIBUSF4/OMNIBUSF4V3_S6_SS.mk deleted file mode 100644 index 207070ba7f5..00000000000 --- a/src/main/target/OMNIBUSF4/OMNIBUSF4V3_S6_SS.mk +++ /dev/null @@ -1 +0,0 @@ -# OMNIBUSF4V3_S6_SS diff --git a/src/main/target/OMNIBUSF4/target.mk b/src/main/target/OMNIBUSF4/target.mk deleted file mode 100644 index b6c11e7c820..00000000000 --- a/src/main/target/OMNIBUSF4/target.mk +++ /dev/null @@ -1,19 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH SDCARD MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/compass/compass_ak8975.c \ - drivers/pitotmeter_adc.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/OMNIBUSF7/OMNIBUSF7V2.mk b/src/main/target/OMNIBUSF7/OMNIBUSF7V2.mk deleted file mode 100755 index e69de29bb2d..00000000000 diff --git a/src/main/target/OMNIBUSF7/target.mk b/src/main/target/OMNIBUSF7/target.mk deleted file mode 100644 index ac20568838e..00000000000 --- a/src/main/target/OMNIBUSF7/target.mk +++ /dev/null @@ -1,18 +0,0 @@ -F765XG_TARGETS += $(TARGET) -FEATURES += SDCARD VCP MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/OMNIBUSF7NXT/target.mk b/src/main/target/OMNIBUSF7NXT/target.mk deleted file mode 100644 index 9be9afc5faf..00000000000 --- a/src/main/target/OMNIBUSF7NXT/target.mk +++ /dev/null @@ -1,14 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_lps25h.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/pitotmeter_adc.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/PIKOBLX/target.mk b/src/main/target/PIKOBLX/target.mk deleted file mode 100644 index d53a4c76d1f..00000000000 --- a/src/main/target/PIKOBLX/target.mk +++ /dev/null @@ -1,14 +0,0 @@ -F3_TARGETS += $(TARGET) -FEATURES = VCP - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/light_ws2811strip.c \ - drivers/serial_softserial.c - -# seth neiman dec06.16 porting inav to PIKO BLX using betaflight target related files from before timer.h/timer_def.h changes -# current inav does not have transponder related files - removing from build -# drivers/transponder_ir.c \ -# drivers/transponder_ir_stm32f30x.c \ -# io/transponder_ir.c diff --git a/src/main/target/PIXRACER/target.mk b/src/main/target/PIXRACER/target.mk deleted file mode 100755 index 4f4343a7bfa..00000000000 --- a/src/main/target/PIXRACER/target.mk +++ /dev/null @@ -1,18 +0,0 @@ -F427_TARGETS += $(TARGET) -FEATURES += SDCARD VCP MSC - -HSE_VALUE = 24000000 - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu9250.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_mpu9250.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/serial_usb_vcp.c diff --git a/src/main/target/RCEXPLORERF3/target.mk b/src/main/target/RCEXPLORERF3/target.mk deleted file mode 100644 index e7a04881a54..00000000000 --- a/src/main/target/RCEXPLORERF3/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F3_TARGETS += $(TARGET) -FEATURES = VCP HIGHEND - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/display_ug2864hsweg01.c \ - drivers/serial_usb_vcp.c \ - drivers/flash_m25p16.c \ - drivers/light_ws2811strip.c diff --git a/src/main/target/REVO/target.mk b/src/main/target/REVO/target.mk deleted file mode 100644 index ff9b702cdb5..00000000000 --- a/src/main/target/REVO/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/pitotmeter_adc.c \ - drivers/pitotmeter_ms4525.c \ - drivers/light_ws2811strip.c diff --git a/src/main/target/RMDO/target.mk b/src/main/target/RMDO/target.mk deleted file mode 100644 index ced7c059419..00000000000 --- a/src/main/target/RMDO/target.mk +++ /dev/null @@ -1,21 +0,0 @@ -F3_TARGETS += $(TARGET) -FEATURES = VCP ONBOARDFLASH -TARGET_FLAGS = -DSPRACINGF3 - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6050.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_ak8975.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/flash_m25p16.c \ - drivers/light_ws2811strip.c \ - drivers/serial_softserial.c - diff --git a/src/main/target/SPARKY/target.mk b/src/main/target/SPARKY/target.mk deleted file mode 100644 index eb23cc1bbd7..00000000000 --- a/src/main/target/SPARKY/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F3_TARGETS += $(TARGET) -FEATURES = VCP - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6050.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_ak8975.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c diff --git a/src/main/target/SPARKY2/target.mk b/src/main/target/SPARKY2/target.mk deleted file mode 100644 index 64c49354947..00000000000 --- a/src/main/target/SPARKY2/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu9250.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_mpu9250.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c diff --git a/src/main/target/SPEEDYBEEF4/SPEEDYBEEF4_SFTSRL1.mk b/src/main/target/SPEEDYBEEF4/SPEEDYBEEF4_SFTSRL1.mk deleted file mode 100644 index 123317b4ed8..00000000000 --- a/src/main/target/SPEEDYBEEF4/SPEEDYBEEF4_SFTSRL1.mk +++ /dev/null @@ -1 +0,0 @@ -#SPEEDYBEEF4_SFTSRL1 \ No newline at end of file diff --git a/src/main/target/SPEEDYBEEF4/SPEEDYBEEF4_SFTSRL2.mk b/src/main/target/SPEEDYBEEF4/SPEEDYBEEF4_SFTSRL2.mk deleted file mode 100644 index 6cc372b3632..00000000000 --- a/src/main/target/SPEEDYBEEF4/SPEEDYBEEF4_SFTSRL2.mk +++ /dev/null @@ -1 +0,0 @@ -#SPEEDYBEEF4_SFTSRL2 \ No newline at end of file diff --git a/src/main/target/SPEEDYBEEF4/target.mk b/src/main/target/SPEEDYBEEF4/target.mk deleted file mode 100644 index 481f0495d8e..00000000000 --- a/src/main/target/SPEEDYBEEF4/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/pitotmeter_adc.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/SPEEDYBEEF7/target.mk b/src/main/target/SPEEDYBEEF7/target.mk deleted file mode 100644 index c582b37531e..00000000000 --- a/src/main/target/SPEEDYBEEF7/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH - -TARGET_SRC = \ - drivers/accgyro/accgyro_icm20689.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/pitotmeter_adc.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/SPRACINGF3/target.mk b/src/main/target/SPRACINGF3/target.mk deleted file mode 100644 index c8549b88c4d..00000000000 --- a/src/main/target/SPRACINGF3/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F3_TARGETS += $(TARGET) -FEATURES = ONBOARDFLASH - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6050.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/serial_softserial.c diff --git a/src/main/target/SPRACINGF3MINI/target.mk b/src/main/target/SPRACINGF3MINI/target.mk deleted file mode 100644 index aa9a87bdd19..00000000000 --- a/src/main/target/SPRACINGF3MINI/target.mk +++ /dev/null @@ -1,20 +0,0 @@ -F3_TARGETS += $(TARGET) -FEATURES = VCP SDCARD - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu9250.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/compass/compass_ak8963.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/flash_m25p16.c \ - drivers/light_ws2811strip.c \ - drivers/serial_softserial.c \ - drivers/serial_usb_vcp.c \ - drivers/rangefinder/rangefinder_hcsr04.c \ diff --git a/src/main/target/SPRACINGF4EVO/target.mk b/src/main/target/SPRACINGF4EVO/target.mk deleted file mode 100755 index 3e17d6cc12e..00000000000 --- a/src/main/target/SPRACINGF4EVO/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES = VCP SDCARD MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu9250.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/compass/compass_mpu9250.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c \ No newline at end of file diff --git a/src/main/target/SPRACINGF7DUAL/target.mk b/src/main/target/SPRACINGF7DUAL/target.mk deleted file mode 100644 index 45fb3dd7273..00000000000 --- a/src/main/target/SPRACINGF7DUAL/target.mk +++ /dev/null @@ -1,18 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES = VCP SDCARD MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_fake.c \ - drivers/barometer/barometer_fake.c \ - drivers/compass/compass_fake.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c \ No newline at end of file diff --git a/src/main/target/YUPIF7/target.mk b/src/main/target/YUPIF7/target.mk deleted file mode 100644 index 7c4c979b9bb..00000000000 --- a/src/main/target/YUPIF7/target.mk +++ /dev/null @@ -1,17 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6050.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_mag3110.c \ - drivers/max7456.c \ - drivers/display_ug2864hsweg01.c \ - drivers/pitotmeter_ms4525.c \ - drivers/light_ws2811strip.c \ - drivers/serial_softserial.c diff --git a/src/main/target/ZEEZF7/target.mk b/src/main/target/ZEEZF7/target.mk deleted file mode 100755 index d2ace104ed7..00000000000 --- a/src/main/target/ZEEZF7/target.mk +++ /dev/null @@ -1,7 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += ONBOARDFLASH VCP MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c \ From dd9a831df0d7557fefaf1d3ef1efe9892a05f50b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Fri, 18 Sep 2020 19:11:24 +0100 Subject: [PATCH 243/248] [BUILD] Delete disabled target files from Makefile based build We had several target.mk_ files in order to disable them. With cmake, those targets are fully defined but we just skip them from CI builds and releases, so these old files can be safely deleted. --- src/main/target/ALIENFLIGHTF3/target.mk_ | 21 -------------------- src/main/target/ALIENFLIGHTF4/target.mk_ | 16 --------------- src/main/target/ANYFCM7/target.mk_ | 14 ------------- src/main/target/CHEBUZZF3/target.mk_ | 25 ------------------------ src/main/target/COLIBRI_RACE/target.mk_ | 16 --------------- src/main/target/FURYF3/target.mk_ | 20 ------------------- src/main/target/KFC32F3_INAV/target.mk_ | 19 ------------------ src/main/target/KISSFC/target.mk_ | 9 --------- src/main/target/KROOZX/target.mk_ | 15 -------------- src/main/target/OMNIBUS/target.mk_ | 20 ------------------- src/main/target/RADIX/target.mk_ | 12 ------------ src/main/target/SPRACINGF3EVO/target.mk_ | 19 ------------------ src/main/target/SPRACINGF3NEO/target.mk_ | 18 ----------------- src/main/target/YUPIF4/target.mk_ | 15 -------------- 14 files changed, 239 deletions(-) delete mode 100644 src/main/target/ALIENFLIGHTF3/target.mk_ delete mode 100644 src/main/target/ALIENFLIGHTF4/target.mk_ delete mode 100644 src/main/target/ANYFCM7/target.mk_ delete mode 100644 src/main/target/CHEBUZZF3/target.mk_ delete mode 100644 src/main/target/COLIBRI_RACE/target.mk_ delete mode 100755 src/main/target/FURYF3/target.mk_ delete mode 100644 src/main/target/KFC32F3_INAV/target.mk_ delete mode 100644 src/main/target/KISSFC/target.mk_ delete mode 100755 src/main/target/KROOZX/target.mk_ delete mode 100644 src/main/target/OMNIBUS/target.mk_ delete mode 100644 src/main/target/RADIX/target.mk_ delete mode 100755 src/main/target/SPRACINGF3EVO/target.mk_ delete mode 100644 src/main/target/SPRACINGF3NEO/target.mk_ delete mode 100644 src/main/target/YUPIF4/target.mk_ diff --git a/src/main/target/ALIENFLIGHTF3/target.mk_ b/src/main/target/ALIENFLIGHTF3/target.mk_ deleted file mode 100644 index 70a7b0e3f34..00000000000 --- a/src/main/target/ALIENFLIGHTF3/target.mk_ +++ /dev/null @@ -1,21 +0,0 @@ -F3_TARGETS += $(TARGET) -FEATURES = VCP - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6050.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu9250.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_ak8963.c \ - drivers/compass/compass_ak8975.c \ - drivers/compass/compass_mpu9250.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c - diff --git a/src/main/target/ALIENFLIGHTF4/target.mk_ b/src/main/target/ALIENFLIGHTF4/target.mk_ deleted file mode 100644 index 12cfd715478..00000000000 --- a/src/main/target/ALIENFLIGHTF4/target.mk_ +++ /dev/null @@ -1,16 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += SDCARD VCP - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu9250.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_mpu9250.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c diff --git a/src/main/target/ANYFCM7/target.mk_ b/src/main/target/ANYFCM7/target.mk_ deleted file mode 100644 index 62211096bcc..00000000000 --- a/src/main/target/ANYFCM7/target.mk_ +++ /dev/null @@ -1,14 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH MSC - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/CHEBUZZF3/target.mk_ b/src/main/target/CHEBUZZF3/target.mk_ deleted file mode 100644 index 596a1455dc9..00000000000 --- a/src/main/target/CHEBUZZF3/target.mk_ +++ /dev/null @@ -1,25 +0,0 @@ -F3_TARGETS += $(TARGET) -FEATURES = VCP SDCARD - -TARGET_SRC = \ - drivers/accgyro/accgyro_adxl345.c \ - drivers/accgyro/accgyro_bma280.c \ - drivers/accgyro/accgyro_mma845x.c \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu3050.c \ - drivers/accgyro/accgyro_mpu6050.c \ - drivers/accgyro/accgyro_mpu9250.c \ - drivers/accgyro/accgyro_l3g4200d.c \ - drivers/accgyro/accgyro_l3gd20.c \ - drivers/accgyro/accgyro_lsm303dlhc.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/compass/compass_ak8975.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c - diff --git a/src/main/target/COLIBRI_RACE/target.mk_ b/src/main/target/COLIBRI_RACE/target.mk_ deleted file mode 100644 index d016226a767..00000000000 --- a/src/main/target/COLIBRI_RACE/target.mk_ +++ /dev/null @@ -1,16 +0,0 @@ -F3_TARGETS += $(TARGET) -FEATURES = VCP - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu9250.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c diff --git a/src/main/target/FURYF3/target.mk_ b/src/main/target/FURYF3/target.mk_ deleted file mode 100755 index 758082e8986..00000000000 --- a/src/main/target/FURYF3/target.mk_ +++ /dev/null @@ -1,20 +0,0 @@ -F3_TARGETS += $(TARGET) -FEATURES = VCP ONBOARDFLASH SDCARD - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu9250.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_mpu9250.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/serial_softserial.c - diff --git a/src/main/target/KFC32F3_INAV/target.mk_ b/src/main/target/KFC32F3_INAV/target.mk_ deleted file mode 100644 index 99d179b6877..00000000000 --- a/src/main/target/KFC32F3_INAV/target.mk_ +++ /dev/null @@ -1,19 +0,0 @@ -F3_TARGETS += $(TARGET) -FEATURES = VCP ONBOARDFLASH - -TARGET_SRC = \ - io/osd.c \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_fake.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/flash_m25p16.c \ - drivers/max7456.c \ - drivers/light_ws2811strip.c \ - drivers/pitotmeter_adc.c diff --git a/src/main/target/KISSFC/target.mk_ b/src/main/target/KISSFC/target.mk_ deleted file mode 100644 index a07094b5267..00000000000 --- a/src/main/target/KISSFC/target.mk_ +++ /dev/null @@ -1,9 +0,0 @@ -F3_TARGETS += $(TARGET) -FEATURES = VCP - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6050.c \ - drivers/display_ug2864hsweg01.c \ - drivers/serial_usb_vcp.c - diff --git a/src/main/target/KROOZX/target.mk_ b/src/main/target/KROOZX/target.mk_ deleted file mode 100755 index 529d41babbf..00000000000 --- a/src/main/target/KROOZX/target.mk_ +++ /dev/null @@ -1,15 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP SDCARD -HSE_VALUE = 16000000 - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/max7456.c \ - drivers/light_ws2811strip.c \ No newline at end of file diff --git a/src/main/target/OMNIBUS/target.mk_ b/src/main/target/OMNIBUS/target.mk_ deleted file mode 100644 index 163577e3f4b..00000000000 --- a/src/main/target/OMNIBUS/target.mk_ +++ /dev/null @@ -1,20 +0,0 @@ -F3_TARGETS += $(TARGET) -FEATURES = VCP SDCARD - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6000.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/compass/compass_ak8975.c \ - drivers/pitotmeter_adc.c \ - drivers/light_ws2811strip.c \ - drivers/serial_usb_vcp.c \ - drivers/max7456.c diff --git a/src/main/target/RADIX/target.mk_ b/src/main/target/RADIX/target.mk_ deleted file mode 100644 index 723df086b42..00000000000 --- a/src/main/target/RADIX/target.mk_ +++ /dev/null @@ -1,12 +0,0 @@ -F446_TARGETS += $(TARGET) -FEATURES += VCP SDCARD -HSE_VALUE = 16000000 - -TARGET_SRC = \ - drivers/accgyro/accgyro_bmi160.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c diff --git a/src/main/target/SPRACINGF3EVO/target.mk_ b/src/main/target/SPRACINGF3EVO/target.mk_ deleted file mode 100755 index bc26cae3272..00000000000 --- a/src/main/target/SPRACINGF3EVO/target.mk_ +++ /dev/null @@ -1,19 +0,0 @@ -F3_TARGETS += $(TARGET) -FEATURES = VCP SDCARD - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu9250.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_mpu9250.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/serial_usb_vcp.c \ - drivers/serial_softserial.c diff --git a/src/main/target/SPRACINGF3NEO/target.mk_ b/src/main/target/SPRACINGF3NEO/target.mk_ deleted file mode 100644 index fa6bb65435c..00000000000 --- a/src/main/target/SPRACINGF3NEO/target.mk_ +++ /dev/null @@ -1,18 +0,0 @@ -F3_TARGETS += $(TARGET) -FEATURES = VCP SDCARD - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_mpu9250.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_mpu9250.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_ist8308.c \ - drivers/compass/compass_mag3110.c \ - drivers/compass/compass_lis3mdl.c \ - drivers/light_ws2811strip.c \ - drivers/max7456.c diff --git a/src/main/target/YUPIF4/target.mk_ b/src/main/target/YUPIF4/target.mk_ deleted file mode 100644 index d1329a43f80..00000000000 --- a/src/main/target/YUPIF4/target.mk_ +++ /dev/null @@ -1,15 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += SDCARD VCP - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6050.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms56xx.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_ist8310.c \ - drivers/compass/compass_mag3110.c \ - drivers/max7456.c \ - drivers/light_ws2811strip.c From 2e3000798bc8ee36a04de85be6644c5c5067b407 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sun, 20 Sep 2020 17:17:07 +0100 Subject: [PATCH 244/248] [CMAKE] Change clean_* targets to call clean Removing CMAKE_CURRENT_BINARY_DIR directly is problematic, since it also removes files generated by cmake and can cause errors that will require regenerating the build system files. Instead, call clean (e.g. make clean or ninja clean) in CMAKE_CURRENT_BINARY_DIR. This ensures all the files generated by the build system are removed, but any files generated as a part of cmake's configuration step are preserved. --- cmake/stm32.cmake | 40 ++++++++++++++++------------------------ 1 file changed, 16 insertions(+), 24 deletions(-) diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake index 760c92ade26..eed7a9dfa06 100644 --- a/cmake/stm32.cmake +++ b/cmake/stm32.cmake @@ -413,28 +413,20 @@ function(target_stm32) endif() # clean_ - set(clean_target "clean_${name}") - if(CMAKE_VERSION VERSION_LESS 3.17) - if(CMAKE_HOST_SYSTEM MATCHES ".*Windows.*") - set(rm del /s /q) - set(rmdir rmdir /s /q) - else() - set(rm rm -fr) - set(rmdir ${rm}) - endif() - else() - set(rm ${CMAKE_COMMAND} -E rm -fr) - set(rmdir ${rm}) - endif() - add_custom_target(${clean_target} - WORKING_DIRECTORY ${CMAKE_BINARY_DIR} - COMMAND ${rmdir} "${CMAKE_CURRENT_BINARY_DIR}" - COMMAND ${rm} ${main_hex_filename} - COMMAND ${rm} ${bl_hex_filename} - COMMAND ${rm} ${main_hex_filename} - COMMENT "Removing intermediate files for ${name}") - set_property(TARGET ${clean_target} PROPERTY - TARGET_MESSAGES OFF - EXCLUDE_FROM_ALL 1 - EXCLUDE_FROM_DEFAULT_BUILD 1) + set(generator_cmd "") + if (CMAKE_GENERATOR STREQUAL "Unix Makefiles") + set(generator_cmd "make") + elseif(CMAKE_GENERATOR STREQUAL "Ninja") + set(generator_cmd "ninja") + endif() + if (NOT generator_cmd STREQUAL "") + set(clean_target "clean_${name}") + add_custom_target(${clean_target} + WORKING_DIRECTORY ${CMAKE_BINARY_DIR} + COMMAND ${generator_cmd} clean + COMMENT "Removing intermediate files for ${name}") + set_property(TARGET ${clean_target} PROPERTY + EXCLUDE_FROM_ALL 1 + EXCLUDE_FROM_DEFAULT_BUILD 1) + endif() endfunction() From a88aaca74bd4cd9223db4563fe6c96f3ff68cae9 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Sun, 20 Sep 2020 21:02:40 +0100 Subject: [PATCH 245/248] [CMAKE] Override .hex start address with 0x08000000 The configurator does rely on the .hex start address being set to 0x08000000. I'm not sure this is actually required and we should fix the configurator instead. However, in order to allow older versions of configurator to flash newer firmwares, we should the .hex files built with cmake compatible for at least some releases. --- cmake/stm32.cmake | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/cmake/stm32.cmake b/cmake/stm32.cmake index eed7a9dfa06..5d7db58f2e0 100644 --- a/cmake/stm32.cmake +++ b/cmake/stm32.cmake @@ -189,7 +189,11 @@ endfunction() function(add_hex_target name exe hex) add_custom_target(${name} ALL cmake -E env PATH=$ENV{PATH} - ${CMAKE_OBJCOPY} -Oihex $ ${hex} + # TODO: Overriding the start address with --set-start 0x08000000 + # seems to be required due to some incorrect assumptions about .hex + # files in the configurator. Verify wether that's the case and fix + # the bug in configurator or delete this comment. + ${CMAKE_OBJCOPY} -Oihex --set-start 0x08000000 $ ${hex} BYPRODUCTS ${hex} ) endfunction() From f565b9ae4d8c0387a247f24fe5706ed54a774224 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 21 Sep 2020 10:51:17 +0200 Subject: [PATCH 246/248] Ability to read current waypoint index as part of LC --- docs/Programming Framework.md | 18 ++++++++++++++++++ src/main/programming/logic_condition.c | 8 ++++++++ src/main/programming/logic_condition.h | 2 ++ 3 files changed, 28 insertions(+) diff --git a/docs/Programming Framework.md b/docs/Programming Framework.md index ddcb0188634..6c4e96f48d2 100644 --- a/docs/Programming Framework.md +++ b/docs/Programming Framework.md @@ -111,6 +111,24 @@ IPF can be edited using INAV Configurator user interface, of via CLI | 23 | IS_WP | boolean `0`/`1` | | 24 | IS_LANDING | boolean `0`/`1` | | 25 | IS_FAILSAFE | boolean `0`/`1` | +| 26 | STABILIZED_ROLL | Roll PID controller output `[-500:500]` | +| 27 | STABILIZED_PITCH | Pitch PID controller output `[-500:500]` | +| 28 | STABILIZED_YAW | Yaw PID controller output `[-500:500]` | +| 29 | ACTIVE_WAYPOINT_INDEX | Indexed from `1`. To verify WP is in progress, use `IS_WP` | +| 30 | ACTIVE_WAYPOINT_ACTION | See ACTIVE_WAYPOINT_ACTION paragraph | + +##### ACTIVE_WAYPOINT_ACTION + +| Action | Value | +|---- |---- | +| WAYPOINT | 1 | +| HOLD_TIME | 3 | +| RTH | 4 | +| SET_POI | 5 | +| JUMP | 6 | +| SET_HEAD | 7 | +| LAND | 8 | + #### FLIGHT_MODE diff --git a/src/main/programming/logic_condition.c b/src/main/programming/logic_condition.c index a35dd32598a..d63f3639f0a 100644 --- a/src/main/programming/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -466,6 +466,14 @@ static int logicConditionGetFlightOperandValue(int operand) { return axisPID[PITCH]; break; + case LOGIC_CONDITION_OPERAND_FLIGHT_WAYPOINT_INDEX: + return NAV_Status.activeWpNumber; + break; + + case LOGIC_CONDITION_OPERAND_FLIGHT_WAYPOINT_ACTION: + return NAV_Status.activeWpAction; + break; + default: return 0; break; diff --git a/src/main/programming/logic_condition.h b/src/main/programming/logic_condition.h index 628b3b5adb3..e46b8c6c43a 100644 --- a/src/main/programming/logic_condition.h +++ b/src/main/programming/logic_condition.h @@ -110,6 +110,8 @@ typedef enum { LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_ROLL, // 26 LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_PITCH, // 27 LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_YAW, // 28 + LOGIC_CONDITION_OPERAND_FLIGHT_WAYPOINT_INDEX, // 29 + LOGIC_CONDITION_OPERAND_FLIGHT_WAYPOINT_ACTION, // 30 } logicFlightOperands_e; typedef enum { From 81e9e7e18f4f97535ba2cea43fe6b20a5a1a7c83 Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Wed, 23 Sep 2020 14:36:55 -0400 Subject: [PATCH 247/248] Missing SNR Alarm Level default added --- src/main/io/osd.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index f069f209ea6..dbbc3f61207 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2568,7 +2568,9 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .baro_temp_alarm_min = -200, .baro_temp_alarm_max = 600, #endif - +#ifdef USE_SERIALRX_CRSF + .snr_alarm = 5, +#endif #ifdef USE_TEMPERATURE_SENSOR .temp_label_align = OSD_ALIGN_LEFT, #endif From be42332e1835e7076fa8ad1cef978c9c450ca914 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 24 Sep 2020 10:10:52 +0200 Subject: [PATCH 248/248] WSL error troubleshooting --- ...ding in Windows 10 with Linux Subsystem.md | 24 +++++++++++++++++++ 1 file changed, 24 insertions(+) diff --git a/docs/development/Building in Windows 10 with Linux Subsystem.md b/docs/development/Building in Windows 10 with Linux Subsystem.md index 19aec3f1bb5..52dd61527e9 100644 --- a/docs/development/Building in Windows 10 with Linux Subsystem.md +++ b/docs/development/Building in Windows 10 with Linux Subsystem.md @@ -69,3 +69,27 @@ make MATEKF722 ## Flashing: Launch windows configurator GUI and from within the firmware flasher select `Load firmware[Local]` Hex files can be found in the folder `c:\inav\build` + +## Troubleshooting + +### Syntax error: "(" unexpected + +``` +dzikuvx@BerlinAtHome:/mnt/c/Users/pspyc/Documents/Projects/inav/build$ make MATEKF722SE +Generating MATEKF722SE/settings_generated.h, MATEKF722SE/settings_generated.c +/bin/sh: 1: Syntax error: "(" unexpected +make[3]: *** [src/main/target/MATEKF722SE/CMakeFiles/MATEKF722SE.elf.dir/build.make:63: src/main/target/MATEKF722SE/MATEKF722SE/settings_generated.h] Error 2 +make[2]: *** [CMakeFiles/Makefile2:33607: src/main/target/MATEKF722SE/CMakeFiles/MATEKF722SE.elf.dir/all] Error 2 +make[1]: *** [CMakeFiles/Makefile2:33290: src/main/target/MATEKF722SE/CMakeFiles/MATEKF722SE.dir/rule] Error 2 +make: *** [Makefile:13703: MATEKF722SE] Error 2 +``` + +This error can be triggered by a Windows PATHs included in the Linux Subsystem. The solution is to: + +1. Open Windows RegEdit tool +1. Find `HKEY_CURRENT_USER\Software\Microsoft\Windows\CurrentVersion\Lxss\{GUID}\Flags` +1. Change `Flags` from `7` to `5` +1. Restart WSL and Windows preferably +1. `cd build` +1. `cmake ..` +1. `make {TARGET}` should be working again \ No newline at end of file