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_INA3221.h
Views: 1798
#pragma once12#include "AP_BattMonitor_config.h"34#if AP_BATTERY_INA3221_ENABLED56/*7*8* Datasheet: https://www.ti.com/lit/ds/symlink/ina3221.pdf?ts=15973692540469*/1011// The INA3221 takes two measurements for each channel: one for shunt voltage12// and one for bus voltage. Each measurement can be independently or13// sequentially measured, based on the mode setting (bits 2-0 in the14// Configuration register). When the INA3221 is in normal operating mode15// (that is, the MODE bits of the Configuration register are set to 111), the16// device continuously converts a shunt-voltage reading followed by a17// bus-voltage reading. This procedure converts one channel, and then continues18// to the shunt voltage reading of the next enabled channel, followed by the19// bus-voltage reading for that channel, and so on, until all enabled channels20// have been measured. The programmed Configuration register mode setting21// applies to all channels. Any channels that are not enabled are bypassed in22// the measurement sequence, regardless of mode setting.232425// 8.3.3 Software Reset26// The INA3221 features a software reset that reinitializes the device and27// register settings to default power-up values without having to cycle power28// to the device. Use bit 15 (RST) of the Configuration register to perform a29// software reset. Setting RST reinitializes all registers and settings to the30// default power state with the exception of the power-valid output state. If a31// software reset is issued, the INA3221 holds the output of the PV pin until32// the power-valid detection sequence completes. The Power-Valid UpperLimit and33// Power-Valid Lowerlimit registers return to the default state when the34// software reset has been issued. Therefore, any reprogrammed limit registers35// are reset, resulting in the original power-valid thresholds validating the36// power-valid conditions. This architecture prevents interruption to circuitry37// connected to the powervalid output during a software reset event.3839// The INA3221 has programmable conversion times for both the shunt- and40// bus-voltage measurements. The selectable conversion times for these41// measurements range from 140μs to 8.244ms.424344#include "AP_BattMonitor.h"45#include "AP_BattMonitor_Backend.h"4647#ifndef HAL_BATTMON_INA3221_MAX_DEVICES48#define HAL_BATTMON_INA3221_MAX_DEVICES 149#endif5051class AP_BattMonitor_INA3221 : public AP_BattMonitor_Backend52{53public:54/// Constructor55AP_BattMonitor_INA3221(AP_BattMonitor &mon,56AP_BattMonitor::BattMonitor_State &mon_state,57AP_BattMonitor_Params ¶ms);5859void init() override;6061/// Read the battery voltage and current. Should be called at 10hz62void read() override;6364bool has_current() const override {65return true;66}6768static const struct AP_Param::GroupInfo var_info[];6970private:7172AP_Int8 i2c_bus;73AP_Int8 i2c_address;74AP_Int8 channel;7576static struct AddressDriver {77bool read_register(uint8_t addr, uint16_t &ret);78bool write_register(uint8_t addr, uint16_t val);79bool write_config(void);80void timer(void);81void register_timer();8283AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev;84uint8_t bus;85uint8_t address;86uint8_t channel_mask;87uint8_t dev_channel_mask;8889struct StateList {90struct StateList *next;91HAL_Semaphore sem;92uint8_t channel;9394bool healthy;95float voltage;96float current_amps;97float delta_mah;98float delta_wh;99uint32_t last_time_micros;100};101StateList *statelist;102103} address_driver[HAL_BATTMON_INA3221_MAX_DEVICES];104static uint8_t address_driver_count;105106AddressDriver::StateList *address_driver_state;107};108109#endif // AP_BATTERY_INA3221_ENABLED110111112