APMrover2: use ARRAY_SIZE macro

This commit is contained in:
Lucas De Marchi 2015-07-06 12:30:40 -03:00 committed by Andrew Tridgell
parent dee1bf3da3
commit 8f74d7d982
2 changed files with 2 additions and 2 deletions

View File

@ -100,7 +100,7 @@ void Rover::setup()
init_ardupilot();
// initialise the main loop scheduler
scheduler.init(&scheduler_tasks[0], sizeof(scheduler_tasks)/sizeof(scheduler_tasks[0]));
scheduler.init(&scheduler_tasks[0], ARRAY_SIZE(scheduler_tasks));
}
/*

View File

@ -394,7 +394,7 @@ const LogStructure Rover::log_structure[] PROGMEM = {
void Rover::log_init(void)
{
DataFlash.Init(log_structure, sizeof(log_structure)/sizeof(log_structure[0]));
DataFlash.Init(log_structure, ARRAY_SIZE(log_structure));
if (!DataFlash.CardInserted()) {
gcs_send_text_P(SEVERITY_LOW, PSTR("No dataflash card inserted"));
g.log_bitmask.set(0);