mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: Allow AP_Soaring to specify loiter radius in THERMAL mode.
This commit is contained in:
parent
4ec1e55833
commit
d2c8eb8ce9
@ -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…
Reference in New Issue
Block a user