1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-18 22:05:17 +03:00

Merge branch 'feature-sonar-flight-mode-no-baro' of dclifton-github.com:nebbian/cleanflight into nebbian-feature-sonar-flight-mode-no-baro

Fixed tabs, kept old references to VARIO.  Made SONAR mode a new option so that aux settings could be preserved.

Conflicts:
	src/main/config/runtime_config.h
	src/main/flight/altitudehold.h
	src/main/flight/imu.c
	src/main/io/rc_controls.h
	src/main/mw.c
	src/main/sensors/initialisation.c
This commit is contained in:
Dominic Clifton 2014-09-26 13:36:19 +01:00
commit 3eb8bcb3e5
8 changed files with 77 additions and 20 deletions

View file

@ -372,7 +372,8 @@ int16_t calculateThrottleAngleCorrection(uint8_t throttle_correction_value)
return lrintf(throttle_correction_value * sinf(angle / (900.0f * M_PI / 2.0f)));
}
#ifdef BARO
#if defined(BARO) || defined(SONAR)
// 40hz update rate (20hz LPF on acc)
#define BARO_UPDATE_FREQUENCY_40HZ (1000 * 25)
@ -453,6 +454,7 @@ void calculateEstimatedAltitude(uint32_t currentTime)
previousTime = currentTime;
#ifdef BARO
if (!isBaroCalibrationComplete()) {
performBaroCalibrationCycle();
vel = 0;
@ -460,6 +462,9 @@ void calculateEstimatedAltitude(uint32_t currentTime)
}
BaroAlt = baroCalculateAltitude();
#else
BaroAlt = 0;
#endif
#ifdef SONAR
tiltAngle = calculateTiltAngle(&inclination);
@ -496,9 +501,11 @@ void calculateEstimatedAltitude(uint32_t currentTime)
accSum_reset();
#ifdef BARO
if (!isBaroCalibrationComplete()) {
return;
}
#endif
if (sonarAlt > 0 && sonarAlt < 200) {
// the sonar has the best range