mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
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)
This commit is contained in:
parent
67252c8a9b
commit
6f236f0c3b
@ -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());
|
||||
|
Loading…
Reference in New Issue
Block a user