mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
fixed warning in Log build
This commit is contained in:
parent
bf1eb670e3
commit
a2d0900460
@ -219,7 +219,7 @@ void print_latlon(BetterStream *s, int32_t lat_or_lon)
|
|||||||
{
|
{
|
||||||
int32_t dec_portion = lat_or_lon / T7;
|
int32_t dec_portion = lat_or_lon / T7;
|
||||||
int32_t frac_portion = labs(lat_or_lon - dec_portion*T7);
|
int32_t frac_portion = labs(lat_or_lon - dec_portion*T7);
|
||||||
s->printf("%ld.%07ld",dec_portion,frac_portion);
|
s->printf("%ld.%07ld",(long)dec_portion,(long)frac_portion);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Write an GPS packet. Total length : 31 bytes
|
// Write an GPS packet. Total length : 31 bytes
|
||||||
|
Loading…
Reference in New Issue
Block a user