Explorar o código

fixed handling of negative lock level

Andrew Tridgell %!s(int64=2) %!d(string=hai) anos
pai
achega
f5cf88dc72
Modificáronse 2 ficheiros con 2 adicións e 2 borrados
  1. 1 1
      RemoteIDModule/DroneCAN.cpp
  2. 1 1
      RemoteIDModule/mavlink.cpp

+ 1 - 1
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

+ 1 - 1
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