mirror of https://github.com/ArduPilot/ardupilot
AP_Beacon: adjust for location flags being moved out of union
This commit is contained in:
parent
8dfdda1cf0
commit
1075227c90
|
@ -137,10 +137,10 @@ bool AP_Beacon::get_origin(Location &origin_loc) const
|
||||||
}
|
}
|
||||||
|
|
||||||
// return origin
|
// return origin
|
||||||
|
memset(&origin_loc, 0, sizeof(origin_loc));
|
||||||
origin_loc.lat = origin_lat * 1.0e7;
|
origin_loc.lat = origin_lat * 1.0e7;
|
||||||
origin_loc.lng = origin_lon * 1.0e7;
|
origin_loc.lng = origin_lon * 1.0e7;
|
||||||
origin_loc.alt = origin_alt * 100;
|
origin_loc.alt = origin_alt * 100;
|
||||||
origin_loc.options = 0; // all flags to zero meaning alt-above-sea-level
|
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue