mirror of https://github.com/ArduPilot/ardupilot
Plane: move landing servo override out of throttle control function
This commit is contained in:
parent
283a1edb9f
commit
21a9f8e3a2
|
@ -1091,7 +1091,7 @@ private:
|
|||
// servos.cpp
|
||||
void set_servos_idle(void);
|
||||
void set_servos();
|
||||
void set_servos_controlled(void);
|
||||
void set_throttle(void);
|
||||
void set_takeoff_expected(void);
|
||||
void set_servos_old_elevons(void);
|
||||
void set_servos_flaps(void);
|
||||
|
|
|
@ -829,8 +829,13 @@ void Plane::set_servos(void)
|
|||
quadplane.update();
|
||||
#endif
|
||||
|
||||
if (flight_stage == AP_FixedWing::FlightStage::LAND) {
|
||||
// allow landing to override servos if it would like to
|
||||
landing.override_servos();
|
||||
}
|
||||
|
||||
if (control_mode != &mode_manual) {
|
||||
set_servos_controlled();
|
||||
set_throttle();
|
||||
set_takeoff_expected();
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue