From f30a21237829fcb6d6d5950d5398b38be8710ca4 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 19 Jan 2020 20:50:39 +0100 Subject: [PATCH 01/56] 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 26b1fe49f7..27a2a28efa 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 ce7e657982..862ec61897 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 343ecf21e5..0ce8b3e94f 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 3cfe2459ef..2956b6e962 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 f7d0891761..6b4bfe8f08 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 596b47f646..aee57bffca 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 a11e9a0f62..f56048e8ab 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 02/56] 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 aee57bffca..13eea54dfe 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 03/56] 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 2484bd4f54..e59925478d 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 07734efdac..3897ecac33 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 cb53cc220c..51e6469d9d 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 6400c95c9c..634aae2c04 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 13eea54dfe..b0130f3a11 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 f56048e8ab..e97d76311d 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 04/56] 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 64329dbe17..c54f331958 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 e8ba6f432a..a915146101 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 1fb455f336..0ea8ebd8b7 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 8bc148e2be..f0bf6964ed 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 b9cf88bd21..2b7c3a243c 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 05/56] 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 0ea8ebd8b7..fd3e3d19ec 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 29c94d7284e01b8da1b1d91d8a13615685816dec Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Wed, 8 Jul 2020 15:03:23 +0200 Subject: [PATCH 06/56] [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 dcedfc373c..5fbe12fc69 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 567264f783..49d8d0cc59 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 28cf60802d..5cb146cf16 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 07/56] 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 6c4800aa35..e1b9aa1284 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 dc6f43f071..a63a0946ff 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 dc50817963..9aece7e69d 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 ac4656bcac..1ee4dd016d 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 066e02dd5f..f20e576d5e 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 7a5c64b06d..f79c596b9f 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 24aab18727..b24b78c911 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 a9e621285e..2a48c71946 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 375eacb288..dbd910e273 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 f8ca7b5112..14df882289 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 5e12bf9761..a9929e6623 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 f8e0128eab..adcaec001b 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 72230a97ae..df2faace76 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 7ba9dd2f1b..d42d62fa71 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 0000000000..1447ffd231 --- /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 0000000000..f19e3f184b --- /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 a9d13ef5ef..99ebc68193 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 d79dad8a62..a6ff91b038 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 206aef3197907a07ff8916c86ac2a6f36a3c5c51 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Thu, 9 Jul 2020 09:39:51 +0100 Subject: [PATCH 08/56] [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 ce545ab777..e73844ccab 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 09/56] [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 e73844ccab..5ab9066e3d 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 10/56] 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 f74d772b65..81f350cff2 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 dda74ae3e7..2c4db39b58 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 a9929e6623..675da33215 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 adcaec001b..e6221ef8e3 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 11/56] 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 5215060725..8c2ddc4639 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 4687ce4e4c..d48118bd37 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 b7bfa2e2d7..964cb980fe 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 cecaddd8ef2df16ed654573bbd83608cf105c94f Mon Sep 17 00:00:00 2001 From: Felipe Machado Date: Wed, 15 Jul 2020 16:36:33 +0100 Subject: [PATCH 12/56] [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 e6194797d2..2a6f4f8b5a 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 13/56] 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 eb4960ff0a..97431dedf7 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 147a190967..6cc0c48c79 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 169d069306..9bbe02cfe9 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 14/56] 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 08e65492e7..5dd2e1f95f 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 20287ee521..08905ded67 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 6e168aaac4..1a548febda 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 3e2a9b11d9..2220ce26cd 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 66970585a4..0dc2513b30 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 15/56] 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 0edda29c66..1ca0439bda 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 0000000000..1713188901 --- /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 0000000000..ebabbd28a1 --- /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 0000000000..c745a853be --- /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 0000000000..ee06f7a49c --- /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 16/56] 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 e1b9aa1284..d1b0b3e065 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 a5a5e90ea6..3ae2e3109c 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 d5a877f7d6..6e7dc2f48b 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 0000000000..dded542209 --- /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 0000000000..dc87f69449 --- /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 1ee4dd016d..dbc91f4681 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 5ab9066e3d..9493f03915 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 a6ff91b038..95bd52a71e 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 b372e9c8f7..0818d11973 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 17/56] 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 d1b0b3e065..37e70f9ee2 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 dded542209..b42386cf9b 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 0000000000..5125fe2260 --- /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 0000000000..5a78b9b3c3 --- /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 dbc91f4681..d5b1d071d4 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 d42d62fa71..a63196b3fe 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 f48383870a..2ae2db8311 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 95bd52a71e..95d55be536 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 0818d11973..ad8736d0db 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 18/56] 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 97f24933bb..10ffc058d4 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 19/56] 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 e1b9aa1284..57909d6ec2 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 a5a5e90ea6..cb05965d31 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 3ed062a198..d1f42515b6 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 104a3e4627..c07afcb82f 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 1ee4dd016d..de5b2e7c9a 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 f79c596b9f..3207509ea3 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 5ab9066e3d..d0ab6d67ee 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 6f77480f73..76e57b3638 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 0000000000..cc51b4235d --- /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 0000000000..c499b490e5 --- /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 99ebc68193..3a8666f2d3 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 20/56] 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 aa20153cca..7ea9a13b6a 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 9e6c059d7f..aeb29b38da 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 232ce7fe04..b7b05eff3b 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 3c740a564b..2216605fee 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 342a8cbf95..28da7c4df9 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 57909d6ec2..9c17d064a5 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 aa0544bffd..c111ddb75c 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), $(F7X5XG_TARGETS))) -TARGET_MCU := STM32F7X5XG +else ifeq ($(TARGET),$(filter $(TARGET), $(F745XG_TARGETS))) +TARGET_MCU := STM32F745XG TARGET_MCU_GROUP := STM32F7 -else ifeq ($(TARGET),$(filter $(TARGET), $(F7X5XI_TARGETS))) -TARGET_MCU := STM32F7X5XI +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 := 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 0000000000..b1a75170af --- /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 67669ade06..0f2f9aca74 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 2a608fcb4d..9548a8e1ed 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 ff26802788..34faa14536 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 55691bb291..1ac0824c74 100644 --- a/src/main/drivers/system.c +++ b/src/main/drivers/system.c @@ -85,10 +85,15 @@ void systemReset(void) NVIC_SystemReset(); } +void systemResetRequest(uint32_t requestId) +{ + persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, requestId); + systemReset(); +} + void systemResetToBootloader(void) { - persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_BOOTLOADER_REQUEST_ROM); - systemReset(); + systemResetRequest(RESET_BOOTLOADER_REQUEST_ROM); } typedef void resetHandler_t(void); diff --git a/src/main/drivers/system.h b/src/main/drivers/system.h index 87cc140690..878d9d94a8 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 aa98183484..dfb97c3e68 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 a63a0946ff..f9233eb712 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 de5b2e7c9a..cbc5d7cb5e 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 f20e576d5e..dd7528f0fb 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 0000000000..be8a22171b --- /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 0000000000..4bbb11693e --- /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 0000000000..2d3370b78f --- /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 0000000000..a463551b48 --- /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 ecf4f268f5..5f57a10b8b 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 209ce4e6af..521bd48fba 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 0367bc5a3b..b2d43590f2 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 26d64b7bca..35d30f5bd7 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 07e5ccfc94..8709f1ebcf 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 9e34a0864e..52b7bf2ef3 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 30cffe4432..ac20568838 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 0000000000..6ae82e6f8a --- /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 0000000000..c2a60a1429 --- /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 0000000000..e7ebaf2944 --- /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 0c9041676f..e7e8ee24ae 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 86e394c673..3ec7258643 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 0000000000..867bdbe8c4 --- /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 0000000000..9661ff663c --- /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 296708678d..7aba1e7b78 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 0000000000..1241562d05 --- /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 0000000000..5ce5fb0377 --- /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 a83374e4e4..0e72963cdb 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 0000000000..6639776539 --- /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 0000000000..4cfd76df20 --- /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 0000000000..916654eaa5 --- /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 65add7cf71..be9b27ec3b 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 034c14a2db..29ece48639 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 0000000000..c32110f3d5 --- /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 0000000000..58dca4024d --- /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 21ef8fc2c2e6780139810e65199a8baf1a377022 Mon Sep 17 00:00:00 2001 From: craigmunday Date: Wed, 22 Jul 2020 21:21:09 +1000 Subject: [PATCH 21/56] 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 dda74ae3e7..04a298e222 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 22/56] 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 | 218 ++++++++++++------------ 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, 269 insertions(+), 138 deletions(-) diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index e9382d2dd3..67a916371e 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 b24b78c911..eebb090dd1 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 2c4db39b58..02086f8503 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 675da33215..3b1a98fec3 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; + // 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 - ); + // 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; - } + // 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); +// void NOINLINE globalFunctionsUpdateTask(timeUs_t currentTimeUs) { +// UNUSED(currentTimeUs); - //Disable all flags - globalFunctionsFlags = 0; +// //Disable all flags +// globalFunctionsFlags = 0; - for (uint8_t i = 0; i < MAX_GLOBAL_FUNCTIONS; i++) { - globalFunctionsProcess(i); - } -} +// for (uint8_t i = 0; i < MAX_GLOBAL_FUNCTIONS; i++) { +// globalFunctionsProcess(i); +// } +// } -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]; -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 (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 (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; +// } - 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; -} +// return outputValue; +// } #endif diff --git a/src/main/programming/global_functions.h b/src/main/programming/global_functions.h index e6221ef8e3..f0f0aa1e41 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 d42d62fa71..e73e868d74 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 f48383870a..b5900c4b93 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 1447ffd231..7afe4ffb3a 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 23/56] 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 81f350cff2..0000000000 --- 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 10ffc058d4..6bbc4ecd76 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 8de6927dc5..21f7b7abf4 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 f9233eb712..ffa75db9b6 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 67a916371e..5317dc0470 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 dd7528f0fb..076b7077f1 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 eebb090dd1..20fa78d30b 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 732bc26520..88dedf1814 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 02086f8503..5453718eeb 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 3b1a98fec3..0000000000 --- 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 f0f0aa1e41..0000000000 --- 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 7afe4ffb3a..ba26217fc3 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 24/56] [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 719476204e..a8551523fa 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 25/56] [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 8de6927dc5..7110593f46 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 1c92bb9df4..67ab520085 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 7676453059..7abff66d32 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 0000000000..dafaff734d --- /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 0000000000..ff08eb6dc2 --- /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 f5b02d6a50..c5c022027a 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 a8551523fa..edebe8ec6f 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 f5975f1c15..130e9cac22 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 4d42b6daf4..d6c5741e1e 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 26/56] [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 | 369 +++++++++++++------------- src/main/io/osd.h | 6 +- src/main/io/osd_dji_hd.c | 2 +- 7 files changed, 208 insertions(+), 200 deletions(-) diff --git a/src/main/cms/cms_menu_osd.c b/src/main/cms/cms_menu_osd.c index 33eab41670..dceb87da6b 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 c07afcb82f..078352ce74 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 f9233eb712..b4c964f3ec 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 dd7528f0fb..5393e000c0 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 2c4db39b58..6b16fc12c6 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) -{ - 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); - - osdConfig->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); - - // avoid OSD_VARIO under OSD_CROSSHAIRS - osdConfig->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; - - osdConfig->item_pos[0][OSD_CRAFT_NAME] = OSD_POS(20, 2); - osdConfig->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); - - 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); - - osdConfig->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); - -#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); -#endif - -#if defined(USE_RX_MSP) && defined(USE_MSP_RC_OVERRIDE) - osdConfig->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; - - 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; +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 - osdConfig->baro_temp_alarm_min = -200; - osdConfig->baro_temp_alarm_max = 600; + .baro_temp_alarm_min = -200, + .baro_temp_alarm_max = 600, #endif #ifdef USE_TEMPERATURE_SENSOR - osdConfig->temp_label_align = OSD_ALIGN_LEFT; + .temp_label_align = OSD_ALIGN_LEFT, #endif - osdConfig->video_system = VIDEO_SYSTEM_AUTO; + .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; + .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, - osdConfig->units = OSD_UNIT_METRIC; - osdConfig->main_voltage_decimals = 1; + .units = OSD_UNIT_METRIC, + .main_voltage_decimals = 1, - osdConfig->estimations_wind_compensation = true; - osdConfig->coordinate_digits = 9; + .estimations_wind_compensation = true, + .coordinate_digits = 9, - osdConfig->osd_failsafe_switch_layout = false; + .osd_failsafe_switch_layout = false, - osdConfig->plus_code_digits = 11; + .plus_code_digits = 11, +); + +void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) +{ + 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); + + osdLayoutsConfig->item_pos[0][OSD_RSSI_VALUE] = OSD_POS(23, 0) | OSD_VISIBLE_FLAG; + //line 2 + 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 + osdLayoutsConfig->item_pos[0][OSD_VARIO] = OSD_POS(23, 5); + // OSD_VARIO_NUM at the right of OSD_VARIO + 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; + + 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); + + 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); + + 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. + 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) + 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) + osdLayoutsConfig->item_pos[0][OSD_RC_SOURCE] = OSD_POS(3, 4); +#endif + + // Under OSD_FLYMODE. TODO: Might not be visible on NTSC? + 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(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 c641875e60..e345cfc2f5 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 29b3abf074..379937d63d 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 27/56] [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 fcd367dba4..cab85a143d 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 6b16fc12c6..a28f12989c 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 e345cfc2f5..9ce97a6730 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 d6c5741e1e..c3dcd5e053 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 28/56] [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 dafaff734d..a7fbc8e5e6 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 ff08eb6dc2..9e7c536999 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 bdbd1508b5..8859325d10 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 c5c022027a..b3571b8522 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 130e9cac22..3190f556f9 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 a28f12989c..d13f9969da 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 c3dcd5e053..3ad02d643f 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 38243cb6d9..b6fc2722ce 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 7d632edc9d..5dc53ea41d 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 1614033b6d..a878c2f3d4 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 97f499e758..d0d4c24d27 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 c4c8b7b0e0..baf69dc918 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 29/56] [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 bddefea7ce..82e882f6c6 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 8859325d10..62f0c05dc5 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 30/56] [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 b4c964f3ec..44d7d3867c 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 5393e000c0..cd26f87ccb 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 76e57b3638..9ea7869ab1 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 31/56] [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 edebe8ec6f..7486e1efbf 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 32/56] [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 82e882f6c6..54e9753a97 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 33/56] [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 cab85a143d..f9f6522e35 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 d13f9969da..ffd3f4413b 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 9ce97a6730..2c27e8dcc9 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 3ad02d643f..3d42c608b4 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 d0d4c24d27..26a1c64338 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 34/56] [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 f9f6522e35..1a239d8acb 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 2c27e8dcc9..554fd4a82e 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 3d42c608b4..02de3b0649 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 35/56] [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 67ab520085..a3738e5edb 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 36/56] [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 | 78 +++++++++++++++++++++++----------------- 1 file changed, 45 insertions(+), 33 deletions(-) diff --git a/src/main/io/osd_canvas.c b/src/main/io/osd_canvas.c index 02de3b0649..c55c988b5e 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; + // 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); - osdDrawPointGetGrid(&ex, &ey, display, canvas, p); + 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; - osdCanvasDrawVarioShape(canvas, ex, ey, prev, true); - osdCanvasDrawVarioShape(canvas, ex, ey, zvel, false); + 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 37/56] [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 ffd3f4413b..a340e0ecad 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 535bb32c9e..ed131f7496 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 3845c2347b..a22ab18846 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 38/56] [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 c55c988b5e..801fb1703e 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 39/56] [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 ee3742b127..f98d5abf91 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 40/56] [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 a340e0ecad..0d3b7d75d4 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 801fb1703e..a649b10b5b 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 b6fc2722ce..6a8d013e80 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 5dc53ea41d..f5453f4ec6 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 a878c2f3d4..054f458a63 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 41/56] [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 a649b10b5b..dedb36db34 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 42/56] [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 1a239d8acb..7700c3586c 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 0d3b7d75d4..e0b02faf3c 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 554fd4a82e..6415b7530b 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 43/56] [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 0000000000..3c6243de51 --- /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 0000000000..56a44b256d --- /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 0000000000..3f2d63e993 --- /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 0000000000..f83631e49e --- /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 44/56] [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 3f2d63e993..4c471a044a 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 f83631e49e..e6cb4cec02 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 45/56] [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 0000000000..6d49f5a589 --- /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 0000000000..faad1abbae --- /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 0000000000..2cadc1ff2f --- /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 46/56] [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 1ca0439bda..7eb829efa8 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 6d49f5a589..d9dc7ccc9b 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 faad1abbae..419d5ba9e4 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 e520db67f8215b072ab6b0e0e95e0b704c5ffe50 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 24 Jul 2020 19:19:51 +0200 Subject: [PATCH 47/56] 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 1a548febda..f62dc3722b 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 7eb829efa8..a8806f99a7 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 c111ddb75c..fcec998045 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 0000000000..2effcd7687 --- /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 75eec081ff..e1ac91c271 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 48/56] [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 fcaf5c9443..7968233c9f 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 0e49751519..7eb0418397 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 49/56] [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 7ea9a13b6a..5b95e5a6ac 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 4f3804f703..0000000000 --- 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 a9a03b2e3b..0000000000 --- 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 f302822552..0000000000 --- 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 0000000000..796b96d1c4 --- /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 0000000000..2c9adc21d8 --- /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 676bd496e7..0000000000 --- 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 0000000000..7163000b17 --- /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 0000000000..2f8bf52da4 --- /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 0000000000..42567db71a --- /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 4dcf2092c7..f8a337fece 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 50/56] [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 8cc243f608..39f7d57184 100644 --- a/src/utils/compiler.rb +++ b/src/utils/compiler.rb @@ -57,6 +57,7 @@ class Compiler 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 @@ class Compiler 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 7795552308..bb517de362 100644 --- a/src/utils/settings.rb +++ b/src/utils/settings.rb @@ -718,7 +718,7 @@ class Generator 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 @@ class Generator 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 51/56] [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 fcd367dba4..6181f88f60 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 52/56] [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 3d99991cd4..f4edd67c17 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 0000000000..df804980cd --- /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 0000000000..18c6102991 --- /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 0000000000..190fb08193 --- /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 0000000000..f74f6589d9 --- /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 0000000000..40dbf413b5 --- /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 0000000000..d22eb104a6 --- /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 0000000000..a631d74448 --- /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 bb50b269f2..d75282cf8b 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 0000000000..65f9a19c48 --- /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 0000000000..426c86cb5d --- /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 0000000000..0031ec68c2 --- /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 0000000000..588b589c87 --- /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 53/56] [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 e83869b57f..92d18ab3a0 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 54/56] [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 05187869d8..9039990d56 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 0f56f1d9fa..389b0b0218 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 6ae9950603..cf54897bca 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 d4dbb9a2c6..91c9938ba5 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 55/56] [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 91c9938ba5..ddaa1b8f4f 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 56/56] [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 a538fb2ccd..ecc4ce4f3e 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).