5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-02-25 01:03:59 -04:00
ardupilot/ArduPlane/mode_autotune.cpp
2019-04-02 16:28:52 +11:00

25 lines
389 B
C++

#include "mode.h"
#include "Plane.h"
bool ModeAutoTune::_enter()
{
plane.throttle_allows_nudging = false;
plane.auto_throttle_mode = false;
plane.auto_navigation_mode = false;
plane.autotune_start();
return true;
}
void ModeAutoTune::_exit()
{
// restore last gains
plane.autotune_restore();
}
void ModeAutoTune::update()
{
plane.mode_fbwa.update();
}