From f4fee69f296601869a940f496b355a070315adb2 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 8 Aug 2016 12:14:02 +0900 Subject: [PATCH] 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 --- ArduCopter/Attitude.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ArduCopter/Attitude.cpp b/ArduCopter/Attitude.cpp index 073d0e697e..bdcc379621 100644 --- a/ArduCopter/Attitude.cpp +++ b/ArduCopter/Attitude.cpp @@ -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);