mirror of https://github.com/ArduPilot/ardupilot
AP_Compass: use ARRAY_SIZE macro
This commit is contained in:
parent
3136b8916c
commit
fd5d25b1d5
|
@ -59,7 +59,7 @@ AP_Compass_HIL::init(void)
|
|||
|
||||
void AP_Compass_HIL::read()
|
||||
{
|
||||
for (uint8_t i=0; i<sizeof(_compass_instance)/sizeof(_compass_instance[0]); i++) {
|
||||
for (uint8_t i=0; i < ARRAY_SIZE(_compass_instance); i++) {
|
||||
if (_compass._hil.healthy[i]) {
|
||||
publish_field(_compass._hil.field[_compass_instance[i]], _compass_instance[i]);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue