mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_ICEngine: added allow_throttle_while_disarmed()
This commit is contained in:
parent
e46fec60e2
commit
f366cbbcb4
@ -55,6 +55,11 @@ public:
|
||||
// update min throttle for idle governor
|
||||
void update_idle_governor(int8_t &min_throttle);
|
||||
|
||||
// do we have throttle while disarmed enabled?
|
||||
bool allow_throttle_while_disarmed(void) const {
|
||||
return enable && option_set(Options::THROTTLE_WHILE_DISARMED);
|
||||
}
|
||||
|
||||
static AP_ICEngine *get_singleton() { return _singleton; }
|
||||
|
||||
private:
|
||||
|
Loading…
Reference in New Issue
Block a user