DataFlash: POS.RelOriginAlt should be NaN if unknown

This commit is contained in:
Michael du Breuil 2017-07-15 13:18:43 -07:00 committed by Francisco Ferreira
parent aee82db204
commit 52ddaa3e72

View File

@ -667,7 +667,6 @@ void DataFlash_Class::Log_Write_POS(AP_AHRS &ahrs)
} }
float home, origin; float home, origin;
ahrs.get_relative_position_D_home(home); ahrs.get_relative_position_D_home(home);
ahrs.get_relative_position_D_origin(origin);
struct log_POS pkt = { struct log_POS pkt = {
LOG_PACKET_HEADER_INIT(LOG_POS_MSG), LOG_PACKET_HEADER_INIT(LOG_POS_MSG),
time_us : AP_HAL::micros64(), time_us : AP_HAL::micros64(),
@ -675,7 +674,7 @@ void DataFlash_Class::Log_Write_POS(AP_AHRS &ahrs)
lng : loc.lng, lng : loc.lng,
alt : loc.alt*1.0e-2f, alt : loc.alt*1.0e-2f,
rel_home_alt : -home, rel_home_alt : -home,
rel_origin_alt : -origin rel_origin_alt : ahrs.get_relative_position_D_origin(origin) ? -origin : nanf("ARDUPILOT")
}; };
WriteBlock(&pkt, sizeof(pkt)); WriteBlock(&pkt, sizeof(pkt));
} }