Plane: Allow AP_Soaring to specify loiter radius in THERMAL mode.

This commit is contained in:
Samuel Tabor 2021-01-20 21:08:27 +00:00 committed by Tom Pittenger
parent 4ec1e55833
commit d2c8eb8ce9
1 changed files with 4 additions and 2 deletions

View File

@ -114,8 +114,10 @@ void ModeThermal::update_soaring()
void ModeThermal::navigate()
{
// Zero indicates to use WP_LOITER_RAD
plane.update_loiter(0);
// Soaring library calculates radius from SOAR_THML_BANK.
const float radius = plane.g2.soaring_controller.get_thermalling_radius();
plane.update_loiter(radius);
}
bool ModeThermal::exit_heading_aligned() const