mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 00:58:37 -04:00
AP_MotorsMulticopter: add spool_up_complete accessor function
This commit is contained in:
parent
983d2dc97a
commit
d7c27c949c
@ -119,6 +119,9 @@ public:
|
||||
// get_throttle_limit - throttle limit ratio - for logging purposes only
|
||||
float get_throttle_limit() const { return _throttle_limit; }
|
||||
|
||||
// return true if spool up is complete
|
||||
bool spool_up_complete() const { return _multicopter_flags.spool_mode == THROTTLE_UNLIMITED; }
|
||||
|
||||
// var_info for holding Parameter information
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user