mirror of https://github.com/ArduPilot/ardupilot
Mavlink: fixed warnings about limits on int32 values
This commit is contained in:
parent
409c147ce3
commit
8ccf3a05f0
|
@ -1471,7 +1471,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
#endif
|
#endif
|
||||||
if (packet.param_value < 0) rounding_addition = -rounding_addition;
|
if (packet.param_value < 0) rounding_addition = -rounding_addition;
|
||||||
float v = packet.param_value+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);
|
((AP_Int32 *)vp)->set_and_save(v);
|
||||||
} else if (var_type == AP_PARAM_INT16) {
|
} else if (var_type == AP_PARAM_INT16) {
|
||||||
#if LOGGING_ENABLED == ENABLED
|
#if LOGGING_ENABLED == ENABLED
|
||||||
|
|
|
@ -1792,7 +1792,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
} else if (var_type == AP_PARAM_INT32) {
|
} else if (var_type == AP_PARAM_INT32) {
|
||||||
if (packet.param_value < 0) rounding_addition = -rounding_addition;
|
if (packet.param_value < 0) rounding_addition = -rounding_addition;
|
||||||
float v = packet.param_value+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);
|
((AP_Int32 *)vp)->set_and_save(v);
|
||||||
} else if (var_type == AP_PARAM_INT16) {
|
} else if (var_type == AP_PARAM_INT16) {
|
||||||
if (packet.param_value < 0) rounding_addition = -rounding_addition;
|
if (packet.param_value < 0) rounding_addition = -rounding_addition;
|
||||||
|
|
Loading…
Reference in New Issue