Ardupilot2/ArduPlane/mode_guided.cpp
Peter Barker f6cb1b5ad6 Plane: use a method on Mode for auto-navigation-mode
Avoids the state getting stale, which it will with a failed attempt to
go into qautotune, for example.
2021-01-10 16:04:30 +11:00

35 lines
741 B
C++

#include "mode.h"
#include "Plane.h"
bool ModeGuided::_enter()
{
plane.auto_throttle_mode = true;
plane.guided_throttle_passthru = false;
/*
when entering guided mode we set the target as the current
location. This matches the behaviour of the copter code
*/
plane.guided_WP_loc = plane.current_loc;
plane.set_guided_WP();
return true;
}
void ModeGuided::update()
{
if (plane.auto_state.vtol_loiter && plane.quadplane.available()) {
plane.quadplane.guided_update();
} else {
plane.calc_nav_roll();
plane.calc_nav_pitch();
plane.calc_throttle();
}
}
void ModeGuided::navigate()
{
// Zero indicates to use WP_LOITER_RAD
plane.update_loiter(0);
}