Browse Source

MAVLink: constrain variable changes to the datatype range

if someone tries to set a AP_Int16 to a value of 300000, they now get
32767 instead of -27678
mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
458d55e5bc
  1. 12
      ArduCopter/GCS_Mavlink.pde
  2. 12
      ArduPlane/GCS_Mavlink.pde

12
ArduCopter/GCS_Mavlink.pde

@ -1470,19 +1470,25 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) @@ -1470,19 +1470,25 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
Log_Write_Data(1, ((AP_Int32 *)vp)->get());
#endif
if (packet.param_value < 0) rounding_addition = -rounding_addition;
((AP_Int32 *)vp)->set_and_save(packet.param_value+rounding_addition);
float v = packet.param_value+rounding_addition;
v = constrain(v, -2147483648, 2147483647);
((AP_Int32 *)vp)->set_and_save(v);
} else if (var_type == AP_PARAM_INT16) {
#if LOGGING_ENABLED == ENABLED
Log_Write_Data(3, (int32_t)((AP_Int16 *)vp)->get());
#endif
if (packet.param_value < 0) rounding_addition = -rounding_addition;
((AP_Int16 *)vp)->set_and_save(packet.param_value+rounding_addition);
float v = packet.param_value+rounding_addition;
v = constrain(v, -32768, 32767);
((AP_Int16 *)vp)->set_and_save(v);
} else if (var_type == AP_PARAM_INT8) {
#if LOGGING_ENABLED == ENABLED
Log_Write_Data(4, (int32_t)((AP_Int8 *)vp)->get());
#endif
if (packet.param_value < 0) rounding_addition = -rounding_addition;
((AP_Int8 *)vp)->set_and_save(packet.param_value+rounding_addition);
float v = packet.param_value+rounding_addition;
v = constrain(v, -128, 127);
((AP_Int8 *)vp)->set_and_save(v);
} else {
// we don't support mavlink set on this parameter
break;

12
ArduPlane/GCS_Mavlink.pde

@ -1791,13 +1791,19 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) @@ -1791,13 +1791,19 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
((AP_Float *)vp)->set_and_save(packet.param_value);
} else if (var_type == AP_PARAM_INT32) {
if (packet.param_value < 0) rounding_addition = -rounding_addition;
((AP_Int32 *)vp)->set_and_save(packet.param_value+rounding_addition);
float v = packet.param_value+rounding_addition;
v = constrain(v, -2147483648, 2147483647);
((AP_Int32 *)vp)->set_and_save(v);
} else if (var_type == AP_PARAM_INT16) {
if (packet.param_value < 0) rounding_addition = -rounding_addition;
((AP_Int16 *)vp)->set_and_save(packet.param_value+rounding_addition);
float v = packet.param_value+rounding_addition;
v = constrain(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;
((AP_Int8 *)vp)->set_and_save(packet.param_value+rounding_addition);
float v = packet.param_value+rounding_addition;
v = constrain(v, -128, 127);
((AP_Int8 *)vp)->set_and_save(v);
} else {
// we don't support mavlink set on this parameter
break;

Loading…
Cancel
Save