Skip to content
Snippets Groups Projects
Commit eb1b2c42 authored by Randy Mackay's avatar Randy Mackay
Browse files

OptFlow: correct SPI mode and baud rates

parent d6549319
No related branches found
No related tags found
No related merge requests found
...@@ -42,7 +42,7 @@ void APM2SPIDeviceManager::init(void* machtnichts) { ...@@ -42,7 +42,7 @@ void APM2SPIDeviceManager::init(void* machtnichts) {
AVRDigitalSource* optflow_cs = new AVRDigitalSource(_BV(3), PF); AVRDigitalSource* optflow_cs = new AVRDigitalSource(_BV(3), PF);
/* optflow: divide clock by 8 to 2Mhz /* optflow: divide clock by 8 to 2Mhz
* spcr gets bit SPR0, spsr gets bit SPI2X */ * 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(); _optflow_spi0->init();
/* Dataflash CS is on Arduino pin 28, PORTA6 */ /* Dataflash CS is on Arduino pin 28, PORTA6 */
...@@ -53,8 +53,10 @@ void APM2SPIDeviceManager::init(void* machtnichts) { ...@@ -53,8 +53,10 @@ void APM2SPIDeviceManager::init(void* machtnichts) {
_dataflash = new AVRSPI3DeviceDriver(df_cs, 0, 0); _dataflash = new AVRSPI3DeviceDriver(df_cs, 0, 0);
_dataflash->init(); _dataflash->init();
/* XXX need correct mode and baud */ /* optflow uses mode 3 and a clock of 2mhz
_optflow_spi3 = new AVRSPI3DeviceDriver(optflow_cs, 0, 0); * ucsr3c = _BV(UCPHA3N)|_BV(UCPOL3) = 3
* ubrr3 = 3 */
_optflow_spi3 = new AVRSPI3DeviceDriver(optflow_cs, 3, 3);
_optflow_spi3->init(); _optflow_spi3->init();
} }
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment