diff --git a/examples/ina3221_test/Makefile b/examples/ina3221_test/Makefile
new file mode 100644
index 0000000..a257987
--- /dev/null
+++ b/examples/ina3221_test/Makefile
@@ -0,0 +1,3 @@
+PROGRAM=ina3221_test
+EXTRA_COMPONENTS = extras/i2c extras/ina3221
+include ../../common.mk
diff --git a/examples/ina3221_test/main.c b/examples/ina3221_test/main.c
new file mode 100644
index 0000000..5a883d2
--- /dev/null
+++ b/examples/ina3221_test/main.c
@@ -0,0 +1,126 @@
+/*
+ * Example of using INA3221
+ *
+ * Part of esp-open-rtos
+ * Copyright (C) 2016 Zaltora
+ * MIT Licensed as described in the file LICENSE
+ */
+
+#include "espressif/esp_common.h"
+#include "FreeRTOS.h"
+#include "task.h"
+#include <esp/uart.h>
+#include <stdbool.h>
+#include "ina3221/ina3221.h"
+
+#define PIN_SCL 5
+#define PIN_SDA 2
+#define ADDR INA3221_ADDR_0
+
+#define WARNING_CHANNEL 1
+#define WARNING_CURRENT (40.0)
+
+//#define STRUCT_SETTING 0
+#define MODE false  // true : continuous  measurements // false : trigger measurements
+
+void ina_measure(void *pvParameters)
+{
+    uint32_t measure_number = 0;
+    float bus_voltage;
+    float shunt_voltage;
+    float shunt_current;
+    bool warning = false ;
+
+    // Create ina3221 device
+    ina3221_t dev = {
+            .addr = ADDR,
+            .shunt = { 100 ,100 ,100 },  // shunt values are 100 mOhm for each channel
+            .mask.mask_register = INA3221_DEFAULT_MASK, // Init
+            .config.config_register = INA3221_DEFAULT_CONFIG, // Init
+    };
+
+#ifndef STRUCT_SETTING
+    if(ina3221_setting(&dev ,MODE, true, true)) //  mode selection ,  bus and shunt activated
+        goto error_loop;
+    if(ina3221_enableChannel(&dev , true, true, true)) // Enable all channels
+        goto error_loop;
+    if(ina3221_setAverage(&dev, INA3221_AVG_64)) // 64 samples average
+        goto error_loop;
+    if(ina3221_setBusConversionTime(&dev, INA3221_CT_2116)) // 2ms by channel
+        goto error_loop;
+    if(ina3221_setShuntConversionTime(&dev, INA3221_CT_2116)) // 2ms by channel
+        goto error_loop;
+#else
+    dev.config.mode = MODE; // mode selection
+    dev.config.esht = true; // shunt enable
+    dev.config.ebus = true; // bus enable
+    dev.config.ch1 = true; // channel 1 enable
+    dev.config.ch2 = true; // channel 2 enable
+    dev.config.ch3 = true; // channel 3 enable
+    dev.config.avg = INA3221_AVG_64; // 64 samples average
+    dev.config.vbus = INA3221_CT_2116; // 2ms by channel (bus)
+    dev.config.vsht = INA3221_CT_2116; // 2ms by channel (shunt)
+    if(ina3221_sync(&dev))
+        goto error_loop;
+#endif
+
+    ina3221_setWarningAlert(&dev, WARNING_CHANNEL-1, WARNING_CURRENT); //Set security flag overcurrent
+
+    while(1)
+    {
+        measure_number++;
+#if !MODE
+        if (ina3221_trigger(&dev)) // Start a measure
+            goto error_loop;
+        printf("trig done, wait: ");
+        do
+        {
+            printf("X");
+            if (ina3221_getStatus(&dev)) // get mask
+                goto error_loop;
+            vTaskDelay(20/portTICK_PERIOD_MS);
+            if(dev.mask.wf&(1<<(3-WARNING_CHANNEL)))
+                warning = true ;
+        } while(!(dev.mask.cvrf)); // check if measure done
+#else
+        if (ina3221_getStatus(&dev)) // get mask
+            goto error_loop;
+        if(dev.mask.wf&(1<<(3-WARNING_CHANNEL)))
+            warning = true ;
+#endif
+        for (uint8_t i = 0 ; i < BUS_NUMBER ; i++)
+        {
+            if(ina3221_getBusVoltage(&dev, i, &bus_voltage)) // Get voltage in V
+                goto error_loop;
+            if(ina3221_getShuntValue(&dev, i, &shunt_voltage, &shunt_current)) // Get voltage in mV and currant in mA
+                goto error_loop;
+
+            printf("\nC%u:Measure number %u\n",i+1,measure_number);
+            if (warning && (i+1) == WARNING_CHANNEL) printf("C%u:Warning Current > %.2f mA !!\n",i+1,WARNING_CURRENT);
+            printf("C%u:Bus voltage: %.02f V\n",i+1,bus_voltage );
+            printf("C%u:Shunt voltage: %.02f mV\n",i+1,shunt_voltage );
+            printf("C%u:Shunt current: %.02f mA\n\n",i+1,shunt_current );
+
+        }
+        warning = false ;
+        vTaskDelay(5000/portTICK_PERIOD_MS);
+    }
+
+    error_loop:
+    printf("%s: error while com with INA3221\n", __func__);
+    for(;;)
+    {
+        vTaskDelay(2000/portTICK_PERIOD_MS);
+        printf("%s: error loop\n", __FUNCTION__);
+    }
+}
+
+void user_init(void)
+{
+    uart_set_baud(0, 115200);
+    printf("SDK version:%s\n", sdk_system_get_sdk_version());
+
+    i2c_init(PIN_SCL,PIN_SDA);
+
+    xTaskCreate(ina_measure, "Measurements_task", 512, NULL, 2, NULL);
+}
diff --git a/extras/ina3221/component.mk b/extras/ina3221/component.mk
new file mode 100644
index 0000000..9f39aef
--- /dev/null
+++ b/extras/ina3221/component.mk
@@ -0,0 +1,9 @@
+# Component makefile for extras/ina3221
+
+# expected anyone using this driver includes it as 'ina3221/ina3221.h'
+INC_DIRS += $(ina3221_ROOT)..
+
+# args for passing into compile rule generation
+ina3221_SRC_DIR = $(ina3221_ROOT)
+
+$(eval $(call component_compile_rules,ina3221))
diff --git a/extras/ina3221/ina3221.c b/extras/ina3221/ina3221.c
new file mode 100644
index 0000000..f507b2c
--- /dev/null
+++ b/extras/ina3221/ina3221.c
@@ -0,0 +1,230 @@
+/**
+ * INA3221 driver for esp-open-rtos.
+ *
+ * Copyright (c) 2016 Zaltora (https://github.com/Zaltora)
+ *
+ * MIT Licensed as described in the file LICENSE
+ *
+ * @todo Interupt system for critical and warning alert pin
+ */
+
+#include "ina3221.h"
+
+#ifdef INA3221_DEBUG
+#define debug(fmt, ...) printf("%s: " fmt "\n", "INA3221", ## __VA_ARGS__)
+#else
+#define debug(fmt, ...)
+#endif
+
+static int _wireWriteRegister (uint8_t addr, uint8_t reg, uint16_t value)
+{
+    i2c_start();
+    if (!i2c_write(addr<<1)) // adress + W
+        goto error;
+    if (!i2c_write(reg))
+        goto error;
+    if (!i2c_write((value >> 8) & 0xFF))
+        goto error;
+    if (!i2c_write(value & 0xFF))
+        goto error;
+    i2c_stop();
+    debug("Data write to %02X : %02X+%04X\n",addr,reg,value);
+
+    return 0 ;
+
+    error:
+    debug("Error while xmitting I2C slave\n");
+    i2c_stop();
+    return -EIO;
+}
+
+static int _wireReadRegister(uint8_t addr, uint8_t reg, uint16_t *value)
+{
+    uint8_t tampon[2] = { 0 } ;
+
+    i2c_start();
+    if (!i2c_write(addr<<1)) // adress + W
+        goto error;
+    if (!i2c_write(reg))
+        goto error;
+    i2c_stop();
+    i2c_start(); // restart condition
+    if (!i2c_write((addr<<1) | 1)) // adress + R
+        goto error;
+    tampon[1] = i2c_read(0);
+    tampon[0] = i2c_read(1);
+    i2c_stop();
+    *value = tampon[1]<<8 | tampon[0] ;
+    debug("Data read from %02X: %02X+%04X\n",addr,reg,*value);
+
+    return 0;
+
+    error:
+    debug("Error while xmitting I2C slave\n");
+    i2c_stop();
+    return -EIO;
+}
+
+int ina3221_trigger(ina3221_t *dev)
+{
+    return _wireWriteRegister(dev->addr, INA3221_REG_CONFIG, dev->config.config_register);
+}
+
+int ina3221_getStatus(ina3221_t *dev)
+{
+    return _wireReadRegister(dev->addr, INA3221_REG_MASK, &dev->mask.mask_register);
+}
+
+int ina3221_sync(ina3221_t *dev)
+{
+    uint16_t ptr_data;
+    int err = 0;
+    //////////////////////// Sync config register
+    if ((err = _wireReadRegister(dev->addr, INA3221_REG_CONFIG, &ptr_data))) // Read config
+        return err;
+    if( ptr_data != dev->config.config_register) {
+        if ((err = _wireWriteRegister(dev->addr, INA3221_REG_CONFIG, dev->config.config_register))) // Update config
+            return err;
+    }
+    //////////////////////// Sync mask register config
+    if ((err = _wireReadRegister(dev->addr, INA3221_REG_MASK, &ptr_data))) // Read mask
+        return err;
+    if( (ptr_data & INA3221_MASK_CONFIG) != (dev->mask.mask_register & INA3221_MASK_CONFIG)) {
+        if ((err = _wireWriteRegister(dev->addr, INA3221_REG_MASK, dev->mask.mask_register & INA3221_MASK_CONFIG))) // Update config
+            return err;
+    }
+    return 0;
+}
+
+int ina3221_setting(ina3221_t *dev ,bool mode, bool bus, bool shunt)
+{
+    dev->config.mode = mode;
+    dev->config.ebus = bus;
+    dev->config.esht = shunt;
+    return _wireWriteRegister(dev->addr, INA3221_REG_CONFIG, dev->config.config_register);
+}
+
+int ina3221_enableChannel(ina3221_t *dev ,bool ch1, bool ch2, bool ch3)
+{
+    dev->config.ch1 = ch1;
+    dev->config.ch2 = ch2;
+    dev->config.ch3 = ch3;
+    return _wireWriteRegister(dev->addr, INA3221_REG_CONFIG, dev->config.config_register);
+}
+
+int ina3221_enableChannelSum(ina3221_t *dev ,bool ch1, bool ch2, bool ch3)
+{
+    dev->mask.scc1 = ch1;
+    dev->mask.scc2 = ch2;
+    dev->mask.scc3 = ch3;
+    return _wireWriteRegister(dev->addr, INA3221_REG_MASK, dev->mask.mask_register & INA3221_MASK_CONFIG);
+}
+
+int ina3221_enableLatchPin(ina3221_t *dev ,bool warning, bool critical)
+{
+    dev->mask.wen = warning;
+    dev->mask.cen = critical;
+    return _wireWriteRegister(dev->addr, INA3221_REG_MASK, dev->mask.mask_register & INA3221_MASK_CONFIG);
+}
+
+int ina3221_setAverage(ina3221_t *dev, ina3221_avg_t avg)
+{
+    dev->config.avg = avg;
+    return _wireWriteRegister(dev->addr, INA3221_REG_CONFIG, dev->config.config_register);
+}
+
+int ina3221_setBusConversionTime(ina3221_t *dev,ina3221_ct_t ct)
+{
+    dev->config.vbus = ct;
+    return _wireWriteRegister(dev->addr, INA3221_REG_CONFIG, dev->config.config_register);
+}
+
+int ina3221_setShuntConversionTime(ina3221_t *dev,ina3221_ct_t ct)
+{
+    dev->config.vsht = ct;
+    return _wireWriteRegister(dev->addr, INA3221_REG_CONFIG, dev->config.config_register);
+}
+
+int ina3221_reset(ina3221_t *dev)
+{
+    dev->config.config_register = INA3221_DEFAULT_CONFIG ; //dev reset
+    dev->mask.mask_register = INA3221_DEFAULT_CONFIG ; //dev reset
+    dev->config.rst = 1 ;
+    return _wireWriteRegister(dev->addr, INA3221_REG_CONFIG, dev->config.config_register); // send reset to device
+}
+
+int ina3221_getBusVoltage(ina3221_t *dev, ina3221_channel_t channel, float *voltage)
+{
+    int16_t raw_value;
+    int err = 0;
+    if ((err = _wireReadRegister(dev->addr,INA3221_REG_BUSVOLTAGE_1+channel*2, (uint16_t*)&raw_value)))
+        return err;
+    *voltage = raw_value*0.001 ; //V    8mV step
+	return 0;
+}
+
+int ina3221_getShuntValue(ina3221_t *dev, ina3221_channel_t channel, float *voltage, float *current)
+{
+    int16_t raw_value;
+	int err = 0;
+    if ((err = _wireReadRegister(dev->addr,INA3221_REG_SHUNTVOLTAGE_1+channel*2, (uint16_t*)&raw_value)))
+        return err;
+    *voltage = raw_value*0.005; //mV   40uV step
+    if(!dev->shunt[channel])
+    {
+        debug("No shunt configured for channel %u. Dev:%X\n",channel+1, dev->addr);
+        return -EINVAL;
+    }
+    *current = (*voltage*1000.0)/dev->shunt[channel] ;  //mA
+	return 0;
+}
+
+int ina3221_getSumShuntValue(ina3221_t *dev, float *voltage)
+{
+    int16_t raw_value;
+    int err = 0;
+    if ((err = _wireReadRegister(dev->addr,INA3221_REG_SHUNT_VOLTAGE_SUM, (uint16_t*)&raw_value)))
+        return err;
+    *voltage = raw_value*0.02; //uV   40uV step
+    return 0;
+}
+
+int ina3221_setCriticalAlert(ina3221_t *dev, ina3221_channel_t channel, float current)
+{
+    int16_t raw_value = current*dev->shunt[channel]*0.2; // format
+    return _wireWriteRegister(dev->addr,INA3221_REG_CRITICAL_ALERT_1+channel*2, *(uint16_t*)&raw_value);
+}
+
+int ina3221_setWarningAlert(ina3221_t *dev, ina3221_channel_t channel, float current)
+{
+    int16_t raw_value = current*dev->shunt[channel]*0.2  ; // format
+    return _wireWriteRegister(dev->addr,INA3221_REG_WARNING_ALERT_1+channel*2, *(uint16_t*)&raw_value);
+}
+
+int ina3221_setSumWarningAlert(ina3221_t *dev, float voltage)
+{
+    int16_t raw_value = voltage*50.0 ; // format
+    return _wireWriteRegister(dev->addr,INA3221_REG_SHUNT_VOLTAGE_SUM_LIMIT, *(uint16_t*)&raw_value);
+}
+
+int ina3221_setPowerValidUpperLimit(ina3221_t *dev, float voltage)
+{
+    if(!dev->config.ebus)
+    {
+        debug("Bus not enable. Dev:%X\n", dev->addr);
+        return -ENOTSUP;
+    }
+    int16_t raw_value = voltage*1000.0; //format
+    return _wireWriteRegister(dev->addr,INA3221_REG_VALID_POWER_UPPER_LIMIT, *(uint16_t*)&raw_value);
+}
+
+int ina3221_setPowerValidLowerLimit(ina3221_t *dev, float voltage)
+{
+    if(!dev->config.ebus)
+    {
+        debug("Bus not enable. Dev:%X\n", dev->addr);
+        return -ENOTSUP;
+    }
+    int16_t raw_value = voltage*1000.0; // round and format
+    return _wireWriteRegister(dev->addr,INA3221_REG_VALID_POWER_LOWER_LIMIT, *(uint16_t*)&raw_value);
+}
diff --git a/extras/ina3221/ina3221.h b/extras/ina3221/ina3221.h
new file mode 100644
index 0000000..000919c
--- /dev/null
+++ b/extras/ina3221/ina3221.h
@@ -0,0 +1,306 @@
+/**
+ * INA3221 driver for esp-open-rtos.
+ *
+ * Copyright (c) 2016 Zaltora (https://github.com/Zaltora)
+ *
+ * MIT Licensed as described in the file LICENSE
+ *
+ */
+
+#ifndef INA3221_H_
+#define INA3221_H_
+
+#include <errno.h>
+#include <stdio.h>
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#include "i2c/i2c.h"
+
+#define INA3221_ADDR_0  (0x40)      // A0 to GND
+#define INA3221_ADDR_1  (0x41)      // A0 to Vs+
+#define INA3221_ADDR_2  (0x42)      // A0 to SDA
+#define INA3221_ADDR_3  (0x43)      // A0 to SCL
+
+#define BUS_NUMBER 3  //Number of shunt available
+
+#define INA3221_REG_CONFIG                      (0x00)
+#define INA3221_REG_SHUNTVOLTAGE_1              (0x01)
+#define INA3221_REG_BUSVOLTAGE_1                (0x02)
+#define INA3221_REG_CRITICAL_ALERT_1            (0x07)
+#define INA3221_REG_WARNING_ALERT_1             (0x08)
+#define INA3221_REG_SHUNT_VOLTAGE_SUM           (0x0D)
+#define INA3221_REG_SHUNT_VOLTAGE_SUM_LIMIT     (0x0E)
+#define INA3221_REG_MASK                        (0x0F)
+#define INA3221_REG_VALID_POWER_UPPER_LIMIT     (0x10)
+#define INA3221_REG_VALID_POWER_LOWER_LIMIT     (0x11)
+
+/*
+ *  Default register after reset
+ */
+#define INA3221_DEFAULT_CONFIG                   (0x7127)
+#define INA3221_DEFAULT_MASK                     (0x0002)
+#define INA3221_DEFAULT_POWER_UPPER_LIMIT        (0x2710) //10V
+#define INA3221_DEFAULT_POWER_LOWER_LIMIT        (0x2328) //9V
+
+#define INA3221_MASK_CONFIG (0x7C00)
+/*
+ * Numbrer of samples
+ */
+typedef enum {
+	INA3221_AVG_1 = 0,  //Default
+	INA3221_AVG_4,
+	INA3221_AVG_16,
+	INA3221_AVG_64,
+	INA3221_AVG_128,
+	INA3221_AVG_256,
+	INA3221_AVG_512,
+	INA3221_AVG_1024,
+} ina3221_avg_t;
+
+/*
+ * Channel selection list
+ */
+typedef enum {
+    CHANNEL_1 = 0,
+    CHANNEL_2,
+    CHANNEL_3,
+} ina3221_channel_t;
+
+/*
+ * Conversion time in us
+ */
+typedef enum {
+	INA3221_CT_140 = 0,
+	INA3221_CT_204,
+	INA3221_CT_332,
+	INA3221_CT_588,
+	INA3221_CT_1100,  //Default
+	INA3221_CT_2116,
+	INA3221_CT_4156,
+	INA3221_CT_8244,
+} ina3221_ct_t ;
+
+/*
+ * Config description register
+ */
+typedef union
+{
+    struct {
+        uint16_t esht : 1; // Enable/Disable shunt measure    // LSB
+        uint16_t ebus : 1; // Enable/Disable bus measure
+        uint16_t mode : 1; // Single shot measure or continious mode
+        uint16_t vsht : 3; // Shunt voltage conversion time
+        uint16_t vbus : 3; // Bus voltage conversion time
+        uint16_t avg : 3; // number of sample collected and averaged together
+        uint16_t ch3 : 1; // Enable/Disable channel 3
+        uint16_t ch2 : 1; // Enable/Disable channel 2
+        uint16_t ch1 : 1; // Enable/Disable channel 1
+        uint16_t rst : 1; //Set this bit to 1 to reset device  // MSB
+    };
+    uint16_t config_register;
+} ina3221_config_t;
+
+
+/*
+ * Mask/enable description register
+ */
+typedef union
+{
+    struct {
+        uint16_t cvrf : 1 ; // Conversion ready flag (1: ready)   // LSB
+        uint16_t tcf : 1 ; // Timing control flag
+        uint16_t pvf : 1 ; // Power valid flag
+        uint16_t wf : 3 ; // Warning alert flag (Read mask to clear) (order : Channel1:channel2:channel3)
+        uint16_t sf : 1 ; // Sum alert flag (Read mask to clear)
+        uint16_t cf : 3 ; // Critical alert flag (Read mask to clear) (order : Channel1:channel2:channel3)
+        uint16_t cen : 1 ; // Critical alert latch (1:enable)
+        uint16_t wen : 1 ; // Warning alert latch (1:enable)
+        uint16_t scc3 : 1 ; // channel 3 sum (1:enable)
+        uint16_t scc2 : 1 ; // channel 2 sum (1:enable)
+        uint16_t scc1 : 1 ; // channel 1 sum (1:enable)
+        uint16_t  : 1 ; //Reserved         //MSB
+    };
+    uint16_t mask_register;
+} ina3221_mask_t;
+
+/*
+ *  Device description
+ */
+typedef struct {
+    const uint8_t addr; // ina3221 I2C address
+    const uint16_t shunt[BUS_NUMBER]; //Memory of shunt value  (mOhm)
+    ina3221_config_t config; //Memory of ina3221 config
+    ina3221_mask_t mask; //Memory of mask_config
+} ina3221_t;
+
+/**
+ * sync internal config buffer  and mask with external device register ( When struct is manually set )
+ * @param dev Pointer to device descriptor
+ * @return Non-zero if error occured
+ */
+int ina3221_sync(ina3221_t *dev);
+
+/**
+ * send current config register to trig a measurement in single-shot mode
+ * @param dev Pointer to device descriptor
+ * @return Non-zero if error occured
+ */
+int ina3221_trigger(ina3221_t *dev);
+
+/**
+ * get mask register from the device ( Used to read flags )
+ * @param dev Pointer to device descriptor
+ * @return Non-zero if error occured
+ */
+int ina3221_getStatus(ina3221_t *dev);
+
+/**
+ * Set options for bus and shunt
+ * @param dev Pointer to device descriptor
+ * @param mode Selection of measurement (true :continuous // false:single-shot)
+ * @param bus Enable/Disable bus measures
+ * @param shunt Enable/Disable shunt measures
+ * @return Non-zero if error occured
+ */
+int ina3221_setting(ina3221_t *dev ,bool mode, bool bus, bool shunt);
+
+/**
+ * Select channel
+ * @param dev Pointer to device descriptor
+ * @param ch1 Enable/Disable channel 1 ( true : enable // false : disable )
+ * @param ch2 Enable/Disable channel 2 ( true : enable // false : disable )
+ * @param ch3 Enable/Disable channel 3 ( true : enable // false : disable )
+ * @return Non-zero if error occured
+ */
+int ina3221_enableChannel(ina3221_t *dev ,bool ch1, bool ch2, bool ch3);
+
+/**
+ * Select channel to be sum (don't impact enable channel status)
+ * @param dev Pointer to device descriptor
+ * @param ch1 Enable/Disable channel 1 ( true : enable // false : disable )
+ * @param ch2 Enable/Disable channel 2 ( true : enable // false : disable )
+ * @param ch3 Enable/Disable channel 3 ( true : enable // false : disable )
+ * @return Non-zero if error occured
+ */
+int ina3221_enableChannelSum(ina3221_t *dev ,bool ch1, bool ch2, bool ch3);
+
+/**
+ * enable Latch on warning and critical alert pin
+ * @param dev Pointer to device descriptor
+ * @param warning Enable/Disable warning latch ( true : Latch // false : Transparent )
+ * @param critical Enable/Disable critical latch ( true : Latch // false : Transparent )
+ * @return Non-zero if error occured
+ */
+int ina3221_enableLatchPin(ina3221_t *dev ,bool warning, bool critical);
+
+/**
+ * Set average ( number(s) of point measured )
+ * @param dev Pointer to device descriptor
+ * @param avg Value of average selection
+ * @return Non-zero if error occured
+ */
+int ina3221_setAverage(ina3221_t *dev, ina3221_avg_t avg);
+
+/**
+ * Set conversion time ( time for a measurement ) for bus.
+ * @param dev Pointer to device descriptor
+ * @param ct Value of conversion time selection
+ * @return Non-zero if error occured
+ */
+int ina3221_setBusConversionTime(ina3221_t *dev,ina3221_ct_t ct);
+
+/**
+ * Set conversion time ( time for a measurement ) for shunt.
+ * @param dev Pointer to device descriptor
+ * @param ct Value of conversion time selection
+ * @return Non-zero if error occured
+ */
+int ina3221_setShuntConversionTime(ina3221_t *dev,ina3221_ct_t ct);
+
+/**
+ * Reset device and config like POR (Power-On-Reset)
+ * @param dev Pointer to device descriptor
+ * @return Non-zero if error occured
+ */
+int ina3221_reset(ina3221_t *dev);
+
+/**
+ * Get Bus voltage (V)
+ * @param dev Pointer to device descriptor
+ * @param channel Select channel value to get
+ * @param voltage Data pointer to get bus voltage (V)
+ * @return Non-zero if error occured
+ */
+int ina3221_getBusVoltage(ina3221_t *dev, ina3221_channel_t channel, float *voltage);
+
+/**
+ * Get Shunt voltage (mV) and current (mA)
+ * @param dev Pointer to device descriptor
+ * @param channel Select channel value to get
+ * @param voltage Data pointer to get shunt voltage (mV)
+ * @param current Data pointer to get shunt voltage (mA)
+ * @return Non-zero if error occured
+ */
+int ina3221_getShuntValue(ina3221_t *dev, ina3221_channel_t channel, float *voltage, float *current);
+
+/**
+ * Get Shunt-voltage (mV) sum value of selected channels
+ * @param dev Pointer to device descriptor
+ * @param channel Select channel value to get
+ * @param voltage Data pointer to get shunt voltage (mV)
+ * @return Non-zero if error occured
+ */
+int ina3221_getSumShuntValue(ina3221_t *dev, float *voltage);
+
+/**
+ * Set Critical alert (when measurement(s) is greater that value set )
+ * @param dev Pointer to device descriptor
+ * @param channel Select channel value to set
+ * @param current Value to set (mA) // max : 163800/shunt (mOhm)
+ * @return Non-zero if error occured
+ */
+int ina3221_setCriticalAlert(ina3221_t *dev, ina3221_channel_t channel, float current);
+
+/**
+ * Set Warning alert (when average measurement(s) is greater that value set )
+ * @param dev Pointer to device descriptor
+ * @param channel Select channel value to set
+ * @param current Value to set (mA)  // max : 163800/shunt (mOhm)
+ * @return Non-zero if error occured
+ */
+int ina3221_setWarningAlert(ina3221_t *dev, ina3221_channel_t channel, float current);
+
+/**
+ * Set Sum Warning alert (Compared to each completed cycle of all selected channels : Sum register )
+ * @param dev Pointer to device descriptor
+ * @param voltage voltage to set (mV) //  max : 655.32
+ * @return Non-zero if error occured
+ */
+int ina3221_setSumWarningAlert(ina3221_t *dev, float voltage);
+
+/**
+ * Set Power-valid upper-limit ( To determine if power conditions are met.)( bus need enable )
+ * If bus voltage exceed the value set, PV pin is high
+ * @param dev Pointer to device descriptor
+ * @param voltage voltage to set (V)
+ * @return Non-zero if error occured
+ */
+int ina3221_setPowerValidUpperLimit(ina3221_t *dev, float voltage);
+
+/**
+ * Set Power-valid lower-limit ( To determine if power conditions are met.)( bus need enable )
+ * If bus voltage drops below the value set, PV pin is low
+ * @param dev Pointer to device descriptor
+ * @param voltage voltage to set (V)
+ * @return Non-zero if error occured
+ */
+int ina3221_setPowerValidLowerLimit(ina3221_t *dev, float voltage);
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* INA3221_H_ */