Copter: poshold loses stray set-desired-spool-state

spool state is all handled higher up in the poshold state switch statement
This commit is contained in:
Randy Mackay 2019-04-05 14:15:28 +09:00
parent 29d05dfeac
commit d626ea66f1

View File

@ -443,9 +443,6 @@ void Copter::ModePosHold::run()
break;
}
// set motors to full range
motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
//
// Shared roll & pitch states (POSHOLD_BRAKE_TO_LOITER and POSHOLD_LOITER)
//