AP_HAL: fixed frequency init for register checking

This commit is contained in:
Andrew Tridgell 2016-11-26 18:36:36 +11:00
parent dc85ffa834
commit fdc94ec28a
1 changed files with 2 additions and 2 deletions

View File

@ -42,14 +42,14 @@ bool AP_HAL::Device::setup_checked_registers(uint8_t nregs, uint8_t frequency)
_checked.n_allocated = 0; _checked.n_allocated = 0;
_checked.n_set = 0; _checked.n_set = 0;
_checked.next = 0; _checked.next = 0;
_checked.frequency = frequency;
_checked.counter = 0;
} }
_checked.regs = new struct checkreg[nregs]; _checked.regs = new struct checkreg[nregs];
if (_checked.regs == nullptr) { if (_checked.regs == nullptr) {
return false; return false;
} }
_checked.n_allocated = nregs; _checked.n_allocated = nregs;
_checked.frequency = frequency;
_checked.counter = 0;
return true; return true;
} }