mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_Soaring: 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
67bbc6962a
commit
31a32c7ea0
@ -141,7 +141,7 @@ SoaringController::SoaringController(AP_AHRS &ahrs, AP_SpdHgtControl &spdHgt, co
|
||||
void SoaringController::get_target(Location &wp)
|
||||
{
|
||||
wp = _prev_update_location;
|
||||
location_offset(wp, _ekf.X[2], _ekf.X[3]);
|
||||
wp.offset(_ekf.X[2], _ekf.X[3]);
|
||||
}
|
||||
|
||||
bool SoaringController::suppress_throttle()
|
||||
|
Loading…
Reference in New Issue
Block a user