From 6f236f0c3b3fff4de2ad9090a06e6b758b5e00b7 Mon Sep 17 00:00:00 2001 From: rmackay9 Date: Tue, 28 Aug 2012 17:29:48 +0900 Subject: [PATCH] ArduCopter: increase SPI bus speed to 2Mhz after IMU initialisation has completed (MPU6000 accepts maximum of 1Mhz for some registers but up to 20Mhz for main sensor and interrupt registers) --- ArduCopter/system.pde | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index b11ef389d1..6a4a5ad178 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -309,6 +309,9 @@ static void init_ardupilot() startup_ground(); + // now that initialisation of IMU has occurred increase SPI to 2MHz + SPI.setClockDivider(SPI_CLOCK_DIV8); // 2MHZ SPI rate + #if LOGGING_ENABLED == ENABLED Log_Write_Startup(); Log_Write_Data(10, (float)g.pi_stabilize_roll.kP());