mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_Baro_MS5611: init must also perform SPI.begin
This commit is contained in:
parent
a75257f102
commit
45cbb24ba5
@ -115,8 +115,15 @@ uint8_t AP_Baro_MS5611::MS5611_Ready()
|
|||||||
// SPI should be initialized externally
|
// SPI should be initialized externally
|
||||||
void AP_Baro_MS5611::init()
|
void AP_Baro_MS5611::init()
|
||||||
{
|
{
|
||||||
|
SPI.begin();
|
||||||
|
#if F_CPU == 16000000
|
||||||
|
SPI.setClockDivider(SPI_CLOCK_DIV16);
|
||||||
|
#else
|
||||||
|
# error MS5611 requires SPI at 1MHZ! Need appropriate SPI clock divider
|
||||||
|
#endif
|
||||||
pinMode(MS5611_CS, OUTPUT); // Chip select Pin
|
pinMode(MS5611_CS, OUTPUT); // Chip select Pin
|
||||||
|
digitalWrite(MS5611_CS, HIGH);
|
||||||
|
delay(1);
|
||||||
|
|
||||||
MS5611_SPI_write(CMD_MS5611_RESET);
|
MS5611_SPI_write(CMD_MS5611_RESET);
|
||||||
delay(4);
|
delay(4);
|
||||||
|
Loading…
Reference in New Issue
Block a user