HAL_PX4: fixed a race condition on i2c init

we could call init on two devices with the same name, which caused
init_ok to be false. This could cause the SMBus battery to fail to
initialise

Thanks to Michael duBreuil for finding this!
This commit is contained in:
Andrew Tridgell 2017-10-26 15:08:29 +11:00
parent b6404ff26b
commit 3402d07651
3 changed files with 15 additions and 0 deletions

View File

@ -155,6 +155,9 @@ static int main_loop(int argc, char **argv)
hal.uartE->begin(57600); hal.uartE->begin(57600);
hal.scheduler->init(); hal.scheduler->init();
// init the I2C wrapper class
PX4_I2C::init_lock();
/* /*
run setup() at low priority to ensure CLI doesn't hang the run setup() at low priority to ensure CLI doesn't hang the
system, and to allow initial sensor read loops to run system, and to allow initial sensor read loops to run

View File

@ -22,6 +22,7 @@
namespace PX4 { namespace PX4 {
uint8_t PX4::PX4_I2C::instance; uint8_t PX4::PX4_I2C::instance;
pthread_mutex_t PX4::PX4_I2C::instance_lock;
DeviceBus I2CDevice::businfo[I2CDevice::num_buses]; DeviceBus I2CDevice::businfo[I2CDevice::num_buses];
@ -72,14 +73,19 @@ bool PX4_I2C::do_transfer(uint8_t address, const uint8_t *send, uint32_t send_le
{ {
set_address(address); set_address(address);
if (!init_done) { if (!init_done) {
if (pthread_mutex_lock(&instance_lock) != 0) {
return false;
}
init_done = true; init_done = true;
// we do late init() so we can setup the device paths // we do late init() so we can setup the device paths
snprintf(devname, sizeof(devname), "AP_I2C_%u", instance); snprintf(devname, sizeof(devname), "AP_I2C_%u", instance);
snprintf(devpath, sizeof(devpath), "/dev/api2c%u", instance); snprintf(devpath, sizeof(devpath), "/dev/api2c%u", instance);
init_ok = (init() == OK); init_ok = (init() == OK);
if (init_ok) { if (init_ok) {
instance++; instance++;
} }
pthread_mutex_unlock(&instance_lock);
} }
if (!init_ok) { if (!init_ok) {
return false; return false;

View File

@ -24,8 +24,14 @@ public:
uint8_t map_bus_number(uint8_t bus) const; uint8_t map_bus_number(uint8_t bus) const;
// setup instance_lock
static void init_lock(void) {
pthread_mutex_init(&instance_lock, nullptr);
}
private: private:
static uint8_t instance; static uint8_t instance;
static pthread_mutex_t instance_lock;
bool init_done; bool init_done;
bool init_ok; bool init_ok;
char devname[10]; char devname[10];