AP_HAL: default to register checking every 10th call

this saves having this in nearly all callers
This commit is contained in:
Andrew Tridgell 2016-11-25 19:53:32 +11:00
parent 0e793e1214
commit 7100272f14
2 changed files with 13 additions and 3 deletions

View File

@ -35,13 +35,15 @@
/*
setup nregs checked registers
*/
bool AP_HAL::Device::setup_checked_registers(uint8_t nregs)
bool AP_HAL::Device::setup_checked_registers(uint8_t nregs, uint8_t frequency)
{
if (_checked.regs != nullptr) {
delete[] _checked.regs;
_checked.n_allocated = 0;
_checked.n_set = 0;
_checked.next = 0;
_checked.frequency = frequency;
_checked.counter = 0;
}
_checked.regs = new struct checkreg[nregs];
if (_checked.regs == nullptr) {
@ -84,6 +86,11 @@ bool AP_HAL::Device::check_next_register(void)
if (_checked.n_set == 0) {
return true;
}
if (++_checked.counter < _checked.frequency) {
return true;
}
_checked.counter = 0;
struct checkreg &reg = _checked.regs[_checked.next];
uint8_t v;
if (!read_registers(reg.regnum, &v, 1) || v != reg.value) {

View File

@ -121,9 +121,10 @@ public:
void set_checked_register(uint8_t reg, uint8_t val);
/**
* setup for register value checking
* setup for register value checking. Frequency is how often to check registers. If set to 10 then
* every 10th call to check_next_register will check a register
*/
bool setup_checked_registers(uint8_t num_regs);
bool setup_checked_registers(uint8_t num_regs, uint8_t frequency=10);
/**
* check next register value for correctness. Return false if value is incorrect
@ -266,6 +267,8 @@ private:
uint8_t n_allocated;
uint8_t n_set;
uint8_t next;
uint8_t frequency;
uint8_t counter;
struct checkreg *regs;
} _checked;
};