AP_HAL_Empty: remove I2CDriver

I2CDevice now serves for the same purpose.
This commit is contained in:
Lucas De Marchi 2016-07-22 15:02:19 -03:00
parent b21ad36676
commit 3eb0a48d59
5 changed files with 0 additions and 104 deletions

View File

@ -7,7 +7,6 @@ namespace Empty {
class GPIO;
class I2CDevice;
class I2CDeviceManager;
class I2CDriver;
class OpticalFlow;
class PrivateMember;
class RCInput;

View File

@ -7,7 +7,6 @@
#include "AnalogIn.h"
#include "GPIO.h"
#include "I2CDevice.h"
#include "I2CDriver.h"
#include "OpticalFlow.h"
#include "PrivateMember.h"
#include "RCInput.h"

View File

@ -12,8 +12,6 @@ using namespace Empty;
static UARTDriver uartADriver;
static UARTDriver uartBDriver;
static UARTDriver uartCDriver;
static Semaphore i2cSemaphore;
static I2CDriver i2cDriver(&i2cSemaphore);
static SPIDeviceManager spiDeviceManager;
static AnalogIn analogIn;
static Storage storageDriver;
@ -32,9 +30,6 @@ HAL_Empty::HAL_Empty() :
NULL, /* no uartD */
NULL, /* no uartE */
NULL, /* no uartF */
&i2cDriver,
NULL, /* only one i2c */
NULL, /* only one i2c */
&spiDeviceManager,
&analogIn,
&storageDriver,

View File

@ -1,48 +0,0 @@
#include <AP_HAL/AP_HAL.h>
#include "I2CDriver.h"
using namespace Empty;
void I2CDriver::begin() {}
void I2CDriver::end() {}
void I2CDriver::setTimeout(uint16_t ms) {}
void I2CDriver::setHighSpeed(bool active) {}
uint8_t I2CDriver::write(uint8_t addr, uint8_t len, uint8_t* data)
{return 1;}
uint8_t I2CDriver::writeRegister(uint8_t addr, uint8_t reg, uint8_t val)
{return 1;}
uint8_t I2CDriver::writeRegisters(uint8_t addr, uint8_t reg,
uint8_t len, uint8_t* data)
{return 1;}
uint8_t I2CDriver::read(uint8_t addr, uint8_t len, uint8_t* data)
{
memset(data, 0, len);
return 0;
}
uint8_t I2CDriver::readRegister(uint8_t addr, uint8_t reg, uint8_t* data)
{
*data = 0;
return 1;
}
uint8_t I2CDriver::readRegisters(uint8_t addr, uint8_t reg,
uint8_t len, uint8_t* data)
{
memset(data, 0, len);
return 1;
}
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
uint8_t I2CDriver::readRegistersMultiple(uint8_t addr, uint8_t reg,
uint8_t len, uint8_t count,
uint8_t* data)
{
memset(data, 0, len*count);
return 1;
}
#endif
uint8_t I2CDriver::lockup_count() {return 0;}

View File

@ -1,49 +0,0 @@
#pragma once
#include "AP_HAL_Empty.h"
class Empty::I2CDriver : public AP_HAL::I2CDriver {
public:
I2CDriver(AP_HAL::Semaphore* semaphore) : _semaphore(semaphore) {}
void begin() override;
void end() override;
void setTimeout(uint16_t ms) override;
void setHighSpeed(bool active) override;
/* write: for i2c devices which do not obey register conventions */
uint8_t write(uint8_t addr, uint8_t len, uint8_t* data) override;
/* writeRegister: write a single 8-bit value to a register */
uint8_t writeRegister(uint8_t addr, uint8_t reg, uint8_t val) override;
/* writeRegisters: write bytes to contiguous registers */
uint8_t writeRegisters(uint8_t addr, uint8_t reg,
uint8_t len, uint8_t* data) override;
/* read: for i2c devices which do not obey register conventions */
uint8_t read(uint8_t addr, uint8_t len, uint8_t* data) override;
/* readRegister: read from a device register - writes the register,
* then reads back an 8-bit value. */
uint8_t readRegister(uint8_t addr, uint8_t reg, uint8_t* data) override;
/* readRegister: read contiguous device registers - writes the first
* register, then reads back multiple bytes */
uint8_t readRegisters(uint8_t addr, uint8_t reg,
uint8_t len, uint8_t* data) override;
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
/* readRegistersMultiple: read contiguous device registers.
Equivalent to count calls to readRegisters() */
virtual uint8_t readRegistersMultiple(uint8_t addr, uint8_t reg,
uint8_t len, uint8_t count,
uint8_t* data) override;
#endif
uint8_t lockup_count();
AP_HAL::Semaphore* get_semaphore() { return _semaphore; }
private:
AP_HAL::Semaphore* _semaphore;
};