// read word from register // returns true if read was successful, false if failed bool AP_BattMonitor_SMBus_I2C::read_word(uint8_t reg, uint16_t& data) const { // take i2c bus semaphore if (!_dev->get_semaphore()->take_nonblocking()) { return false; } uint8_t buff[3]; // buffer to hold results // read three bytes and place in last three bytes of buffer if (!_dev->read_registers(reg, buff, sizeof(buff))) { _dev->get_semaphore()->give(); return false; } // check PEC uint8_t pec = get_PEC(BATTMONITOR_SMBUS_I2C_ADDR, reg, true, buff, 2); if (pec != buff[2]) { _dev->get_semaphore()->give(); return false; } // convert buffer to word data = (uint16_t)buff[1]<<8 | (uint16_t)buff[0]; // give back i2c semaphore _dev->get_semaphore()->give(); // return success return true; }
// read_block - returns number of characters read if successful, zero if unsuccessful uint8_t AP_BattMonitor_SMBus_I2C::read_block(uint8_t reg, uint8_t* data, uint8_t max_len, bool append_zero) const { uint8_t buff[max_len+2]; // buffer to hold results (2 extra byte returned holding length and PEC) // take i2c bus semaphore if (!_dev->get_semaphore()->take_nonblocking()) { return 0; } // read bytes if (!_dev->read_registers(reg, buff, sizeof(buff))) { _dev->get_semaphore()->give(); return 0; } // give back i2c semaphore _dev->get_semaphore()->give(); // get length uint8_t bufflen = buff[0]; // sanity check length returned by smbus if (bufflen == 0 || bufflen > max_len) { return 0; } // check PEC uint8_t pec = get_PEC(BATTMONITOR_SMBUS_I2C_ADDR, reg, true, buff, bufflen+1); if (pec != buff[bufflen+1]) { return 0; } // copy data (excluding PEC) memcpy(data, &buff[1], bufflen); // optionally add zero to end if (append_zero) { data[bufflen] = '\0'; } // return success return bufflen; }
// read_block - returns number of characters read if successful, zero if unsuccessful uint8_t AP_BattMonitor_SMBus_Maxell::read_block(uint8_t reg, uint8_t* data, bool append_zero) const { // get length uint8_t bufflen; // read byte (first byte indicates the number of bytes in the block) if (!_dev->read_registers(reg, &bufflen, 1)) { return 0; } // sanity check length returned by smbus if (bufflen == 0 || bufflen > SMBUS_READ_BLOCK_MAXIMUM_TRANSFER) { return 0; } // buffer to hold results (2 extra byte returned holding length and PEC) const uint8_t read_size = bufflen + 1 + (_pec_supported ? 1 : 0); uint8_t buff[read_size]; // read bytes if (!_dev->read_registers(reg, buff, read_size)) { return 0; } // check PEC if (_pec_supported) { uint8_t pec = get_PEC(AP_BATTMONITOR_SMBUS_I2C_ADDR, reg, true, buff, bufflen+1); if (pec != buff[bufflen+1]) { return 0; } } // copy data (excluding PEC) memcpy(data, &buff[1], bufflen); // optionally add zero to end if (append_zero) { data[bufflen] = '\0'; } // return success return bufflen; }
uint8_t BATT_SMBUS::read_block(uint8_t reg, uint8_t *data, uint8_t max_len, bool append_zero) { uint8_t buff[max_len + 2]; // buffer to hold results // read bytes including PEC int ret = transfer(®, 1, buff, max_len + 2); // return zero on failure if (ret != OK) { return 0; } // get length uint8_t bufflen = buff[0]; // sanity check length returned by smbus if (bufflen == 0 || bufflen > max_len) { return 0; } // check PEC uint8_t pec = get_PEC(reg, true, buff, bufflen + 1); if (pec != buff[bufflen + 1]) { return 0; } // copy data memcpy(data, &buff[1], bufflen); // optionally add zero to end if (append_zero) { data[bufflen] = '\0'; } // return success return bufflen; }
int BATT_SMBUS::read_reg(uint8_t reg, uint16_t &val) { uint8_t buff[3]; // 2 bytes of data + PEC // read from register int ret = transfer(®, 1, buff, 3); if (ret == OK) { // check PEC uint8_t pec = get_PEC(reg, true, buff, 2); if (pec == buff[2]) { val = (uint16_t)buff[1] << 8 | (uint16_t)buff[0]; } else { ret = ENOTTY; } } // return success or failure return ret; }