Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_BattMonitor/AP_BattMonitor_SMBus.cpp
Views: 1798
#include "AP_BattMonitor_config.h"12#if AP_BATTERY_SMBUS_ENABLED34#include "AP_BattMonitor_SMBus.h"56#define AP_BATTMONITOR_SMBUS_PEC_POLYNOME 0x07 // Polynome for CRC generation78extern const AP_HAL::HAL& hal;910const AP_Param::GroupInfo AP_BattMonitor_SMBus::var_info[] = {1112// @Param: I2C_BUS13// @DisplayName: Battery monitor I2C bus number14// @Description: Battery monitor I2C bus number15// @Range: 0 316// @User: Advanced17// @RebootRequired: True18AP_GROUPINFO("I2C_BUS", 10, AP_BattMonitor_SMBus, _bus, 0),1920// @Param: I2C_ADDR21// @DisplayName: Battery monitor I2C address22// @Description: Battery monitor I2C address23// @Range: 0 12724// @User: Advanced25// @RebootRequired: True26AP_GROUPINFO("I2C_ADDR", 11, AP_BattMonitor_SMBus, _address, AP_BATTMONITOR_SMBUS_I2C_ADDR),2728// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS2930AP_GROUPEND31};3233AP_BattMonitor_SMBus::AP_BattMonitor_SMBus(AP_BattMonitor &mon,34AP_BattMonitor::BattMonitor_State &mon_state,35AP_BattMonitor_Params ¶ms,36uint8_t i2c_bus)37: AP_BattMonitor_Backend(mon, mon_state, params)38{39AP_Param::setup_object_defaults(this, var_info);40_state.var_info = var_info;4142_bus.set_default(i2c_bus);43_params._serial_number.set(AP_BATT_SERIAL_NUMBER_DEFAULT);44_params._pack_capacity.set(0);45}4647void AP_BattMonitor_SMBus::init(void)48{49_dev = hal.i2c_mgr->get_device(_bus, _address, 100000, true, 20);5051if (_dev) {52timer_handle = _dev->register_periodic_callback(100000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_SMBus::timer, void));53}54}5556// return true if cycle count can be provided and fills in cycles argument57bool AP_BattMonitor_SMBus::get_cycle_count(uint16_t &cycles) const58{59if (!_has_cycle_count) {60return false;61}62cycles = _cycle_count;63return true;64}6566/// read the battery_voltage and current, should be called at 10hz67void AP_BattMonitor_SMBus::read(void)68{69// nothing to be done here for actually interacting with the battery70// however we can use this to set any parameters that need to be set7172if (_serial_number != _params._serial_number) {73_params._serial_number.set_and_notify(_serial_number);74}7576if (_full_charge_capacity != _params._pack_capacity) {77_params._pack_capacity.set_and_notify(_full_charge_capacity);78}79}8081// reads the pack full charge capacity82// returns if we already knew the pack capacity83void AP_BattMonitor_SMBus::read_full_charge_capacity(void)84{85if (_full_charge_capacity != 0) {86return;87}8889if (read_word(BATTMONITOR_SMBUS_FULL_CHARGE_CAPACITY, _full_charge_capacity)) {90_full_charge_capacity *= get_capacity_scaler();91}92}9394// reads the remaining capacity95// which will only be read if we know the full charge capacity (accounting for battery degradation)96void AP_BattMonitor_SMBus::read_remaining_capacity(void)97{98int32_t capacity = _params._pack_capacity;99100if (capacity <= 0) {101return;102}103104uint16_t data;105if (read_word(BATTMONITOR_SMBUS_REMAINING_CAPACITY, data)) {106_state.consumed_mah = MAX(0, capacity - (data * get_capacity_scaler()));107}108}109110// reads the temperature word from the battery111void AP_BattMonitor_SMBus::read_temp(void)112{113uint16_t data;114if (!read_word(BATTMONITOR_SMBUS_TEMP, data)) {115_has_temperature = (AP_HAL::millis() - _state.temperature_time) <= AP_BATT_MONITOR_TIMEOUT;116return;117}118_has_temperature = true;119120_state.temperature_time = AP_HAL::millis();121_state.temperature = KELVIN_TO_C(0.1f * data);122}123124// reads the serial number if it's not already known125// returns if the serial number was already known126void AP_BattMonitor_SMBus::read_serial_number(void)127{128// don't recheck the serial number if we already have it129if (_serial_number != -1) {130return;131}132133uint16_t data;134if (read_word(BATTMONITOR_SMBUS_SERIAL, data)) {135_serial_number = data;136}137}138139// reads the battery's cycle count140void AP_BattMonitor_SMBus::read_cycle_count()141{142// only read cycle count once143if (_has_cycle_count) {144return;145}146_has_cycle_count = read_word(BATTMONITOR_SMBUS_CYCLE_COUNT, _cycle_count);147}148149// read word from register150// returns true if read was successful, false if failed151bool AP_BattMonitor_SMBus::read_word(uint8_t reg, uint16_t& data) const152{153// buffer to hold results (1 extra byte returned holding PEC)154const uint8_t read_size = 2 + (_pec_supported ? 1 : 0);155uint8_t buff[read_size]; // buffer to hold results156157// read the appropriate register from the device158if (!_dev->read_registers(reg, buff, sizeof(buff))) {159return false;160}161162// check PEC163if (_pec_supported) {164const uint8_t pec = get_PEC(_address, reg, true, buff, 2);165if (pec != buff[2]) {166return false;167}168}169170// convert buffer to word171data = (uint16_t)buff[1]<<8 | (uint16_t)buff[0];172173// return success174return true;175}176177// read_block - returns number of characters read if successful, zero if unsuccessful178uint8_t AP_BattMonitor_SMBus::read_block(uint8_t reg, uint8_t* data, uint8_t len) const179{180// get length181uint8_t bufflen;182// read byte (first byte indicates the number of bytes in the block)183if (!_dev->read_registers(reg, &bufflen, 1)) {184return 0;185}186187// sanity check length returned by smbus188if (bufflen == 0 || bufflen > len) {189return 0;190}191192// buffer to hold results (2 extra byte returned holding length and PEC)193const uint8_t read_size = bufflen + 1 + (_pec_supported ? 1 : 0);194uint8_t buff[read_size];195196// read bytes197if (!_dev->read_registers(reg, buff, read_size)) {198return 0;199}200201// check PEC202if (_pec_supported) {203const uint8_t pec = get_PEC(_address, reg, true, buff, bufflen+1);204if (pec != buff[bufflen+1]) {205return 0;206}207}208209// copy data (excluding length & PEC)210memcpy(data, &buff[1], bufflen);211212// return success213return bufflen;214}215216/// get_PEC - calculate packet error correction code of buffer217uint8_t AP_BattMonitor_SMBus::get_PEC(const uint8_t i2c_addr, uint8_t cmd, bool reading, const uint8_t buff[], uint8_t len) const218{219// exit immediately if no data220if (len == 0) {221return 0;222}223224// prepare temp buffer for calculating crc225uint8_t tmp_buff[len+3];226tmp_buff[0] = i2c_addr << 1;227tmp_buff[1] = cmd;228tmp_buff[2] = tmp_buff[0] | (uint8_t)reading;229memcpy(&tmp_buff[3],buff,len);230231// initialise crc to zero232uint8_t crc = 0;233uint8_t shift_reg = 0;234bool do_invert;235236// for each byte in the stream237for (uint8_t i=0; i<sizeof(tmp_buff); i++) {238// load next data byte into the shift register239shift_reg = tmp_buff[i];240// for each bit in the current byte241for (uint8_t j=0; j<8; j++) {242do_invert = (crc ^ shift_reg) & 0x80;243crc <<= 1;244shift_reg <<= 1;245if(do_invert) {246crc ^= AP_BATTMONITOR_SMBUS_PEC_POLYNOME;247}248}249}250251// return result252return crc;253}254255#endif // AP_BATTERY_SMBUS_ENABLED256257258