diff --git a/libraries/AP_HAL_AVR/HAL_AVR.cpp b/libraries/AP_HAL_AVR/HAL_AVR.cpp index 0e965ff543..70565facd6 100644 --- a/libraries/AP_HAL_AVR/HAL_AVR.cpp +++ b/libraries/AP_HAL_AVR/HAL_AVR.cpp @@ -8,7 +8,6 @@ void HAL_AVR::init(void* opts) const { /* uart0 is the serial port used for the console, so lets make sure * it is initialized at boot */ - // XXX maybe this should be 57600? uart0->begin(115200); console->init((void*)uart0); /* The AVR RCInput drivers take an AP_HAL_AVR::ISRRegistry* @@ -16,6 +15,8 @@ void HAL_AVR::init(void* opts) const { rcin->init((void*)&isr_registry); rcout->init(NULL); spi->init(NULL); + i2c->begin(); + i2c->setTimeout(100); analogin->init(NULL); }; diff --git a/libraries/AP_HAL_AVR/I2CDriver.cpp b/libraries/AP_HAL_AVR/I2CDriver.cpp index d22463a18b..c0d9635028 100644 --- a/libraries/AP_HAL_AVR/I2CDriver.cpp +++ b/libraries/AP_HAL_AVR/I2CDriver.cpp @@ -106,6 +106,13 @@ uint8_t AVRI2CDriver::writeRegisters(uint8_t addr, uint8_t reg, return stat; } +uint8_t AVRI2CDriver::writeRegister(uint8_t addr, uint8_t reg, uint8_t val) { + /* Sometimes avr-gcc fails at dereferencing a uint8_t arg. */ + uint8_t data[1]; + data[0] = val; + return writeRegisters(addr, reg, 1, data); +} + uint8_t AVRI2CDriver::readRegisters(uint8_t addr, uint8_t reg, uint8_t len, uint8_t* data){ uint8_t stat; @@ -137,6 +144,10 @@ uint8_t AVRI2CDriver::readRegisters(uint8_t addr, uint8_t reg, return stat; } +uint8_t AVRI2CDriver::readRegister(uint8_t addr, uint8_t reg, uint8_t* data) { + return readRegisters(addr, reg, 1, data); +} + uint8_t AVRI2CDriver::_start() { TWCR = _BV(TWINT) | _BV(TWSTA) | _BV(TWEN); uint8_t stat = _waitInterrupt(); diff --git a/libraries/AP_HAL_AVR/I2CDriver.h b/libraries/AP_HAL_AVR/I2CDriver.h index 2239017b42..a3be0b2eef 100644 --- a/libraries/AP_HAL_AVR/I2CDriver.h +++ b/libraries/AP_HAL_AVR/I2CDriver.h @@ -16,18 +16,10 @@ public: void setTimeout(uint16_t ms) { _timeoutDelay = ms; } void setHighSpeed(bool active); - uint8_t writeRegister(uint8_t addr, uint8_t reg, uint8_t val) { - /* Sometimes avr-gcc fails at dereferencing a uint8_t arg. */ - uint8_t data[1]; - data[0] = val; - return writeRegisters(addr, reg, 1, data); - } - + uint8_t writeRegister(uint8_t addr, uint8_t reg, uint8_t val); uint8_t writeRegisters(uint8_t addr, uint8_t reg, uint8_t len, uint8_t* data); - uint8_t readRegister(uint8_t addr, uint8_t reg, uint8_t* data) { - return readRegisters(addr, reg, 1, data); - } + uint8_t readRegister(uint8_t addr, uint8_t reg, uint8_t* data); uint8_t readRegisters(uint8_t addr, uint8_t reg, uint8_t len, uint8_t* data); uint8_t lockup_count() { return _lockup_count; } diff --git a/libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/I2CDriver_HMC5883L.pde b/libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/I2CDriver_HMC5883L.pde index efbffddad5..027aafe352 100644 --- a/libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/I2CDriver_HMC5883L.pde +++ b/libraries/AP_HAL_AVR/examples/I2CDriver_HMC5883L/I2CDriver_HMC5883L.pde @@ -17,9 +17,6 @@ void setup() { hal.uart0->printf_P(PSTR("Initializing HMC5883L at address %x\r\n"), HMC5883L); - // configure device for continuous mode - hal.i2c->begin(); - hal.i2c->setTimeout(100); uint8_t stat = hal.i2c->writeRegister(HMC5883L,0x02,0x00); if (stat == 0) {