mirror of https://github.com/ArduPilot/ardupilot
DataFlash: use print_latlon()
This commit is contained in:
parent
e1f9297551
commit
cf0c8331c2
|
@ -119,7 +119,7 @@ Format characters in the format string for binary log messages
|
|||
C : uint16_t * 100
|
||||
e : int32_t * 100
|
||||
E : uint32_t * 100
|
||||
L : uint32_t latitude/longitude
|
||||
L : int32_t latitude/longitude
|
||||
*/
|
||||
|
||||
// structure used to define logging format
|
||||
|
|
|
@ -4,6 +4,7 @@
|
|||
#include "DataFlash.h"
|
||||
#include <stdlib.h>
|
||||
#include <AP_Param.h>
|
||||
#include <AP_Math.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
|
@ -364,20 +365,7 @@ void DataFlash_Class::_print_log_entry(uint8_t msg_type,
|
|||
case 'L': {
|
||||
int32_t v;
|
||||
memcpy(&v, &pkt[ofs], sizeof(v));
|
||||
int32_t dec_portion, frac_portion;
|
||||
int32_t abs_lat_or_lon = labs(v);
|
||||
|
||||
// extract decimal portion (special handling of negative numbers to ensure we round towards zero)
|
||||
dec_portion = abs_lat_or_lon / 10000000UL;
|
||||
|
||||
// extract fractional portion
|
||||
frac_portion = abs_lat_or_lon - dec_portion*10000000UL;
|
||||
|
||||
// print output including the minus sign
|
||||
if (v < 0) {
|
||||
port->printf_P(PSTR("-"));
|
||||
}
|
||||
port->printf_P(PSTR("%ld.%07ld"),(long)dec_portion,(long)frac_portion);
|
||||
print_latlon(port, v);
|
||||
ofs += sizeof(v);
|
||||
break;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue