AP_Motors: Block Spoolup: stop advance from ground idle
This commit is contained in:
parent
ee31f2322e
commit
f3dc805978
@ -612,7 +612,10 @@ void AP_MotorsMulticopter::output_logic()
|
|||||||
// constrain ramp value and update mode
|
// constrain ramp value and update mode
|
||||||
if (_spin_up_ratio >= 1.0f) {
|
if (_spin_up_ratio >= 1.0f) {
|
||||||
_spin_up_ratio = 1.0f;
|
_spin_up_ratio = 1.0f;
|
||||||
_spool_state = SpoolState::SPOOLING_UP;
|
if (!get_spoolup_block()) {
|
||||||
|
// Only advance from ground idle if spoolup checks have passed
|
||||||
|
_spool_state = SpoolState::SPOOLING_UP;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
@ -77,11 +77,6 @@ void AP_Motors::armed(bool arm)
|
|||||||
|
|
||||||
void AP_Motors::set_desired_spool_state(DesiredSpoolState spool)
|
void AP_Motors::set_desired_spool_state(DesiredSpoolState spool)
|
||||||
{
|
{
|
||||||
// check if spoolup has been blocked
|
|
||||||
if (_spoolup_block && (spool == DesiredSpoolState::THROTTLE_UNLIMITED)) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (_armed || (spool == DesiredSpoolState::SHUT_DOWN)) {
|
if (_armed || (spool == DesiredSpoolState::SHUT_DOWN)) {
|
||||||
_spool_desired = spool;
|
_spool_desired = spool;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user