From 8ccf3a05f05b701ef6af4269071c5de1c64fe504 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 27 Mar 2012 15:37:14 +1100 Subject: [PATCH] Mavlink: fixed warnings about limits on int32 values --- ArduCopter/GCS_Mavlink.pde | 2 +- ArduPlane/GCS_Mavlink.pde | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index d97f89adc1..8cb0957367 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1471,7 +1471,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) #endif if (packet.param_value < 0) rounding_addition = -rounding_addition; float v = packet.param_value+rounding_addition; - v = constrain(v, -2147483648, 2147483647); + v = constrain(v, -2147483648.0, 2147483647.0); ((AP_Int32 *)vp)->set_and_save(v); } else if (var_type == AP_PARAM_INT16) { #if LOGGING_ENABLED == ENABLED diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index dd80bae476..60056b6fcc 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -1792,7 +1792,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) } 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, 2147483647); + v = constrain(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;