Copter: reduce timer speed to 500 on APM2

this reduces the cost of timer interrupts
This commit is contained in:
Andrew Tridgell 2013-10-12 18:24:00 +11:00 committed by Randy Mackay
parent a5788dde8f
commit b69f08c03e
1 changed files with 8 additions and 0 deletions

View File

@ -107,6 +107,14 @@ static void init_ardupilot()
"\n\nFree RAM: %u\n"),
memcheck_available_memory());
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
/*
run the timer a bit slower on APM2 to reduce the interrupt load
on the CPU
*/
hal.scheduler->set_timer_speed(500);
#endif
//
// Report firmware version code expect on console (check of actual EEPROM format version is done in load_parameters function)
//