Copter: Remove redundant throttle channel setting

This commit is contained in:
Michael du Breuil 2018-07-24 20:39:27 -07:00 committed by Andrew Tridgell
parent 80313abf31
commit 5825222818

View File

@ -128,7 +128,6 @@ void Copter::set_throttle_and_failsafe(uint16_t throttle_pwm)
{
// if failsafe not enabled pass through throttle and exit
if(g.failsafe_throttle == FS_THR_DISABLED) {
channel_throttle->set_pwm(throttle_pwm);
return;
}
@ -137,7 +136,6 @@ void Copter::set_throttle_and_failsafe(uint16_t throttle_pwm)
// if we are already in failsafe or motors not armed pass through throttle and exit
if (failsafe.radio || !(ap.rc_receiver_present || motors->armed())) {
channel_throttle->set_pwm(throttle_pwm);
return;
}
@ -147,7 +145,6 @@ void Copter::set_throttle_and_failsafe(uint16_t throttle_pwm)
if( failsafe.radio_counter >= FS_COUNTER ) {
failsafe.radio_counter = FS_COUNTER; // check to ensure we don't overflow the counter
set_failsafe_radio(true);
channel_throttle->set_pwm(throttle_pwm); // pass through failsafe throttle
}
}else{
// we have a good throttle so reduce failsafe counter
@ -161,7 +158,6 @@ void Copter::set_throttle_and_failsafe(uint16_t throttle_pwm)
}
}
// pass through throttle
channel_throttle->set_pwm(throttle_pwm);
}
}