Don't send param_ack if parameter is not set

This commit is contained in:
Oleg Kalachev
2026-01-19 01:08:29 +03:00
parent cef1834ea3
commit 5960e85a74

View File

@@ -140,7 +140,8 @@ void handleMavlink(const void *_msg) {
char name[MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN + 1];
strlcpy(name, m.param_id, sizeof(name)); // param_id might be not null-terminated
setParameter(name, m.param_value);
bool success = setParameter(name, m.param_value);
if (!success) return;
// send ack
mavlink_message_t msg;
mavlink_msg_param_value_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg,