mirror of https://github.com/ArduPilot/ardupilot
Plane: Call plane.update_loiter() rather than plane.mode_loiter.navigate().
This commit is contained in:
parent
06eea6ed9f
commit
6a27866df4
|
@ -13,6 +13,7 @@ void ModeAvoidADSB::update()
|
|||
|
||||
void ModeAvoidADSB::_navigate()
|
||||
{
|
||||
plane.mode_loiter.navigate();
|
||||
// Zero indicates to use WP_LOITER_RAD
|
||||
plane.update_loiter(0);
|
||||
}
|
||||
|
||||
|
|
|
@ -30,6 +30,7 @@ void ModeGuided::update()
|
|||
|
||||
void ModeGuided::_navigate()
|
||||
{
|
||||
plane.mode_loiter.navigate();
|
||||
// Zero indicates to use WP_LOITER_RAD
|
||||
plane.update_loiter(0);
|
||||
}
|
||||
|
||||
|
|
|
@ -133,6 +133,7 @@ void ModeTakeoff::update()
|
|||
|
||||
void ModeTakeoff::_navigate()
|
||||
{
|
||||
plane.mode_loiter.navigate();
|
||||
// Zero indicates to use WP_LOITER_RAD
|
||||
plane.update_loiter(0);
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue