mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
GCS_MAVLInk: Judgment of non-existence value by PARAM_SET
This commit is contained in:
parent
ece777098c
commit
91e09338ea
@ -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, ¶meter_flags);
|
||||
if (vp == nullptr) {
|
||||
if (vp == nullptr || isnan(packet.param_value) || isinf(packet.param_value)) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user