mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 22:18:29 -04:00
HAL_ChibiOS: added paranoid state checking on I2C
this is here just while debugging an issue with Mark
This commit is contained in:
parent
7e19f49e42
commit
23e1b2e271
@ -103,7 +103,9 @@ I2CDevice::~I2CDevice()
|
|||||||
void I2CBus::dma_allocate(void)
|
void I2CBus::dma_allocate(void)
|
||||||
{
|
{
|
||||||
if (!i2c_started) {
|
if (!i2c_started) {
|
||||||
|
osalDbgAssert(I2CD[busnum].i2c->state == I2C_STOP, "i2cStart state");
|
||||||
i2cStart(I2CD[busnum].i2c, &i2ccfg);
|
i2cStart(I2CD[busnum].i2c, &i2ccfg);
|
||||||
|
osalDbgAssert(I2CD[busnum].i2c->state == I2C_READY, "i2cStart state");
|
||||||
i2c_started = true;
|
i2c_started = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -114,7 +116,9 @@ void I2CBus::dma_allocate(void)
|
|||||||
void I2CBus::dma_deallocate(void)
|
void I2CBus::dma_deallocate(void)
|
||||||
{
|
{
|
||||||
if (i2c_started) {
|
if (i2c_started) {
|
||||||
|
osalDbgAssert(I2CD[busnum].i2c->state == I2C_READY, "i2cStart state");
|
||||||
i2cStop(I2CD[busnum].i2c);
|
i2cStop(I2CD[busnum].i2c);
|
||||||
|
osalDbgAssert(I2CD[busnum].i2c->state == I2C_STOP, "i2cStart state");
|
||||||
i2c_started = false;
|
i2c_started = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -174,6 +178,7 @@ bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
|
|||||||
// calculate a timeout as twice the expected transfer time, and set as min of 4ms
|
// calculate a timeout as twice the expected transfer time, and set as min of 4ms
|
||||||
uint32_t timeout_ms = 1+2*(((8*1000000UL/bus.i2ccfg.clock_speed)*MAX(send_len, recv_len))/1000);
|
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);
|
timeout_ms = MAX(timeout_ms, _timeout_ms);
|
||||||
|
bus.i2c_active = true;
|
||||||
if(send_len == 0) {
|
if(send_len == 0) {
|
||||||
ret = i2cMasterReceiveTimeout(I2CD[bus.busnum].i2c, _address, recv_buf, recv_len, MS2ST(timeout_ms));
|
ret = i2cMasterReceiveTimeout(I2CD[bus.busnum].i2c, _address, recv_buf, recv_len, MS2ST(timeout_ms));
|
||||||
} else {
|
} else {
|
||||||
@ -181,13 +186,19 @@ bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
|
|||||||
recv_buf, recv_len, MS2ST(timeout_ms));
|
recv_buf, recv_len, MS2ST(timeout_ms));
|
||||||
}
|
}
|
||||||
i2cReleaseBus(I2CD[bus.busnum].i2c);
|
i2cReleaseBus(I2CD[bus.busnum].i2c);
|
||||||
|
bus.i2c_active = false;
|
||||||
|
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_READY, "i2cStart state");
|
||||||
if (ret != MSG_OK){
|
if (ret != MSG_OK){
|
||||||
//restart the bus
|
//restart the bus
|
||||||
if (bus.i2c_started) {
|
if (bus.i2c_started) {
|
||||||
|
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_READY, "i2cStart state");
|
||||||
i2cStop(I2CD[bus.busnum].i2c);
|
i2cStop(I2CD[bus.busnum].i2c);
|
||||||
|
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_STOP, "i2cStart state");
|
||||||
bus.i2c_started = false;
|
bus.i2c_started = false;
|
||||||
}
|
}
|
||||||
|
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_STOP, "i2cStart state");
|
||||||
i2cStart(I2CD[bus.busnum].i2c, &bus.i2ccfg);
|
i2cStart(I2CD[bus.busnum].i2c, &bus.i2ccfg);
|
||||||
|
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_READY, "i2cStart state");
|
||||||
bus.i2c_started = true;
|
bus.i2c_started = true;
|
||||||
} else {
|
} else {
|
||||||
if (recv_buf != recv) {
|
if (recv_buf != recv) {
|
||||||
|
@ -35,6 +35,7 @@ public:
|
|||||||
I2CConfig i2ccfg;
|
I2CConfig i2ccfg;
|
||||||
uint8_t busnum;
|
uint8_t busnum;
|
||||||
bool i2c_started;
|
bool i2c_started;
|
||||||
|
bool i2c_active;
|
||||||
|
|
||||||
void dma_allocate(void);
|
void dma_allocate(void);
|
||||||
void dma_deallocate(void);
|
void dma_deallocate(void);
|
||||||
|
Loading…
Reference in New Issue
Block a user