mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: replace location_offset() and get_distance() function calls with Location object member function calls
This allows removing duplicated code
This commit is contained in:
parent
f2ca3556cd
commit
44ab1cf14b
|
@ -984,7 +984,7 @@ bool AP_AHRS_DCM::get_position(struct Location &loc) const
|
|||
loc.alt = AP::baro().get_altitude() * 100 + _home.alt;
|
||||
loc.relative_alt = 0;
|
||||
loc.terrain_alt = 0;
|
||||
location_offset(loc, _position_offset_north, _position_offset_east);
|
||||
loc.offset(_position_offset_north, _position_offset_east);
|
||||
const AP_GPS &_gps = AP::gps();
|
||||
if (_flags.fly_forward && _have_position) {
|
||||
float gps_delay_sec = 0;
|
||||
|
|
Loading…
Reference in New Issue