mirror of https://github.com/ArduPilot/ardupilot
AP_Motors: remove unused DESIRED_SPIN_MIN_THROTTLE
This commit is contained in:
parent
dc86e1472c
commit
b39798ad90
|
@ -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; };
|
||||
|
|
Loading…
Reference in New Issue