Browse Source

Plane: Call plane.update_loiter() rather than plane.mode_loiter.navigate().

zr-v5.1
Samuel Tabor 5 years ago committed by Peter Barker
parent
commit
6a27866df4
  1. 3
      ArduPlane/mode_avoidADSB.cpp
  2. 3
      ArduPlane/mode_guided.cpp
  3. 3
      ArduPlane/mode_takeoff.cpp

3
ArduPlane/mode_avoidADSB.cpp

@ -13,6 +13,7 @@ void ModeAvoidADSB::update() @@ -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);
}

3
ArduPlane/mode_guided.cpp

@ -30,6 +30,7 @@ void ModeGuided::update() @@ -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);
}

3
ArduPlane/mode_takeoff.cpp

@ -133,6 +133,7 @@ void ModeTakeoff::update() @@ -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…
Cancel
Save