Copter: add div-by-zero check to get_pilot_desired_throttle
This divide by zero is only possible if there was a coding error in the setup of the throttle channel but added to make Covarity happy
This commit is contained in:
parent
20ade3bb17
commit
f4fee69f29
@ -142,6 +142,11 @@ float Copter::get_pilot_desired_throttle(int16_t throttle_control)
|
||||
|
||||
int16_t mid_stick = channel_throttle->get_control_mid();
|
||||
|
||||
// protect against unlikely divide by zero
|
||||
if (mid_stick <= 0) {
|
||||
mid_stick = 500;
|
||||
}
|
||||
|
||||
// ensure reasonable throttle values
|
||||
throttle_control = constrain_int16(throttle_control,0,1000);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user