Browse Source

AP_Periph: fixed handling of 16 char param names

master
Andrew Tridgell 5 years ago
parent
commit
c6a372bfdd
  1. 4
      Tools/AP_Periph/can.cpp

4
Tools/AP_Periph/can.cpp

@ -162,9 +162,9 @@ static void handle_param_getset(CanardInstance* ins, CanardRxTransfer* transfer)
AP_Param *vp; AP_Param *vp;
enum ap_var_type ptype; 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; 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); strncpy((char *)name, (char *)req.name.data, req.name.len);
vp = AP_Param::find((char *)name, &ptype); vp = AP_Param::find((char *)name, &ptype);
} else { } else {

Loading…
Cancel
Save