GCS_MAVLInk: Judgment of non-existence value by PARAM_SET

This commit is contained in:
murata 2019-12-26 08:00:15 +09:00 committed by Andrew Tridgell
parent ece777098c
commit 91e09338ea

View File

@ -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;
}