mirror of https://github.com/ArduPilot/ardupilot
Plane: mode_qstabilize: combine enter and init
This commit is contained in:
parent
63be15e018
commit
fae22b34b7
|
@ -2,18 +2,9 @@
|
|||
#include "Plane.h"
|
||||
|
||||
bool ModeQStabilize::_enter()
|
||||
{
|
||||
if (!plane.quadplane.init_mode()) {
|
||||
return false;
|
||||
}
|
||||
plane.auto_state.vtol_mode = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
// init quadplane stabilize mode
|
||||
void ModeQStabilize::init()
|
||||
{
|
||||
quadplane.throttle_wait = false;
|
||||
return true;
|
||||
}
|
||||
|
||||
void ModeQStabilize::update()
|
||||
|
|
Loading…
Reference in New Issue