mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: fixed frequency init for register checking
This commit is contained in:
parent
dc85ffa834
commit
fdc94ec28a
|
@ -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;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue