From c6a372bfdd70d5875d44746ad5dc6cb3c39dd597 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 23 Oct 2019 18:56:51 +1100 Subject: [PATCH] AP_Periph: fixed handling of 16 char param names --- Tools/AP_Periph/can.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index a09afd3803..553fea2b57 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -162,9 +162,9 @@ static void handle_param_getset(CanardInstance* ins, CanardRxTransfer* transfer) AP_Param *vp; enum ap_var_type ptype; - if (req.name.len != 0 && req.name.len >= AP_MAX_NAME_SIZE) { + if (req.name.len != 0 && req.name.len > AP_MAX_NAME_SIZE) { vp = nullptr; - } else if (req.name.len != 0 && req.name.len < AP_MAX_NAME_SIZE) { + } else if (req.name.len != 0 && req.name.len <= AP_MAX_NAME_SIZE) { strncpy((char *)name, (char *)req.name.data, req.name.len); vp = AP_Param::find((char *)name, &ptype); } else {