mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
APMrover2: compile warnings: float to double. print statements require doubles
This commit is contained in:
parent
0e3d54d9e4
commit
b35258efed
@ -510,7 +510,7 @@ static void report_compass()
|
|||||||
|
|
||||||
// mag declination
|
// mag declination
|
||||||
cliSerial->printf_P(PSTR("Mag Declination: %4.4f\n"),
|
cliSerial->printf_P(PSTR("Mag Declination: %4.4f\n"),
|
||||||
degrees(compass.get_declination()));
|
(double)degrees(compass.get_declination()));
|
||||||
|
|
||||||
Vector3f offsets = compass.get_offsets();
|
Vector3f offsets = compass.get_offsets();
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user