mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Periph: fixed handling of 16 char param names
This commit is contained in:
parent
ad3b1eaaf0
commit
c6a372bfdd
@ -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 {
|
||||
|
Loading…
Reference in New Issue
Block a user