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_AD7091R5.cpp
Views: 1798
#include "AP_BattMonitor_AD7091R5.h"12/**3* @brief You can use it to Read Current and voltage of 1-3 batteries from a ADC extender IC over I2C.4* AD7091R5 is a ADC extender and we are using it to read current and voltage of multiple batteries.5* Examples of Pin combination:6* 1)Pin 50 = Voltage 51,52,53 = Current. For 3 battery combination Voltage will be same accross.7* 2)Pin 50,51 = Voltage and Current Battery 1 - Pin 52,53 = Voltage and Current Battery 28* Only the First instance of Battery Monitor will be reading the values from IC over I2C.9* Make sure you understand the method of calculation used in this driver before using it.10* e.g. using pin 1 on IC to read voltage of 2 batteries and pin 2 and 3 to read current from individual battery.11* Pin number represents 50 = pin 1, 51 = pin 2 and so on 52, 5312* BATT2_Monitor = 24 , BATT3_Monitor = 2413* BATT2_VOLT_PIN = 50 , BATT3_VOLT_PIN = 5014* BATT2_CURR_PIN = 51 , BATT3_CURR_PIN = 5215*16*17*/1819#if AP_BATTERY_AD7091R5_ENABLED2021#include <AP_HAL/AP_HAL.h>22#include <AP_Common/AP_Common.h>23#include <AP_Math/AP_Math.h>2425//macro defines26#define AD7091R5_I2C_ADDR 0x2F // A0 and A1 tied to GND27#define AD7091R5_I2C_BUS 028#define AD7091R5_RESET 0x0229#define AD7091R5_RESULT_ADDR 0x0030#define AD7091R5_CHAN_ADDR 0x0131#define AD7091R5_CONF_ADDR 0x0232#define AD7091R5_CH_ID(x) ((x >> 5) & 0x03)33#define AD7091R5_RES_MASK 0x0F34#define AD7091R5_REF 3.3f35#define AD7091R5_RESOLUTION (float)409636#define AD7091R5_PERIOD_USEC 10000037#define AD7091R5_BASE_PIN 50383940extern const AP_HAL::HAL& hal;41const AP_Param::GroupInfo AP_BattMonitor_AD7091R5::var_info[] = {4243// @Param: VOLT_PIN44// @DisplayName: Battery Voltage sensing pin on the AD7091R5 Ic45// @Description: Sets the analog input pin that should be used for voltage monitoring on AD7091R5.46// @Values: -1:Disabled47// @User: Standard48// @RebootRequired: True49AP_GROUPINFO("VOLT_PIN", 56, AP_BattMonitor_AD7091R5, _volt_pin, 0),5051// @Param: CURR_PIN52// @DisplayName: Battery Current sensing pin53// @Description: Sets the analog input pin that should be used for Current monitoring on AD7091R5.54// @Values: -1:Disabled55// @User: Standard56// @RebootRequired: True57AP_GROUPINFO("CURR_PIN", 57, AP_BattMonitor_AD7091R5, _curr_pin, 0),5859// @Param: VOLT_MULT60// @DisplayName: Voltage Multiplier61// @Description: Used to convert the voltage of the voltage sensing pin (@PREFIX@VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT).62// @User: Advanced63AP_GROUPINFO("VOLT_MULT", 58, AP_BattMonitor_AD7091R5, _volt_multiplier, 0),6465// @Param: AMP_PERVLT66// @DisplayName: Amps per volt67// @Description: Number of amps that a 1V reading on the current sensor corresponds to.68// @Units: A/V69// @User: Standard70AP_GROUPINFO("AMP_PERVLT", 59, AP_BattMonitor_AD7091R5, _curr_amp_per_volt, 0),7172// @Param: AMP_OFFSET73// @DisplayName: AMP offset74// @Description: Voltage offset at zero current on current sensor75// @Units: V76// @User: Standard77AP_GROUPINFO("AMP_OFFSET", 60, AP_BattMonitor_AD7091R5, _curr_amp_offset, 0),7879// @Param: VLT_OFFSET80// @DisplayName: Volage offset81// @Description: Voltage offset on voltage pin. This allows for an offset due to a diode. This voltage is subtracted before the scaling is applied82// @Units: V83// @User: Advanced84AP_GROUPINFO("VLT_OFFSET", 61, AP_BattMonitor_AD7091R5, _volt_offset, 0),8586// CHECK/UPDATE INDEX TABLE IN AP_BattMonitor_Backend.cpp WHEN CHANGING OR ADDING PARAMETERS8788AP_GROUPEND89};909192//Variable initialised to read from first instance.93AP_BattMonitor_AD7091R5::AnalogData AP_BattMonitor_AD7091R5::_analog_data[AD7091R5_NO_OF_CHANNELS];94bool AP_BattMonitor_AD7091R5::_first = true;95bool AP_BattMonitor_AD7091R5::_health = false;9697/**98* @brief Construct a new ap battmonitor ad7091r5::ap battmonitor ad7091r5 object99*100* @param mon101* @param mon_state102* @param params103*/104AP_BattMonitor_AD7091R5::AP_BattMonitor_AD7091R5(AP_BattMonitor &mon,105AP_BattMonitor::BattMonitor_State &mon_state,106AP_BattMonitor_Params ¶ms) :107AP_BattMonitor_Backend(mon, mon_state, params)108{109AP_Param::setup_object_defaults(this, var_info);110_state.var_info = var_info;111}112113/**114* @brief probe and initialize the sensor and register call back115*116*/117void AP_BattMonitor_AD7091R5::init()118{119// voltage and current pins from params and check if there are in range120if (_volt_pin.get() >= AD7091R5_BASE_PIN && _volt_pin.get() <= AD7091R5_BASE_PIN + AD7091R5_NO_OF_CHANNELS &&121_curr_pin.get() >= AD7091R5_BASE_PIN && _curr_pin.get() <= AD7091R5_BASE_PIN + AD7091R5_NO_OF_CHANNELS) {122volt_buff_pt = _volt_pin.get() - AD7091R5_BASE_PIN;123curr_buff_pt = _curr_pin.get() - AD7091R5_BASE_PIN;124}125else{126return; //pin values are out of range127}128129// only the first instance read the i2c device130if (_first) {131_first = false;132// probe i2c device133_dev = hal.i2c_mgr->get_device(AD7091R5_I2C_BUS, AD7091R5_I2C_ADDR);134135if (_dev) {136WITH_SEMAPHORE(_dev->get_semaphore());137_dev->set_retries(10); // lots of retries during probe138//Reset and config device139if (_initialize()) {140_dev->set_retries(2); // drop to 2 retries for runtime141_dev->register_periodic_callback(AD7091R5_PERIOD_USEC, FUNCTOR_BIND_MEMBER(&AP_BattMonitor_AD7091R5::_read_adc, void));142}143}144}145}146147/**148* @brief read - read the voltage and curren149*150*/151void AP_BattMonitor_AD7091R5::read()152{153154WITH_SEMAPHORE(sem);155//copy global health status to all instances156_state.healthy = _health;157158//return if system not healthy159if (!_state.healthy) {160return;161}162163//voltage conversion164_state.voltage = (_data_to_volt(_analog_data[volt_buff_pt].data) - _volt_offset) * _volt_multiplier;165166//current amps conversion167_state.current_amps = (_data_to_volt(_analog_data[curr_buff_pt].data) - _curr_amp_offset) * _curr_amp_per_volt;168169// calculate time since last current read170uint32_t tnow = AP_HAL::micros();171uint32_t dt_us = tnow - _state.last_time_micros;172173// update total current drawn since startup174update_consumed(_state, dt_us);175176// record time177_state.last_time_micros = tnow;178}179180/**181* @brief read all four channels and store the results182*183*/184void AP_BattMonitor_AD7091R5::_read_adc()185{186uint8_t data[AD7091R5_NO_OF_CHANNELS*2];187//reset and reconfigure IC if health status is not good.188if (!_state.healthy) {189_initialize();190}191//read value192bool ret = _dev->transfer(nullptr, 0, data, sizeof(data));193WITH_SEMAPHORE(sem);194if (ret) {195for (int i=0; i<AD7091R5_NO_OF_CHANNELS; i++) {196uint8_t chan = AD7091R5_CH_ID(data[2*i]);197_analog_data[chan].data = ((uint16_t)(data[2*i]&AD7091R5_RES_MASK)<<8) | data[2*i+1];198}199_health = true;200} else {201_health = false;202}203}204205/**206* @brief config the adc207*208* @return true209* @return false210*/211bool AP_BattMonitor_AD7091R5::_initialize()212{213//reset the device214uint8_t data[3] = {AD7091R5_CONF_ADDR, AD7091R5_CONF_CMD | AD7091R5_RESET, AD7091R5_CONF_PDOWN0};215216if(_dev->transfer(data, sizeof(data), nullptr, 0)){217//command mode, use external 3.3 reference, all channels enabled, set address pointer register to read the adc results218uint8_t data_2[6] = {AD7091R5_CONF_ADDR, AD7091R5_CONF_CMD, AD7091R5_CONF_PDOWN0, AD7091R5_CHAN_ADDR, AD7091R5_CHAN_ALL, AD7091R5_RESULT_ADDR};219return _dev->transfer(data_2, sizeof(data_2), nullptr, 0);220}221return false;222}223224/**225* @brief convert binary reading to volts226*227* @param data228* @return float229*/230float AP_BattMonitor_AD7091R5::_data_to_volt(uint32_t data)231{232return (AD7091R5_REF/AD7091R5_RESOLUTION)*data;233}234235#endif // AP_BATTERY_AD7091R5_ENABLED236237238