ardupilot/ArduPlane/mode_qautotune.cpp
2021-09-08 18:06:58 +10:00

32 lines
425 B
C++

#include "mode.h"
#include "Plane.h"
bool ModeQAutotune::_enter()
{
#if QAUTOTUNE_ENABLED
return quadplane.qautotune.init();
#else
return false;
#endif
}
void ModeQAutotune::update()
{
plane.mode_qstabilize.update();
}
void ModeQAutotune::run()
{
#if QAUTOTUNE_ENABLED
quadplane.qautotune.run();
#endif
}
void ModeQAutotune::_exit()
{
#if QAUTOTUNE_ENABLED
plane.quadplane.qautotune.stop();
#endif
}