From 9584aa89d91a3ffb5be2e80f56d4e1c4ef9ce63b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 2 May 2013 10:27:10 +1000 Subject: [PATCH] Plane: replaced constrain() with constrain_float() --- ArduPlane/Attitude.pde | 6 +++--- ArduPlane/GCS_Mavlink.pde | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index c6876a8b29..8da141dd64 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -19,7 +19,7 @@ static float get_speed_scaler(void) } else { speed_scaler = 2.0; } - speed_scaler = constrain(speed_scaler, 0.5, 2.0); + speed_scaler = constrain_float(speed_scaler, 0.5, 2.0); } else { if (g.channel_throttle.servo_out > 0) { speed_scaler = 0.5 + ((float)THROTTLE_CRUISE / g.channel_throttle.servo_out / 2.0); // First order taylor expansion of square root @@ -28,7 +28,7 @@ static float get_speed_scaler(void) speed_scaler = 1.67; } // This case is constrained tighter as we don't have real speed info - speed_scaler = constrain(speed_scaler, 0.6, 1.67); + speed_scaler = constrain_float(speed_scaler, 0.6, 1.67); } return speed_scaler; } @@ -377,7 +377,7 @@ static void calc_nav_roll() * float roll_slew_limit(float servo) * { * static float last; - * float temp = constrain(servo, last-ROLL_SLEW_LIMIT * delta_ms_fast_loop/1000.f, last + ROLL_SLEW_LIMIT * delta_ms_fast_loop/1000.f); + * float temp = constrain_float(servo, last-ROLL_SLEW_LIMIT * delta_ms_fast_loop/1000.f, last + ROLL_SLEW_LIMIT * delta_ms_fast_loop/1000.f); * last = servo; * return temp; * }*/ diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 6c06852d6f..5047fa974a 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -1797,17 +1797,17 @@ mission_failed: } else if (var_type == AP_PARAM_INT32) { if (packet.param_value < 0) rounding_addition = -rounding_addition; float v = packet.param_value+rounding_addition; - v = constrain(v, -2147483648.0, 2147483647.0); + v = constrain_float(v, -2147483648.0, 2147483647.0); ((AP_Int32 *)vp)->set_and_save(v); } else if (var_type == AP_PARAM_INT16) { if (packet.param_value < 0) rounding_addition = -rounding_addition; float v = packet.param_value+rounding_addition; - v = constrain(v, -32768, 32767); + v = constrain_float(v, -32768, 32767); ((AP_Int16 *)vp)->set_and_save(v); } else if (var_type == AP_PARAM_INT8) { if (packet.param_value < 0) rounding_addition = -rounding_addition; float v = packet.param_value+rounding_addition; - v = constrain(v, -128, 127); + v = constrain_float(v, -128, 127); ((AP_Int8 *)vp)->set_and_save(v); } else { // we don't support mavlink set on this parameter