mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
FrSky_Telem: fix compile warnings re float constants
This commit is contained in:
parent
dffcdbd751
commit
12b604663c
@ -494,12 +494,12 @@ void AP_Frsky_Telem::calc_gps_position()
|
||||
if (_pos_gps_ok) {
|
||||
Location loc = gps.location();//get gps instance 0
|
||||
|
||||
lat = frsky_format_gps(fabsf(loc.lat/10000000.0));
|
||||
lat = frsky_format_gps(fabsf(loc.lat/10000000.0f));
|
||||
_latdddmm = lat;
|
||||
_latmmmm = (lat - _latdddmm) * 10000;
|
||||
_lat_ns = (loc.lat < 0) ? 'S' : 'N';
|
||||
|
||||
lon = frsky_format_gps(fabsf(loc.lng/10000000.0));
|
||||
lon = frsky_format_gps(fabsf(loc.lng/10000000.0f));
|
||||
_londddmm = lon;
|
||||
_lonmmmm = (lon - _londddmm) * 10000;
|
||||
_lon_ew = (loc.lng < 0) ? 'W' : 'E';
|
||||
|
Loading…
Reference in New Issue
Block a user