From b69f08c03e630c0af61651ce03b9be54461f965e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 12 Oct 2013 18:24:00 +1100 Subject: [PATCH] Copter: reduce timer speed to 500 on APM2 this reduces the cost of timer interrupts --- ArduCopter/system.pde | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 67eb730a56..214fef06e9 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -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) //