Skip to content

Commit

Permalink
Copter: Remove redundant throttle channel setting
Browse files Browse the repository at this point in the history
  • Loading branch information
WickedShell committed Jul 25, 2018
1 parent 4b5babe commit 8891b71
Showing 1 changed file with 0 additions and 4 deletions.
4 changes: 0 additions & 4 deletions ArduCopter/radio.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}

Expand All @@ -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;
}

Expand All @@ -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
Expand All @@ -161,7 +158,6 @@ void Copter::set_throttle_and_failsafe(uint16_t throttle_pwm)
}
}
// pass through throttle
channel_throttle->set_pwm(throttle_pwm);
}
}

Expand Down

0 comments on commit 8891b71

Please sign in to comment.