AP_Motors: remove unused DESIRED_SPIN_MIN_THROTTLE

This commit is contained in:
Randy Mackay 2016-03-25 17:59:26 +09:00
parent dc86e1472c
commit b39798ad90
1 changed files with 1 additions and 2 deletions

View File

@ -77,8 +77,7 @@ public:
enum spool_up_down_desired {
DESIRED_SHUT_DOWN = 0, // all motors stop
DESIRED_SPIN_WHEN_ARMED = 1, // all motors at spin when armed
DESIRED_SPIN_MIN_THROTTLE = 2, // all motors at min throttle
DESIRED_THROTTLE_UNLIMITED = 3, // motors are no longer constrained by start up procedure
DESIRED_THROTTLE_UNLIMITED = 2, // motors are no longer constrained by start up procedure
};
virtual void set_desired_spool_state(enum spool_up_down_desired spool) { _spool_desired = spool; };