mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_Baro: fixed temperature on MS5611
this caused a 2x scaling of altitude
This commit is contained in:
parent
bf38ae5960
commit
bb0f179495
@ -235,7 +235,8 @@ int32_t AP_Baro_MS5611::get_pressure()
|
||||
|
||||
int16_t AP_Baro_MS5611::get_temperature()
|
||||
{
|
||||
return(Temp);
|
||||
// callers want the temperature in 0.1C units
|
||||
return(Temp/10);
|
||||
}
|
||||
|
||||
// Return altitude using the standard 1013.25 mbar at sea level reference
|
||||
|
Loading…
Reference in New Issue
Block a user