mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS_DCM: adjust for location flags being moved out of union
This commit is contained in:
parent
a3a012b77e
commit
b416bc603e
|
@ -982,8 +982,8 @@ bool AP_AHRS_DCM::get_position(struct Location &loc) const
|
|||
loc.lat = _last_lat;
|
||||
loc.lng = _last_lng;
|
||||
loc.alt = AP::baro().get_altitude() * 100 + _home.alt;
|
||||
loc.flags.relative_alt = 0;
|
||||
loc.flags.terrain_alt = 0;
|
||||
loc.relative_alt = 0;
|
||||
loc.terrain_alt = 0;
|
||||
location_offset(loc, _position_offset_north, _position_offset_east);
|
||||
const AP_GPS &_gps = AP::gps();
|
||||
if (_flags.fly_forward && _have_position) {
|
||||
|
@ -1034,7 +1034,6 @@ bool AP_AHRS_DCM::airspeed_estimate(float *airspeed_ret) const
|
|||
void AP_AHRS_DCM::set_home(const Location &loc)
|
||||
{
|
||||
_home = loc;
|
||||
_home.options = 0;
|
||||
_home_is_set = true;
|
||||
|
||||
// log ahrs home and ekf origin dataflash
|
||||
|
|
Loading…
Reference in New Issue