From f5cf88dc729f1331bc9ded81ad44bf1d05798675 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 14 Oct 2023 15:15:50 +1100 Subject: [PATCH] fixed handling of negative lock level --- RemoteIDModule/DroneCAN.cpp | 2 +- RemoteIDModule/mavlink.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/RemoteIDModule/DroneCAN.cpp b/RemoteIDModule/DroneCAN.cpp index 2e8a9a4..8e5ca3f 100644 --- a/RemoteIDModule/DroneCAN.cpp +++ b/RemoteIDModule/DroneCAN.cpp @@ -597,7 +597,7 @@ void DroneCAN::handle_param_getset(CanardInstance* ins, CanardRxTransfer* transf } if (vp != nullptr && req.name.len != 0 && req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY) { - if (g.lock_level != 0) { + if (g.lock_level > 0) { can_printf("Parameters locked"); } else { // param set diff --git a/RemoteIDModule/mavlink.cpp b/RemoteIDModule/mavlink.cpp index cf6403b..98ccc00 100644 --- a/RemoteIDModule/mavlink.cpp +++ b/RemoteIDModule/mavlink.cpp @@ -242,7 +242,7 @@ void MAVLinkSerial::process_packet(mavlink_status_t &status, mavlink_message_t & return; } p->get_as_float(value); - if (g.lock_level != 0 && + if (g.lock_level > 0 && (strcmp(p->name, "LOCK_LEVEL") != 0 || uint8_t(pkt.param_value) <= uint8_t(value))) { // only param set allowed is to increase lock level