@ -108,7 +108,7 @@ void ModeThrow::run()
@@ -108,7 +108,7 @@ void ModeThrow::run()
case Throw_Disarmed :
// prevent motors from rotating before the throw is detected unless enabled by the user
if ( g . throw_motor_start = = 1 ) {
if ( g . throw_motor_start = = PreThrowMotorState : : RUNNING ) {
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : GROUND_IDLE ) ;
} else {
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : SHUT_DOWN ) ;
@ -123,7 +123,7 @@ void ModeThrow::run()
@@ -123,7 +123,7 @@ void ModeThrow::run()
case Throw_Detecting :
// prevent motors from rotating before the throw is detected unless enabled by the user
if ( g . throw_motor_start = = 1 ) {
if ( g . throw_motor_start = = PreThrowMotorState : : RUNNING ) {
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : GROUND_IDLE ) ;
} else {
motors - > set_desired_spool_state ( AP_Motors : : DesiredSpoolState : : SHUT_DOWN ) ;