mirror of https://github.com/ArduPilot/ardupilot
HAL_Empty: make I2C ops fail
This commit is contained in:
parent
9386295428
commit
7ceb14bec0
|
@ -10,12 +10,12 @@ void EmptyI2CDriver::setTimeout(uint16_t ms) {}
|
|||
void EmptyI2CDriver::setHighSpeed(bool active) {}
|
||||
|
||||
uint8_t EmptyI2CDriver::write(uint8_t addr, uint8_t len, uint8_t* data)
|
||||
{return 0;}
|
||||
{return 1;}
|
||||
uint8_t EmptyI2CDriver::writeRegister(uint8_t addr, uint8_t reg, uint8_t val)
|
||||
{return 0;}
|
||||
{return 1;}
|
||||
uint8_t EmptyI2CDriver::writeRegisters(uint8_t addr, uint8_t reg,
|
||||
uint8_t len, uint8_t* data)
|
||||
{return 0;}
|
||||
{return 1;}
|
||||
|
||||
uint8_t EmptyI2CDriver::read(uint8_t addr, uint8_t len, uint8_t* data)
|
||||
{
|
||||
|
@ -25,14 +25,14 @@ uint8_t EmptyI2CDriver::read(uint8_t addr, uint8_t len, uint8_t* data)
|
|||
uint8_t EmptyI2CDriver::readRegister(uint8_t addr, uint8_t reg, uint8_t* data)
|
||||
{
|
||||
*data = 0;
|
||||
return 0;
|
||||
return 1;
|
||||
}
|
||||
|
||||
uint8_t EmptyI2CDriver::readRegisters(uint8_t addr, uint8_t reg,
|
||||
uint8_t len, uint8_t* data)
|
||||
{
|
||||
memset(data, 0, len);
|
||||
return 0;
|
||||
return 1;
|
||||
}
|
||||
|
||||
uint8_t EmptyI2CDriver::lockup_count() {return 0;}
|
||||
|
|
Loading…
Reference in New Issue