diff --git a/libraries/AP_HAL_AVR/SPIDeviceManager_APM2.cpp b/libraries/AP_HAL_AVR/SPIDeviceManager_APM2.cpp index 5f59fe6d75..397bf3eff2 100644 --- a/libraries/AP_HAL_AVR/SPIDeviceManager_APM2.cpp +++ b/libraries/AP_HAL_AVR/SPIDeviceManager_APM2.cpp @@ -42,7 +42,7 @@ void APM2SPIDeviceManager::init(void* machtnichts) { AVRDigitalSource* optflow_cs = new AVRDigitalSource(_BV(3), PF); /* optflow: divide clock by 8 to 2Mhz * spcr gets bit SPR0, spsr gets bit SPI2X */ - _optflow_spi0 = new AVRSPI0DeviceDriver(optflow_cs, _BV(SPR0), _BV(SPR0), _BV(SPI2X)); + _optflow_spi0 = new AVRSPI0DeviceDriver(optflow_cs, _BV(SPR0)|_BV(CPOL)|_BV(CPHA), _BV(SPR0)|_BV(CPOL)|_BV(CPHA), _BV(SPI2X)); _optflow_spi0->init(); /* Dataflash CS is on Arduino pin 28, PORTA6 */ @@ -53,8 +53,10 @@ void APM2SPIDeviceManager::init(void* machtnichts) { _dataflash = new AVRSPI3DeviceDriver(df_cs, 0, 0); _dataflash->init(); - /* XXX need correct mode and baud */ - _optflow_spi3 = new AVRSPI3DeviceDriver(optflow_cs, 0, 0); + /* optflow uses mode 3 and a clock of 2mhz + * ucsr3c = _BV(UCPHA3N)|_BV(UCPOL3) = 3 + * ubrr3 = 3 */ + _optflow_spi3 = new AVRSPI3DeviceDriver(optflow_cs, 3, 3); _optflow_spi3->init(); }