mirror of https://github.com/ArduPilot/ardupilot
AP_Filesystem: detect inconsistent parameter count
on incorrect param count invalidate it so a 2nd param ftp will get the right count
This commit is contained in:
parent
f0bc31cdc3
commit
0b7353bb89
|
@ -188,6 +188,11 @@ uint8_t AP_Filesystem_Param::pack_param(const struct rfile &r, struct cursor &c,
|
||||||
ap = AP_Param::next_scalar(&c.token, &ptype, &default_val);
|
ap = AP_Param::next_scalar(&c.token, &ptype, &default_val);
|
||||||
}
|
}
|
||||||
if (ap == nullptr || (r.count && c.idx >= r.count)) {
|
if (ap == nullptr || (r.count && c.idx >= r.count)) {
|
||||||
|
if (r.count == 0 && c.idx != AP_Param::count_parameters()) {
|
||||||
|
// the parameter count is incorrect, invalidate so a
|
||||||
|
// repeated param download avoids an error
|
||||||
|
AP_Param::invalidate_count();
|
||||||
|
}
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
ap->copy_name_token(c.token, name, AP_MAX_NAME_SIZE, true);
|
ap->copy_name_token(c.token, name, AP_MAX_NAME_SIZE, true);
|
||||||
|
|
Loading…
Reference in New Issue