mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
I2c: default to 5ms timeout, and faster bus speed
we will slow down the speed when we get a failure
This commit is contained in:
parent
60185509f4
commit
cdd5589498
@ -108,7 +108,9 @@ static void init_ardupilot()
|
||||
//
|
||||
#ifndef DESKTOP_BUILD
|
||||
I2c.begin();
|
||||
I2c.timeOut(20);
|
||||
I2c.timeOut(5);
|
||||
// initially set a fast I2c speed, and drop it on first failures
|
||||
I2c.setSpeed(true);
|
||||
#endif
|
||||
SPI.begin();
|
||||
SPI.setClockDivider(SPI_CLOCK_DIV16); // 1MHZ SPI rate
|
||||
|
@ -108,7 +108,9 @@ static void init_ardupilot()
|
||||
//
|
||||
#ifndef DESKTOP_BUILD
|
||||
I2c.begin();
|
||||
I2c.timeOut(20);
|
||||
I2c.timeOut(5);
|
||||
// initially set a fast I2c speed, and drop it on first failures
|
||||
I2c.setSpeed(true);
|
||||
#endif
|
||||
SPI.begin();
|
||||
SPI.setClockDivider(SPI_CLOCK_DIV16); // 1MHZ SPI rate
|
||||
|
Loading…
Reference in New Issue
Block a user