mavlink: fix invalid param handle check in send_autopilot_capabilities

Fix logic error where `mnt_mode_in` (value) was checked against `PARAM_INVALID`
instead of `param_handle`. This caused `param_get` to be called with an invalid
handle if the parameter was missing.
This commit is contained in:
zhaosheng.tan 2026-02-28 11:13:07 +08:00 committed by Jacob Dahl
parent affc18a056
commit d495014878

View File

@ -1087,7 +1087,7 @@ Mavlink::send_autopilot_capabilities()
param_t param_handle = param_find_no_notification("MNT_MODE_IN");
int32_t mnt_mode_in = 0;
if (mnt_mode_in != PARAM_INVALID) {
if (param_handle != PARAM_INVALID) {
param_get(param_handle, &mnt_mode_in);
if (mnt_mode_in == 4) {