mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-27 19:18:28 -04:00
AP_HAL_AVR: I2CDriver initialize in HAL init
* Makes more sense to have everything set to go by the time we're in setup.
This commit is contained in:
parent
ce8dc5fd5c
commit
11cfde1e46
@ -8,7 +8,6 @@ void HAL_AVR::init(void* opts) const {
|
|||||||
|
|
||||||
/* uart0 is the serial port used for the console, so lets make sure
|
/* uart0 is the serial port used for the console, so lets make sure
|
||||||
* it is initialized at boot */
|
* it is initialized at boot */
|
||||||
// XXX maybe this should be 57600?
|
|
||||||
uart0->begin(115200);
|
uart0->begin(115200);
|
||||||
console->init((void*)uart0);
|
console->init((void*)uart0);
|
||||||
/* The AVR RCInput drivers take an AP_HAL_AVR::ISRRegistry*
|
/* 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);
|
rcin->init((void*)&isr_registry);
|
||||||
rcout->init(NULL);
|
rcout->init(NULL);
|
||||||
spi->init(NULL);
|
spi->init(NULL);
|
||||||
|
i2c->begin();
|
||||||
|
i2c->setTimeout(100);
|
||||||
analogin->init(NULL);
|
analogin->init(NULL);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -106,6 +106,13 @@ uint8_t AVRI2CDriver::writeRegisters(uint8_t addr, uint8_t reg,
|
|||||||
return stat;
|
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 AVRI2CDriver::readRegisters(uint8_t addr, uint8_t reg,
|
||||||
uint8_t len, uint8_t* data){
|
uint8_t len, uint8_t* data){
|
||||||
uint8_t stat;
|
uint8_t stat;
|
||||||
@ -137,6 +144,10 @@ uint8_t AVRI2CDriver::readRegisters(uint8_t addr, uint8_t reg,
|
|||||||
return stat;
|
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() {
|
uint8_t AVRI2CDriver::_start() {
|
||||||
TWCR = _BV(TWINT) | _BV(TWSTA) | _BV(TWEN);
|
TWCR = _BV(TWINT) | _BV(TWSTA) | _BV(TWEN);
|
||||||
uint8_t stat = _waitInterrupt();
|
uint8_t stat = _waitInterrupt();
|
||||||
|
@ -16,18 +16,10 @@ public:
|
|||||||
void setTimeout(uint16_t ms) { _timeoutDelay = ms; }
|
void setTimeout(uint16_t ms) { _timeoutDelay = ms; }
|
||||||
void setHighSpeed(bool active);
|
void setHighSpeed(bool active);
|
||||||
|
|
||||||
uint8_t writeRegister(uint8_t addr, uint8_t reg, uint8_t val) {
|
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 writeRegisters(uint8_t addr, uint8_t reg,
|
uint8_t writeRegisters(uint8_t addr, uint8_t reg,
|
||||||
uint8_t len, uint8_t* data);
|
uint8_t len, uint8_t* data);
|
||||||
uint8_t readRegister(uint8_t addr, uint8_t reg, uint8_t* data) {
|
uint8_t readRegister(uint8_t addr, uint8_t reg, uint8_t* data);
|
||||||
return readRegisters(addr, reg, 1, data);
|
|
||||||
}
|
|
||||||
uint8_t readRegisters(uint8_t addr, uint8_t reg,
|
uint8_t readRegisters(uint8_t addr, uint8_t reg,
|
||||||
uint8_t len, uint8_t* data);
|
uint8_t len, uint8_t* data);
|
||||||
uint8_t lockup_count() { return _lockup_count; }
|
uint8_t lockup_count() { return _lockup_count; }
|
||||||
|
@ -17,9 +17,6 @@ void setup() {
|
|||||||
hal.uart0->printf_P(PSTR("Initializing HMC5883L at address %x\r\n"),
|
hal.uart0->printf_P(PSTR("Initializing HMC5883L at address %x\r\n"),
|
||||||
HMC5883L);
|
HMC5883L);
|
||||||
|
|
||||||
// configure device for continuous mode
|
|
||||||
hal.i2c->begin();
|
|
||||||
hal.i2c->setTimeout(100);
|
|
||||||
|
|
||||||
uint8_t stat = hal.i2c->writeRegister(HMC5883L,0x02,0x00);
|
uint8_t stat = hal.i2c->writeRegister(HMC5883L,0x02,0x00);
|
||||||
if (stat == 0) {
|
if (stat == 0) {
|
||||||
|
Loading…
Reference in New Issue
Block a user