52 unsigned int I2C::_bus_clocks[BOARD_NUMBER_I2C_BUSES] = BOARD_I2C_BUS_CLOCK_INIT;
54 I2C::I2C(
const char *
name,
const char *devname,
const int bus,
const uint16_t address,
const uint32_t frequency) :
58 DEVICE_DEBUG(
"I2C::I2C name = %s devname = %s", name, devname);
60 _device_id.devid_s.bus_type = DeviceBusType_I2C;
61 _device_id.devid_s.bus = bus;
62 _device_id.devid_s.address = address;
64 _device_id.devid_s.devtype = 0;
70 px4_i2cbus_uninitialize(
_dev);
100 _dev = px4_i2cbus_initialize(get_device_bus());
102 if (
_dev ==
nullptr) {
110 bus_index = get_device_bus() - 1;
115 (void)px4_i2cbus_uninitialize(
_dev);
117 DEVICE_LOG(
"FAIL: too slow for bus #%u: %u KHz, device max: %u KHz)",
156 DEVICE_LOG(
"on I2C bus %d at 0x%02x (bus: %u KHz, max: %u KHz)",
161 if ((ret !=
OK) && (
_dev !=
nullptr)) {
162 px4_i2cbus_uninitialize(
_dev);
170 I2C::transfer(
const uint8_t *
send,
const unsigned send_len, uint8_t *recv,
const unsigned recv_len)
172 px4_i2c_msg_t msgv[2];
175 unsigned retry_count = 0;
177 if (
_dev ==
nullptr) {
178 PX4_ERR(
"I2C device not opened");
183 DEVICE_DEBUG(
"transfer out %p/%u in %p/%u", send, send_len, recv, recv_len);
187 msgv[msgs].frequency =
_bus_clocks[get_device_bus() - 1];
188 msgv[msgs].addr = get_device_address();
189 msgv[msgs].flags = 0;
190 msgv[msgs].buffer =
const_cast<uint8_t *
>(
send);
191 msgv[msgs].length = send_len;
196 msgv[msgs].frequency =
_bus_clocks[get_device_bus() - 1];
197 msgv[msgs].addr = get_device_address();
198 msgv[msgs].flags = I2C_M_READ;
199 msgv[msgs].buffer = recv;
200 msgv[msgs].length = recv_len;
208 ret = I2C_TRANSFER(
_dev, &msgv[0], msgs);
216 if ((retry_count >= 1) || (retry_count >=
_retries)) {
int transfer(const uint8_t *send, const unsigned send_len, uint8_t *recv, const unsigned recv_len)
Perform an I2C transaction to the device.
static unsigned int _bus_clocks[BOARD_NUMBER_I2C_BUSES]
Namespace encapsulating all device framework classes, functions and data.
virtual int probe()
Check for the presence of the device on the bus.
void init()
Activates/configures the hardware registers.
#define DEVICE_LOG(FMT,...)
virtual int init() override
uint8_t _retries
The number of times a read or write operation will be retried on error.
static int set_bus_clock(unsigned bus, unsigned clock_hz)
#define DEVICE_DEBUG(FMT,...)