mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: Capture the case where the persistent parameter is the newer format INSn_ACC_ID
This fixes the handling of the newer INSn_* parameters when loading those stored in persistent memory.
This commit is contained in:
parent
c771440ea4
commit
ce0ae33c5b
|
@ -641,8 +641,11 @@ void Util::apply_persistent_params(void) const
|
|||
been done by whether the IDs are configured in
|
||||
storage
|
||||
*/
|
||||
if (strncmp(pname, "INS_ACC", 7) == 0 &&
|
||||
strcmp(pname+strlen(pname)-3, "_ID") == 0) {
|
||||
bool legacy_acc_id = strncmp(pname, "INS_ACC", 7) == 0 &&
|
||||
strcmp(pname+strlen(pname)-3, "_ID") == 0;
|
||||
bool new_acc_id = strncmp(pname, "INS", 3) == 0 &&
|
||||
strcmp(pname+strlen(pname)-6, "ACC_ID") == 0;
|
||||
if (legacy_acc_id || new_acc_id) {
|
||||
enum ap_var_type ptype;
|
||||
AP_Int32 *ap = (AP_Int32 *)AP_Param::find(pname, &ptype);
|
||||
if (ap && ptype == AP_PARAM_INT32) {
|
||||
|
|
Loading…
Reference in New Issue