mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
HAL_Flymaple: fix compile warnings re float constants
This commit is contained in:
parent
b7fb4022b4
commit
11951dbf48
@ -71,9 +71,9 @@ void loop()
|
|||||||
hal.console->print(" Temperature:");
|
hal.console->print(" Temperature:");
|
||||||
hal.console->print( bmp085.get_temperature());
|
hal.console->print( bmp085.get_temperature());
|
||||||
hal.console->print(" Altitude:");
|
hal.console->print(" Altitude:");
|
||||||
tmp_float = ( bmp085.get_pressure() / 101325.0);
|
tmp_float = ( bmp085.get_pressure() / 101325.0f);
|
||||||
tmp_float = pow(tmp_float, 0.190295);
|
tmp_float = pow(tmp_float, 0.190295f);
|
||||||
float alt = 44330.0 * (1.0 - tmp_float);
|
float alt = 44330.0f * (1.0f - tmp_float);
|
||||||
hal.console->print(alt);
|
hal.console->print(alt);
|
||||||
hal.console->printf(" t=%lu",
|
hal.console->printf(" t=%lu",
|
||||||
read_time);
|
read_time);
|
||||||
|
Loading…
Reference in New Issue
Block a user