Browse Source

GCS_MAVLInk: Judgment of non-existence value by PARAM_SET

zr-v5.1
murata 5 years ago committed by Andrew Tridgell
parent
commit
91e09338ea
  1. 2
      libraries/GCS_MAVLink/GCS_Param.cpp

2
libraries/GCS_MAVLink/GCS_Param.cpp

@ -268,7 +268,7 @@ void GCS_MAVLINK::handle_param_set(const mavlink_message_t &msg) @@ -268,7 +268,7 @@ void GCS_MAVLINK::handle_param_set(const mavlink_message_t &msg)
// find existing param so we can get the old value
uint16_t parameter_flags = 0;
vp = AP_Param::find(key, &var_type, &parameter_flags);
if (vp == nullptr) {
if (vp == nullptr || isnan(packet.param_value) || isinf(packet.param_value)) {
return;
}

Loading…
Cancel
Save