Browse Source

AP_Soaring: replace location_offset() and get_distance() function calls with Location object member function calls

This allows removing duplicated code
master
Dr.-Ing. Amilcar do Carmo Lucas 6 years ago committed by Peter Barker
parent
commit
31a32c7ea0
  1. 2
      libraries/AP_Soaring/AP_Soaring.cpp

2
libraries/AP_Soaring/AP_Soaring.cpp

@ -141,7 +141,7 @@ SoaringController::SoaringController(AP_AHRS &ahrs, AP_SpdHgtControl &spdHgt, co @@ -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…
Cancel
Save