mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: mode_qhover: combine enter and init
This commit is contained in:
parent
f055471d8a
commit
5ebd439712
@ -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()
|
||||
|
Loading…
Reference in New Issue
Block a user