diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index e670339e7b756..506ab0eee1e27 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -5151,7 +5151,11 @@ static int32_t convert_COMMAND_LONG_loc_param(float param, bool stores_location) } if (stores_location) { - return param *1e7; + float convertedValue = param *1e7; + if (convertedValue < INT32_MIN || convertedValue > INT32_MAX) { + return 0; + } + return convertedValue; } return param;