Plane: mode_qhover: combine enter and init

This commit is contained in:
Iampete1 2021-09-04 20:20:45 +01:00 committed by Andrew Tridgell
parent f055471d8a
commit 5ebd439712

View File

@ -2,12 +2,6 @@
#include "Plane.h"
bool ModeQHover::_enter()
{
return plane.mode_qstabilize._enter();
}
// init quadplane hover mode
void ModeQHover::init()
{
// set vertical speed and acceleration limits
pos_control->set_max_speed_accel_z(-quadplane.get_pilot_velocity_z_max_dn(), quadplane.pilot_velocity_z_max_up, quadplane.pilot_accel_z);
@ -15,6 +9,7 @@ void ModeQHover::init()
quadplane.set_climb_rate_cms(0, false);
quadplane.init_throttle_wait();
return true;
}
void ModeQHover::update()