APM: fixed rounding of altitude
the cast was rounding to the nearest meter
This commit is contained in:
parent
d7d33c64b7
commit
7815e3d810
@ -21,7 +21,7 @@ static LowPassFilterInt32 altitude_filter(0.3);
|
|||||||
static int32_t read_barometer(void)
|
static int32_t read_barometer(void)
|
||||||
{
|
{
|
||||||
barometer.read();
|
barometer.read();
|
||||||
return altitude_filter.apply(((int32_t)barometer.get_altitude() * 100.0));
|
return altitude_filter.apply(barometer.get_altitude() * 100.0);
|
||||||
}
|
}
|
||||||
|
|
||||||
// in M/S * 100
|
// in M/S * 100
|
||||||
|
Loading…
Reference in New Issue
Block a user