Copter: refuse to enter manual throttle modes while landed with throttle high

This commit is contained in:
Jonathan Challinger 2015-10-19 21:56:18 -07:00 committed by Randy Mackay
parent ff2782b790
commit a5e4f64b20
2 changed files with 9 additions and 4 deletions

View File

@ -9,8 +9,11 @@
// acro_init - initialise acro controller
bool Copter::acro_init(bool ignore_checks)
{
// always successfully enter acro
return true;
// if landed and the mode we're switching from does not have manual throttle and the throttle stick is too high
if (motors.armed() && ap.land_complete && !mode_has_manual_throttle(control_mode) && (g.rc_3.control_in > get_non_takeoff_throttle())) {
return false;
}
return true;
}
// acro_run - runs the acro controller

View File

@ -9,11 +9,13 @@
// stabilize_init - initialise stabilize controller
bool Copter::stabilize_init(bool ignore_checks)
{
// if landed and the mode we're switching from does not have manual throttle and the throttle stick is too high
if (motors.armed() && ap.land_complete && !mode_has_manual_throttle(control_mode) && (g.rc_3.control_in > get_non_takeoff_throttle())) {
return false;
}
// set target altitude to zero for reporting
// To-Do: make pos controller aware when it's active/inactive so it can always report the altitude error?
pos_control.set_alt_target(0);
// stabilize should never be made to fail
return true;
}