DataFlash: adjust for location flags being moved out of union

This commit is contained in:
Peter Barker 2019-01-02 15:46:33 +11:00 committed by Peter Barker
parent 90b708f9e7
commit f1299dc9bf
1 changed files with 1 additions and 1 deletions

View File

@ -1309,7 +1309,7 @@ void DataFlash_Class::Log_Write_Radio(const mavlink_radio_t &packet)
void DataFlash_Class::Log_Write_CameraInfo(enum LogMessages msg, const AP_AHRS &ahrs, const Location &current_loc, uint64_t timestamp_us)
{
int32_t altitude, altitude_rel, altitude_gps;
if (current_loc.flags.relative_alt) {
if (current_loc.relative_alt) {
altitude = current_loc.alt+ahrs.get_home().alt;
altitude_rel = current_loc.alt;
} else {