From e340fac2e0fd994b00446ada74d64c3619cce254 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 25 Oct 2017 14:01:26 +1100 Subject: [PATCH] AP_Motors: avoid float exception for small expo very small values of the thrust expo cause a floating point exception. As zero is a documented value meaning linear we need to handle this. --- libraries/AP_Motors/AP_MotorsMulticopter.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 090bc85a1a..0e22b1e38d 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -298,6 +298,10 @@ float AP_MotorsMulticopter::apply_thrust_curve_and_volt_scaling(float thrust) co float throttle_ratio = thrust; // apply thrust curve - domain 0.0 to 1.0, range 0.0 to 1.0 float thrust_curve_expo = constrain_float(_thrust_curve_expo, -1.0f, 1.0f); + if (fabsf(thrust_curve_expo) < 0.001) { + // zero expo means linear, avoid floating point exception for small values + return thrust; + } if(!is_zero(_batt_voltage_filt.get())) { throttle_ratio = ((thrust_curve_expo-1.0f) + safe_sqrt((1.0f-thrust_curve_expo)*(1.0f-thrust_curve_expo) + 4.0f*thrust_curve_expo*_lift_max*thrust))/(2.0f*thrust_curve_expo*_batt_voltage_filt.get()); } else {