mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_HAL: remember details of register check fails
this allows for logging of register resets
This commit is contained in:
parent
85ef6b7ac6
commit
7010eae9e8
@ -103,12 +103,13 @@ bool AP_HAL::Device::check_next_register(void)
|
|||||||
|
|
||||||
if (_bank_select) {
|
if (_bank_select) {
|
||||||
if (!_bank_select(reg.bank)) {
|
if (!_bank_select(reg.bank)) {
|
||||||
// Cannot set bank
|
// Cannot set bank
|
||||||
#if 0
|
#if 0
|
||||||
printf("Device 0x%x set bank 0x%02x\n",
|
printf("Device 0x%x set bank 0x%02x\n",
|
||||||
(unsigned)get_bus_id(),
|
(unsigned)get_bus_id(),
|
||||||
(unsigned)reg.bank);
|
(unsigned)reg.bank);
|
||||||
#endif
|
#endif
|
||||||
|
_checked.last_reg_fail = reg;
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -123,8 +124,22 @@ bool AP_HAL::Device::check_next_register(void)
|
|||||||
(unsigned)reg.regnum, (unsigned)v, (unsigned)reg.value);
|
(unsigned)reg.regnum, (unsigned)v, (unsigned)reg.value);
|
||||||
#endif
|
#endif
|
||||||
write_register(reg.regnum, reg.value);
|
write_register(reg.regnum, reg.value);
|
||||||
|
_checked.last_reg_fail = reg;
|
||||||
|
_checked.last_reg_fail.value = v;
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
_checked.next = (_checked.next+1) % _checked.n_set;
|
_checked.next = (_checked.next+1) % _checked.n_set;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
check one register value, returning information on the failure
|
||||||
|
*/
|
||||||
|
bool AP_HAL::Device::check_next_register(struct checkreg &fail)
|
||||||
|
{
|
||||||
|
if (check_next_register()) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
fail = _checked.last_reg_fail;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
@ -201,6 +201,20 @@ public:
|
|||||||
*/
|
*/
|
||||||
bool check_next_register(void);
|
bool check_next_register(void);
|
||||||
|
|
||||||
|
// checked registers
|
||||||
|
struct checkreg {
|
||||||
|
uint8_t bank;
|
||||||
|
uint8_t regnum;
|
||||||
|
uint8_t value;
|
||||||
|
};
|
||||||
|
|
||||||
|
/**
|
||||||
|
* check next register value for correctness, with return of
|
||||||
|
* failure value. Return false if value is incorrect or register
|
||||||
|
* checking has not been setup
|
||||||
|
*/
|
||||||
|
bool check_next_register(struct checkreg &fail);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Wrapper function over #transfer() to read a sequence of bytes from
|
* Wrapper function over #transfer() to read a sequence of bytes from
|
||||||
* device. No value is written, differently from the #read_registers()
|
* device. No value is written, differently from the #read_registers()
|
||||||
@ -390,18 +404,13 @@ protected:
|
|||||||
private:
|
private:
|
||||||
BankSelectCb _bank_select;
|
BankSelectCb _bank_select;
|
||||||
|
|
||||||
// checked registers
|
|
||||||
struct checkreg {
|
|
||||||
uint8_t bank;
|
|
||||||
uint8_t regnum;
|
|
||||||
uint8_t value;
|
|
||||||
};
|
|
||||||
struct {
|
struct {
|
||||||
uint8_t n_allocated;
|
uint8_t n_allocated;
|
||||||
uint8_t n_set;
|
uint8_t n_set;
|
||||||
uint8_t next;
|
uint8_t next;
|
||||||
uint8_t frequency;
|
uint8_t frequency;
|
||||||
uint8_t counter;
|
uint8_t counter;
|
||||||
|
struct checkreg last_reg_fail;
|
||||||
struct checkreg *regs;
|
struct checkreg *regs;
|
||||||
} _checked;
|
} _checked;
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user