Browse Source

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

zr-v5.1
Samuel Tabor 4 years ago committed by Tom Pittenger
parent
commit
d2c8eb8ce9
  1. 6
      ArduPlane/mode_thermal.cpp

6
ArduPlane/mode_thermal.cpp

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

Loading…
Cancel
Save