mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Fixed Barometer Altitude
This commit is contained in:
parent
80f5292d31
commit
c26956af19
@ -183,8 +183,9 @@ void DcmNavigator::updateFast(float dt) {
|
||||
scaling = getGroundPressure()/abs_pressure;
|
||||
temp = getGroundTemperature() + 273.15f;
|
||||
x = log(scaling) * temp * 29271.267f;
|
||||
_hal->debug->printf_P(PSTR("Ground Pressure %f\tAbsolute Pressure = %f\tGround Temperature = %f\tscaling= %f\n"),getGroundPressure(),abs_pressure,temp,log(scaling));
|
||||
setAlt_intM(x / 10); //changed this from 10 to 100
|
||||
//Barometer Debug
|
||||
//_hal->debug->printf_P(PSTR("Ground Pressure %f\tAbsolute Pressure = %f\tGround Temperature = %f\tscaling= %f\n"),getGroundPressure(),abs_pressure,temp,log(scaling));
|
||||
setAlt_intM(x / 10);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user