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_LTC2946.cpp
Views: 1798
#include "AP_BattMonitor_config.h"12#if AP_BATTERY_LTC2946_ENABLED34#include <GCS_MAVLink/GCS.h>5#include <AP_HAL/utility/sparse-endian.h>67#include "AP_BattMonitor_LTC2946.h"89extern const AP_HAL::HAL& hal;1011#define REG_CTRLA 0x0012#define REG_CTRLB 0x0113#define REG_STATUS 0x8014#define REG_MFR_ID 0xe71516// first byte of 16 bit ID is stable17#define ID_LTC2946 0x601819#define REG_DELTA 0x14 // 16 bits20#define REG_VIN 0x1e // 16 bits2122#define REGA_CONF 0x18 // sense, alternate23#define REGB_CONF 0x01 // auto-reset2425void AP_BattMonitor_LTC2946::init(void)26{27dev = hal.i2c_mgr->get_device(HAL_BATTMON_LTC2946_BUS, HAL_BATTMON_LTC2946_ADDR, 100000, false, 20);28if (!dev) {29return;30}3132uint8_t id = 0;33WITH_SEMAPHORE(dev->get_semaphore());34if (!dev->read_registers(REG_MFR_ID, &id, 1) || id != ID_LTC2946) {35GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "LTC2946: Failed to find device 0x%04x", unsigned(id));36return;37}3839if (!dev->write_register(REG_CTRLA, REGA_CONF) ||40!dev->write_register(REG_CTRLB, REGB_CONF)) {41GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "LTC2946: Failed to configure device");42return;43}4445// use datasheet typical values46voltage_LSB = 102.4 / 4095.0;47current_LSB = (0.1024/0.0005) / 4095.0;4849GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "LTC2946: found monitor on bus %u", HAL_BATTMON_LTC2946_BUS);5051if (dev) {52dev->register_periodic_callback(25000, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_LTC2946::timer, void));53}54}5556/// read the battery_voltage and current, should be called at 10hz57void AP_BattMonitor_LTC2946::read(void)58{59WITH_SEMAPHORE(accumulate.sem);60_state.healthy = accumulate.count > 0;61if (!_state.healthy) {62return;63}6465_state.voltage = accumulate.volt_sum / accumulate.count;66_state.current_amps = accumulate.current_sum / accumulate.count;67accumulate.volt_sum = 0;68accumulate.current_sum = 0;69accumulate.count = 0;7071const uint32_t tnow = AP_HAL::micros();72const uint32_t dt_us = tnow - _state.last_time_micros;7374// update total current drawn since startup75update_consumed(_state, dt_us);7677_state.last_time_micros = tnow;78}7980/*81read word from register82returns true if read was successful, false if failed83*/84bool AP_BattMonitor_LTC2946::read_word(const uint8_t reg, uint16_t& data) const85{86// read the appropriate register from the device87if (!dev->read_registers(reg, (uint8_t *)&data, sizeof(data))) {88return false;89}9091// convert byte order92data = uint16_t(be16toh(uint16_t(data)));9394// return success95return true;96}9798void AP_BattMonitor_LTC2946::timer(void)99{100uint16_t amps, volts;101if (!read_word(REG_DELTA, amps) ||102!read_word(REG_VIN, volts)) {103return;104}105WITH_SEMAPHORE(accumulate.sem);106// convert 12 bit ADC data107accumulate.volt_sum += (volts>>4) * voltage_LSB;108accumulate.current_sum += (amps>>4) * current_LSB;109accumulate.count++;110}111112#endif // AP_BATTERY_LTC2946_ENABLED113114115