mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: added get_desired_spool_state()
This commit is contained in:
parent
699d5bf99c
commit
66c4995c9d
|
@ -82,6 +82,8 @@ public:
|
|||
|
||||
virtual void set_desired_spool_state(enum spool_up_down_desired spool) { _spool_desired = spool; };
|
||||
|
||||
enum spool_up_down_desired get_desired_spool_state(void) const { return _spool_desired; }
|
||||
|
||||
//
|
||||
// voltage, current and air pressure compensation or limiting features - multicopters only
|
||||
//
|
||||
|
|
Loading…
Reference in New Issue