mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
HAL: MPU6k and Baro SPI to 8Mhz
This commit is contained in:
parent
08a6503364
commit
f5488bc447
@ -29,13 +29,13 @@ void APM2SPIDeviceManager::init(void* machtnichts) {
|
||||
AVRDigitalSource* mpu6k_cs = new AVRDigitalSource(_BV(0), PB);
|
||||
/* mpu6k: run clock at 8MHz in high speed mode and 512kHz for low
|
||||
* speed */
|
||||
_mpu6k = new AVRSPI0DeviceDriver(mpu6k_cs, SPI0_SPCR_500kHz, SPI0_SPCR_500kHz, SPI0_SPSR_500kHz);
|
||||
_mpu6k = new AVRSPI0DeviceDriver(mpu6k_cs, SPI0_SPCR_500kHz, SPI0_SPCR_8MHz, SPI0_SPSR_8MHz);
|
||||
_mpu6k->init();
|
||||
|
||||
/* ms5611 cs is on Arduino pin 40, PORTG1 */
|
||||
AVRDigitalSource* ms5611_cs = new AVRDigitalSource(_BV(1), PG);
|
||||
/* ms5611: run clock at 8MHz */
|
||||
_ms5611 = new AVRSPI0DeviceDriver(ms5611_cs, SPI0_SPCR_500kHz, SPI0_SPCR_500kHz, SPI0_SPSR_500kHz);
|
||||
_ms5611 = new AVRSPI0DeviceDriver(ms5611_cs, SPI0_SPCR_500kHz, SPI0_SPCR_8MHz, SPI0_SPSR_8MHz);
|
||||
_ms5611->init();
|
||||
|
||||
/* optflow cs is on Arduino pin A3, PORTF3 */
|
||||
|
Loading…
Reference in New Issue
Block a user