mirror of https://github.com/ArduPilot/ardupilot
AP_Baro: fixed a build warning
This commit is contained in:
parent
168f76e76c
commit
26bf636541
|
@ -35,16 +35,16 @@ void AP_Baro_HIL::setHIL(float altitude_msl)
|
||||||
{
|
{
|
||||||
// approximate a barometer. This uses the typical base pressure in
|
// approximate a barometer. This uses the typical base pressure in
|
||||||
// Canberra, Australia
|
// Canberra, Australia
|
||||||
const float Temp = 312;
|
const float temperature = 312;
|
||||||
|
|
||||||
float y = (altitude_msl - 584.0) / 29.271267;
|
float y = (altitude_msl - 584.0) / 29.271267;
|
||||||
y /= (Temp / 10.0) + 273.15;
|
y /= (temperature / 10.0) + 273.15;
|
||||||
y = 1.0/exp(y);
|
y = 1.0/exp(y);
|
||||||
y *= 95446.0;
|
y *= 95446.0;
|
||||||
|
|
||||||
_count++;
|
_count++;
|
||||||
_pressure_sum += y;
|
_pressure_sum += y;
|
||||||
_temperature_sum += Temp;
|
_temperature_sum += temperature;
|
||||||
if (_count == 128) {
|
if (_count == 128) {
|
||||||
// we have summed 128 values. This only happens
|
// we have summed 128 values. This only happens
|
||||||
// when we stop reading the barometer for a long time
|
// when we stop reading the barometer for a long time
|
||||||
|
|
Loading…
Reference in New Issue