2018-01-05 02:19:51 -04:00
|
|
|
/*
|
|
|
|
* This file is free software: you can redistribute it and/or modify it
|
|
|
|
* under the terms of the GNU General Public License as published by the
|
|
|
|
* Free Software Foundation, either version 3 of the License, or
|
|
|
|
* (at your option) any later version.
|
|
|
|
*
|
|
|
|
* This file is distributed in the hope that it will be useful, but
|
|
|
|
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
|
|
|
* See the GNU General Public License for more details.
|
|
|
|
*
|
|
|
|
* You should have received a copy of the GNU General Public License along
|
|
|
|
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
#include "I2CDevice.h"
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include "Util.h"
|
|
|
|
#include "Scheduler.h"
|
|
|
|
|
|
|
|
#include "ch.h"
|
|
|
|
#include "hal.h"
|
|
|
|
|
2018-03-01 20:46:30 -04:00
|
|
|
#if HAL_USE_I2C == TRUE
|
|
|
|
|
2018-01-11 19:20:49 -04:00
|
|
|
static const struct I2CInfo {
|
|
|
|
struct I2CDriver *i2c;
|
|
|
|
uint8_t dma_channel_rx;
|
|
|
|
uint8_t dma_channel_tx;
|
|
|
|
} I2CD[] = { HAL_I2C_DEVICE_LIST };
|
2018-01-05 02:19:51 -04:00
|
|
|
|
|
|
|
using namespace ChibiOS;
|
2018-01-09 17:18:28 -04:00
|
|
|
extern const AP_HAL::HAL& hal;
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-01-11 21:49:33 -04:00
|
|
|
I2CBus I2CDeviceManager::businfo[ARRAY_SIZE_SIMPLE(I2CD)];
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-01-19 18:01:06 -04:00
|
|
|
#ifndef HAL_I2C_BUS_BASE
|
|
|
|
#define HAL_I2C_BUS_BASE 0
|
|
|
|
#endif
|
|
|
|
|
2018-01-19 18:04:35 -04:00
|
|
|
// default to 100kHz clock for maximum reliability. This can be
|
|
|
|
// changed in hwdef.dat
|
|
|
|
#ifndef HAL_I2C_MAX_CLOCK
|
|
|
|
#define HAL_I2C_MAX_CLOCK 100000
|
|
|
|
#endif
|
|
|
|
|
2018-01-10 00:26:05 -04:00
|
|
|
// get a handle for DMA sharing DMA channels with other subsystems
|
|
|
|
void I2CBus::dma_init(void)
|
|
|
|
{
|
2018-01-11 19:20:49 -04:00
|
|
|
dma_handle = new Shared_DMA(I2CD[busnum].dma_channel_tx, I2CD[busnum].dma_channel_rx,
|
2018-03-14 03:06:30 -03:00
|
|
|
FUNCTOR_BIND_MEMBER(&I2CBus::dma_allocate, void, Shared_DMA *),
|
|
|
|
FUNCTOR_BIND_MEMBER(&I2CBus::dma_deallocate, void, Shared_DMA *));
|
2018-01-10 00:26:05 -04:00
|
|
|
}
|
|
|
|
|
2018-02-05 15:40:05 -04:00
|
|
|
// Clear Bus to avoid bus lockup
|
|
|
|
void I2CBus::clear_all()
|
|
|
|
{
|
|
|
|
#if defined(HAL_GPIO_PIN_I2C1_SCL) && defined(HAL_I2C1_SCL_AF)
|
|
|
|
clear_bus(HAL_GPIO_PIN_I2C1_SCL, HAL_I2C1_SCL_AF);
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#if defined(HAL_GPIO_PIN_I2C2_SCL) && defined(HAL_I2C2_SCL_AF)
|
2018-02-26 22:35:53 -04:00
|
|
|
clear_bus(HAL_GPIO_PIN_I2C2_SCL, HAL_I2C2_SCL_AF);
|
2018-02-05 15:40:05 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#if defined(HAL_GPIO_PIN_I2C3_SCL) && defined(HAL_I2C3_SCL_AF)
|
2018-02-26 22:35:53 -04:00
|
|
|
clear_bus(HAL_GPIO_PIN_I2C3_SCL, HAL_I2C3_SCL_AF);
|
2018-02-05 15:40:05 -04:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#if defined(HAL_GPIO_PIN_I2C4_SCL) && defined(HAL_I2C4_SCL_AF)
|
2018-02-26 22:35:53 -04:00
|
|
|
clear_bus(HAL_GPIO_PIN_I2C4_SCL, HAL_I2C4_SCL_AF);
|
2018-02-05 15:40:05 -04:00
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
|
|
|
//This code blocks!
|
|
|
|
void I2CBus::clear_bus(ioline_t scl_line, uint8_t scl_af)
|
|
|
|
{
|
|
|
|
//send dummy clock
|
|
|
|
palSetLineMode(scl_line, PAL_MODE_OUTPUT_PUSHPULL);
|
|
|
|
for(int i = 0; i < 20; i++) {
|
|
|
|
palToggleLine(scl_line);
|
|
|
|
hal.scheduler->delay_microseconds(200);
|
|
|
|
}
|
|
|
|
palSetLineMode(scl_line, PAL_MODE_ALTERNATE(scl_af) | PAL_STM32_OSPEED_MID2 | PAL_STM32_OTYPE_OPENDRAIN);
|
|
|
|
}
|
|
|
|
|
2018-01-10 00:26:05 -04:00
|
|
|
// setup I2C buses
|
|
|
|
I2CDeviceManager::I2CDeviceManager(void)
|
|
|
|
{
|
2018-01-11 21:49:33 -04:00
|
|
|
for (uint8_t i=0; i<ARRAY_SIZE_SIMPLE(I2CD); i++) {
|
2018-01-10 00:26:05 -04:00
|
|
|
businfo[i].busnum = i;
|
|
|
|
businfo[i].dma_init();
|
|
|
|
/*
|
|
|
|
setup default I2C config. As each device is opened we will
|
|
|
|
drop the speed to be the minimum speed requested
|
|
|
|
*/
|
|
|
|
businfo[i].i2ccfg.op_mode = OPMODE_I2C;
|
2018-01-19 18:04:35 -04:00
|
|
|
businfo[i].i2ccfg.clock_speed = HAL_I2C_MAX_CLOCK;
|
|
|
|
if (businfo[i].i2ccfg.clock_speed <= 100000) {
|
|
|
|
businfo[i].i2ccfg.duty_cycle = STD_DUTY_CYCLE;
|
|
|
|
} else {
|
|
|
|
businfo[i].i2ccfg.duty_cycle = FAST_DUTY_CYCLE_2;
|
|
|
|
}
|
2018-01-10 00:26:05 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
I2CDevice::I2CDevice(uint8_t busnum, uint8_t address, uint32_t bus_clock, bool use_smbus, uint32_t timeout_ms) :
|
2018-01-05 02:19:51 -04:00
|
|
|
_retries(2),
|
2018-01-10 00:26:05 -04:00
|
|
|
_address(address),
|
|
|
|
_use_smbus(use_smbus),
|
|
|
|
_timeout_ms(timeout_ms),
|
|
|
|
bus(I2CDeviceManager::businfo[busnum])
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-01-19 18:01:06 -04:00
|
|
|
set_device_bus(busnum+HAL_I2C_BUS_BASE);
|
2018-01-05 02:19:51 -04:00
|
|
|
set_device_address(address);
|
|
|
|
asprintf(&pname, "I2C:%u:%02x",
|
2018-01-10 00:26:05 -04:00
|
|
|
(unsigned)busnum, (unsigned)address);
|
|
|
|
if (bus_clock < bus.i2ccfg.clock_speed) {
|
|
|
|
bus.i2ccfg.clock_speed = bus_clock;
|
2018-02-07 18:35:16 -04:00
|
|
|
hal.console->printf("I2C%u clock %ukHz\n", busnum, unsigned(bus_clock/1000));
|
2018-01-10 00:26:05 -04:00
|
|
|
if (bus_clock <= 100000) {
|
|
|
|
bus.i2ccfg.duty_cycle = STD_DUTY_CYCLE;
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
I2CDevice::~I2CDevice()
|
|
|
|
{
|
|
|
|
printf("I2C device bus %u address 0x%02x closed\n",
|
2018-01-10 00:26:05 -04:00
|
|
|
(unsigned)bus.busnum, (unsigned)_address);
|
2018-01-05 02:19:51 -04:00
|
|
|
free(pname);
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
allocate DMA channel
|
|
|
|
*/
|
2018-03-14 03:06:30 -03:00
|
|
|
void I2CBus::dma_allocate(Shared_DMA *ctx)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-02-04 01:42:05 -04:00
|
|
|
if (!i2c_started) {
|
2018-02-05 17:14:55 -04:00
|
|
|
osalDbgAssert(I2CD[busnum].i2c->state == I2C_STOP, "i2cStart state");
|
2018-02-04 01:42:05 -04:00
|
|
|
i2cStart(I2CD[busnum].i2c, &i2ccfg);
|
2018-02-05 17:14:55 -04:00
|
|
|
osalDbgAssert(I2CD[busnum].i2c->state == I2C_READY, "i2cStart state");
|
2018-02-04 01:42:05 -04:00
|
|
|
i2c_started = true;
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
deallocate DMA channel
|
|
|
|
*/
|
2018-03-14 03:06:30 -03:00
|
|
|
void I2CBus::dma_deallocate(Shared_DMA *)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-02-04 01:42:05 -04:00
|
|
|
if (i2c_started) {
|
2018-02-05 17:14:55 -04:00
|
|
|
osalDbgAssert(I2CD[busnum].i2c->state == I2C_READY, "i2cStart state");
|
2018-02-04 01:42:05 -04:00
|
|
|
i2cStop(I2CD[busnum].i2c);
|
2018-02-05 17:14:55 -04:00
|
|
|
osalDbgAssert(I2CD[busnum].i2c->state == I2C_STOP, "i2cStart state");
|
2018-02-04 01:42:05 -04:00
|
|
|
i2c_started = false;
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len,
|
|
|
|
uint8_t *recv, uint32_t recv_len)
|
|
|
|
{
|
2018-02-06 02:48:10 -04:00
|
|
|
if (!bus.semaphore.check_owner()) {
|
2018-02-08 18:54:31 -04:00
|
|
|
hal.console->printf("I2C: not owner of 0x%x\n", (unsigned)get_bus_id());
|
2018-02-06 02:48:10 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2018-01-10 00:26:05 -04:00
|
|
|
bus.dma_handle->lock();
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2018-01-10 00:26:05 -04:00
|
|
|
if (_use_smbus) {
|
|
|
|
bus.i2ccfg.op_mode = OPMODE_SMBUS_HOST;
|
|
|
|
} else {
|
|
|
|
bus.i2ccfg.op_mode = OPMODE_I2C;
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2018-01-10 00:26:05 -04:00
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
if (_split_transfers) {
|
|
|
|
/*
|
|
|
|
splitting the transfer() into two pieces avoids a stop condition
|
|
|
|
with SCL low which is not supported on some devices (such as
|
|
|
|
LidarLite blue label)
|
|
|
|
*/
|
|
|
|
if (send && send_len) {
|
|
|
|
if (!_transfer(send, send_len, nullptr, 0)) {
|
2018-01-10 00:26:05 -04:00
|
|
|
bus.dma_handle->unlock();
|
2018-01-05 02:19:51 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
if (recv && recv_len) {
|
|
|
|
if (!_transfer(nullptr, 0, recv, recv_len)) {
|
2018-01-10 00:26:05 -04:00
|
|
|
bus.dma_handle->unlock();
|
2018-01-05 02:19:51 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
} else {
|
|
|
|
// combined transfer
|
|
|
|
if (!_transfer(send, send_len, recv, recv_len)) {
|
2018-01-10 00:26:05 -04:00
|
|
|
bus.dma_handle->unlock();
|
2018-01-05 02:19:51 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-01-10 00:26:05 -04:00
|
|
|
bus.dma_handle->unlock();
|
2018-01-05 02:19:51 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
|
|
|
|
uint8_t *recv, uint32_t recv_len)
|
|
|
|
{
|
2018-01-09 17:18:28 -04:00
|
|
|
uint8_t *recv_buf = recv;
|
|
|
|
const uint8_t *send_buf = send;
|
|
|
|
|
|
|
|
bus.bouncebuffer_setup(send_buf, send_len, recv_buf, recv_len);
|
|
|
|
|
2018-02-06 02:48:10 -04:00
|
|
|
i2cAcquireBus(I2CD[bus.busnum].i2c);
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
for(uint8_t i=0 ; i <= _retries; i++) {
|
2018-01-09 17:18:28 -04:00
|
|
|
int ret;
|
2018-01-05 02:19:51 -04:00
|
|
|
// calculate a timeout as twice the expected transfer time, and set as min of 4ms
|
2018-01-10 00:26:05 -04:00
|
|
|
uint32_t timeout_ms = 1+2*(((8*1000000UL/bus.i2ccfg.clock_speed)*MAX(send_len, recv_len))/1000);
|
|
|
|
timeout_ms = MAX(timeout_ms, _timeout_ms);
|
2018-02-05 17:14:55 -04:00
|
|
|
bus.i2c_active = true;
|
2018-02-06 02:48:10 -04:00
|
|
|
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_READY, "i2cStart state");
|
2018-01-05 02:19:51 -04:00
|
|
|
if(send_len == 0) {
|
2018-01-11 19:20:49 -04:00
|
|
|
ret = i2cMasterReceiveTimeout(I2CD[bus.busnum].i2c, _address, recv_buf, recv_len, MS2ST(timeout_ms));
|
2018-01-05 02:19:51 -04:00
|
|
|
} else {
|
2018-01-11 19:20:49 -04:00
|
|
|
ret = i2cMasterTransmitTimeout(I2CD[bus.busnum].i2c, _address, send_buf, send_len,
|
2018-01-09 17:18:28 -04:00
|
|
|
recv_buf, recv_len, MS2ST(timeout_ms));
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
2018-02-05 17:14:55 -04:00
|
|
|
bus.i2c_active = false;
|
2018-02-06 02:48:10 -04:00
|
|
|
if (ret != MSG_OK) {
|
2018-01-05 02:19:51 -04:00
|
|
|
//restart the bus
|
2018-02-06 02:48:10 -04:00
|
|
|
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_READY || I2CD[bus.busnum].i2c->state == I2C_LOCKED, "i2cStart state");
|
|
|
|
i2cStop(I2CD[bus.busnum].i2c);
|
2018-02-05 17:14:55 -04:00
|
|
|
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_STOP, "i2cStart state");
|
2018-01-11 19:20:49 -04:00
|
|
|
i2cStart(I2CD[bus.busnum].i2c, &bus.i2ccfg);
|
2018-02-05 17:14:55 -04:00
|
|
|
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_READY, "i2cStart state");
|
2018-01-05 02:19:51 -04:00
|
|
|
} else {
|
2018-02-06 02:48:10 -04:00
|
|
|
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_READY, "i2cStart state");
|
2018-01-09 17:18:28 -04:00
|
|
|
if (recv_buf != recv) {
|
|
|
|
memcpy(recv, recv_buf, recv_len);
|
|
|
|
}
|
2018-02-06 02:48:10 -04:00
|
|
|
i2cReleaseBus(I2CD[bus.busnum].i2c);
|
2018-01-05 02:19:51 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
}
|
2018-02-06 02:48:10 -04:00
|
|
|
i2cReleaseBus(I2CD[bus.busnum].i2c);
|
2018-01-05 02:19:51 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool I2CDevice::read_registers_multiple(uint8_t first_reg, uint8_t *recv,
|
|
|
|
uint32_t recv_len, uint8_t times)
|
|
|
|
{
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
register a periodic callback
|
|
|
|
*/
|
|
|
|
AP_HAL::Device::PeriodicHandle I2CDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
|
|
|
|
{
|
2018-01-10 00:26:05 -04:00
|
|
|
return bus.register_periodic_callback(period_usec, cb, this);
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
adjust a periodic callback
|
|
|
|
*/
|
|
|
|
bool I2CDevice::adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec)
|
|
|
|
{
|
2018-01-10 00:26:05 -04:00
|
|
|
return bus.adjust_timer(h, period_usec);
|
2018-01-05 02:19:51 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice>
|
2018-01-10 00:26:05 -04:00
|
|
|
I2CDeviceManager::get_device(uint8_t bus, uint8_t address,
|
|
|
|
uint32_t bus_clock,
|
|
|
|
bool use_smbus,
|
|
|
|
uint32_t timeout_ms)
|
2018-01-05 02:19:51 -04:00
|
|
|
{
|
2018-01-19 18:01:06 -04:00
|
|
|
bus -= HAL_I2C_BUS_BASE;
|
2018-01-11 21:49:33 -04:00
|
|
|
if (bus >= ARRAY_SIZE_SIMPLE(I2CD)) {
|
2018-01-08 00:33:08 -04:00
|
|
|
return AP_HAL::OwnPtr<AP_HAL::I2CDevice>(nullptr);
|
|
|
|
}
|
2018-01-10 00:26:05 -04:00
|
|
|
auto dev = AP_HAL::OwnPtr<AP_HAL::I2CDevice>(new I2CDevice(bus, address, bus_clock, use_smbus, timeout_ms));
|
2018-01-05 02:19:51 -04:00
|
|
|
return dev;
|
|
|
|
}
|
2018-03-01 20:46:30 -04:00
|
|
|
|
|
|
|
#endif // HAL_USE_I2C
|