Compare commits

...

2 Commits

@ -26,7 +26,6 @@ mqttServer = mqttConfig.get("server")
mqttPort = mqttConfig.get("port")
sensorConfig = monitorConfigFile.get("sensor")
transformerLine = sensorConfig['config']['line']
sslEnabled = monitorConfigFile["ssl"]['enabled']
if not sslEnabled:
mqttConfig["port"] = 1883
@ -53,8 +52,7 @@ env.Append(CPPDEFINES=[
("TM_MQTT_PORT", mqttConfig.get('port')),
("TM_MQTT_SVR", mqttConfig.get("server")),
("TM_MQTT_USER", mqttConfig.get("user")),
("TM_MQTT_PASSWD", mqttConfig.get("password")),
("TM_CT", transformerLine)
("TM_MQTT_PASSWD", mqttConfig.get("password"))
])
if sslEnabled:

@ -8,6 +8,7 @@
#include <freertos/FreeRTOS.h>
#include <freertos/queue.h>
#include <idf_additions.h>
#include <energyic_UART.h>
// Turn build flags (Macros) into strings
#define ST(A) #A
@ -40,39 +41,37 @@
char const *mqttPass = STR(TM_MQTT_PASSWD);
#endif
// include the cert if using SSL
#ifdef TM_MQTT_SSL
#include <transformerMonitorServerCert.h>
#endif
//********* GPIO PINS ************* //
// pins for UART
#define PIN_SerialATM_RX 16 //RX pin, CHANGE IT according to your board
#define PIN_SerialATM_TX 17 //TX pin, CHANGE IT according to your board
// GPIO pins where the DS18B20 sensors are connected
const int oilTempBus = 4;
const int cabinetTempBus = 9;
//******************************* //
void messageReceived(String &topic, String &payload);
WiFiClientSecure wifiClient;
PubSubClient mqttClient;
#include <energyic_UART.h>
HardwareSerial ATMSerial(1); //1 = just hardware serial number. ESP32 supports 3 hardware serials. UART 0 usually for flashing.
ATM90E26_UART eic(&ATMSerial);
// we are using the transformer's name to provide a unique ID
char* client_id = "name-of-transformer";
char* client_id = "al-xformer-592";
// GPIO pins where the DS18B20 sensors are connected
const int oilTempBus = 4;
const int cabinetTempBus = 9;
struct tempSensors {
DallasTemperature oil, cabinet;
};
@ -112,8 +111,7 @@ struct energyData {
struct xformerMonitorData {
unsigned short sysStatus, meterStatus;
double neutralCurrent, lineVoltage, phase;
float lineCurrent;
double lineCurrent, lineVoltage;
tm *timeInfo;
tempData temps;
powerData power;

@ -0,0 +1,9 @@
The MIT License (MIT)
Copyright (c) 2016 whatnick and Ryzee
Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.

@ -0,0 +1,8 @@
# ATM90E26 Energy Monitor Arduino Driver
Pre-built eval boards available via [Tindie](https://www.tindie.com/products/whatnick/atm90e26-breakout/) or [PCBWay](https://www.pcbway.com/project/gifts_detail/ATM90E26_Breakout.html)
This driver is for [ATM90E26 Single-phase Energy Monitor ASIC](https://www.microchip.com/wwwproducts/en/atm90e26). This library can be used with various hardware:
- [ATM90E26 Breakout Board](https://github.com/whatnick/ATM90E26_Breakout)
- [ATM90E26 Featherwing](https://github.com/whatnick/ATM90E26_Featherwing_KiCAD)
- [ATM90E26 DIN Rail Module](https://github.com/whatnick/din_meter_atm90e26)

@ -0,0 +1,29 @@
# Support for STM32F1xx
There are STM32F103 based boards available at very affordable price-point, commonly referred to as the [Bluepill](https://stm32-base.org/boards/STM32F103C8T6-Blue-Pill) as in the Matrix. The pin maps is available via [STM32Duino](https://github.com/stm32duino/Arduino_Core_STM32/blob/main/variants/STM32F1xx/F100C(8-B)T/variant_generic.h).
## SPI Mode
Using 1st bank of pins for SPI mode according to diagram [here](https://www.electronicshub.org/how-to-use-spi-in-stm32f103c8t6/).
SPI pins are in the table below
|Pin function| Pin Number|
|------------|-----------|
|MOSI | PA7 |
|MISO | PA6 |
|SCK | PA5 |
|CS | PA4 |
![Bluepill SPI Wiring](bluepill_spi.png)
## UART Mode
**NOTE** - Pin functions are reversed on the ATM90E26 Side
## Software Serial - TBD
|Pin function (STM32)| Pin Number|
|------------|-----------|
|RX | 10 |
|TX | 11 |
### Hardware Serial - Tested Working
|Pin function (STM32) | Pin Number |
|------------|-----------|
|RX | PB11 |
|TX | PB10 |

@ -0,0 +1,49 @@
# ATM90E26 Calibration hardware jig
## Equipment
The following pieces of equipment are recommended for accurate full range calibration of the ATM90E26.
- [Nichrome Wire Wound](https://eepower.com/resistor-guide/resistor-materials/wirewound-resistor/#) resistors with 100W power rating to be measured. These can be made into a resistor box for ease of use.
- [Variable Inductance](https://www.allaboutcircuits.com/textbook/experiments/chpt-4/variable-inductor/) to change circuit inductace and phase calibration.
- Large Purely Resistive Load other than the Nichrome resistors for 240V Power calibration, preferably a 100W+ Incandescent bulb or 1kW+ Heater.
- Large Inductive/Resistive Load for Power factor calibration, preferably a high powered fan or other motorized load such as a fridge.
- Small Inductive/Resistive Load for low end power factor calibration, preferably a compact fluorescent bulb.
- Reference Multimeter/Wattmeter for independent measurement of Current, Voltage, Power and Power Factor.
A sample jig can be seen [here](
https://twitter.com/MaxClerkwell/status/1315005293328297989?s=20)
## Calibration procedure
### Calibrating voltage gain
This is the easiest parameter to calibrate and requires the least equipments. The steps are:
- Setup default parameters and record voltage reported by ASIC and voltage reported by a multimeter with 0.1% accuracy at the AC bus.
- Apply scaling to the **UGain** parameter to account for any discprepancy according to this formula.
- `UGain_n = (Voltage Actual / Voltage Measured) * UGain_o` where `UGain_n` is the new Voltage gain and `UGain_o` is the old voltage gain.
### Calibrating current gain
The measurement of current in an energy monitor ASIC is the most unreliable piece since current is difficult to sample directly. We are obliged to use 1 of the 2 proxies for it.
- Magnetic field around the current carrying wire(s). Magnetic fields are typically sampled using Current Clamps or Rogowski Coils.
- Voltage drop across a thermally stable low resistance shunt in the path of the current.
The current calibration requires use of the reference resistors described in the materials section.
- Wire a 12V AC source in series with the reference resistor and an ammeter.
- Clamp the live side of the wiring with the CT being used with the ASIC and note the current measurements on the ASIC and the ammeter.
- Repeat the measurements with a few different reference Nicrome resistors, taking care not to exceed the power dissipation ratings of the resistors with heatsinks on. There are typically [4R, 8R and 10R](https://au.banggood.com/100W-Watt-Power-Metal-Shell-Case-Wirewound-Resistor-p-89494.html?ID=49543&cur_warehouse=CN) resistors in the calibration kit. With 1R resistors use 9V AC as input. The Voltage reference signal to the ASIC and current into the calibration resistors can come from separate transformers (ideally the same one is used).
- Once a few actual vs measured current values are collected use an equation similar to the **UGain** one to compute **IGain**.
- `IGain_n = (Current Actual / Current Measured) * IGain_o` where `IGain_n` is the new current gain and `IGain_o` is the old current gain.
- Update Checksum as appropriate using built in [library methods](./Calibration_Software.md)
### Calibrating power
If the voltage and current multipliers are set correctly in the above steps the power for unity power factor loads should not require any additional work.
### Calibrating power factor
This requires use of the variable inductor or a well known inductive load. Use the motorized load (fan/fridge) to calibrate the higher set points of the power factor and change the `Lphi` and `Nphi` default values. The library currently does not implement runtime change to these values they are hardcoded in the header file. If the purely resistive load shows unity power factor no phase angle calibrations are necessary.

@ -0,0 +1,8 @@
# Arduino Library Calibration functions
The [ATM90E26 Datasheet](http://ww1.microchip.com/downloads/en/DeviceDoc/Atmel-46002-SE-M90E26-Datasheet.pdf) has an extensive list of calibration registers. Of these the ones we are most interested in are:
- **Ugain** for Voltage gain
- **IgainL** for Live current line gain
These also affect the checksum2 stored in the device and have to be updated together. The library provides a `CalcCheckSum` function to help in evaluating the checksums the ASIC needs when the gain values are changed.

@ -0,0 +1,22 @@
# ATM90E26 Arduino Library and hardware usage
This documentation is designed to capture basics only. For detailed information on the ASIC please look at the [ATM90E26 Datasheet](http://ww1.microchip.com/downloads/en/DeviceDoc/Atmel-46002-SE-M90E26-Datasheet.pdf). As with all handwritten documentation, this documentation may lag behind the code. While all effort will be made to update the documentation and code simultaneously, please refer to the source as the point of truth when in doubt or when errors arise.
- Installing the library
- Various data reading modes
- UART Mode
- SPI Mode
- Calibration and usage in practice
- [Calibration Excel Sheet](./Energy%20setpoint%20calculator.xlsx)
- [Using calibrations in the library](./Calibration_Software.md)
- [Electrical Setup for Calibrations](./Calibration_Hardware.md)
- [Sample usage video for breakout](https://youtu.be/QOhXIIofPQk)
- [Sample usage video for featherwing](https://youtu.be/YI2-IAKHrNQ)
- Reference loads
- Thermal considerations
- Voltage Sensor Considerations
- Current Sensor Considerations
- [CT Article](https://learn.openenergymonitor.org/electricity-monitoring/ct-sensors/introduction)
- Commercial Calibration instruments from [Fluke](http://download.flukecal.com/pub/literature/1262701C_EN_w.pdf)

Binary file not shown.

After

Width:  |  Height:  |  Size: 553 KiB

File diff suppressed because it is too large Load Diff

After

Width:  |  Height:  |  Size: 579 KiB

@ -0,0 +1,41 @@
-15.00,0.13,194.94,-0.58
-15.00,0.13,194.99,-0.58
-15.00,0.13,194.88,-0.57
-15.00,0.13,194.77,-0.57
-15.00,0.13,194.79,-0.57
-15.00,0.13,194.77,-0.57
-15.00,0.13,194.85,-0.57
-15.00,0.13,194.31,-0.57
-15.00,0.13,194.42,-0.57
-15.00,0.13,194.50,-0.57
-15.00,0.13,194.82,-0.57
-15.00,0.13,194.74,-0.57
-15.00,0.13,194.80,-0.57
-15.00,0.13,194.64,-0.57
-15.00,0.13,194.79,-0.57
-15.00,0.13,194.81,-0.57
-15.00,0.13,194.80,-0.57
-15.00,0.13,194.92,-0.57
-15.00,0.13,194.73,-0.57
-15.00,0.13,194.85,-0.57
-15.00,0.13,194.18,-0.57
-15.00,0.13,194.07,-0.57
-15.00,0.13,194.12,-0.57
-15.00,0.13,193.91,-0.57
-15.00,0.13,193.92,-0.57
-15.00,0.13,194.08,-0.57
-15.00,0.13,194.18,-0.57
-15.00,0.13,194.11,-0.57
-15.00,0.13,194.15,-0.57
-15.00,0.13,194.01,-0.57
-15.00,0.13,194.23,-0.57
-15.00,0.13,194.18,-0.56
-15.00,0.13,194.26,-0.57
-15.00,0.13,194.96,-0.56
-15.00,0.13,194.83,-0.57
-15.00,0.13,195.05,-0.56
-15.00,0.13,194.75,-0.57
-15.00,0.13,194.93,-0.57
-15.00,0.13,194.95,-0.56
-15.00,0.13,194.82,-0.57
-15.00,0.13,194.84,-0.57

@ -0,0 +1,305 @@
/* ATM90E26 Energy Monitor Demo Application
The MIT License (MIT)
Copyright (c) 2016 whatnick and Ryzee
Permission is hereby granted, free of charge, to any person obtaining a copy of
this software and associated documentation files (the "Software"), to deal in
the Software without restriction, including without limitation the rights to
use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies
of the Software, and to permit persons to whom the Software is furnished to do
so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all
copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
SOFTWARE.
*/
#include "energyic_SPI.h"
#include <SPI.h>
ATM90E26_SPI::ATM90E26_SPI(int pin) {
_cs = pin;
metering[_plconsth] = 0x00B9;
metering[_plconstl] = 0xC1F3;
metering[_lgain] = 0x1D39;
metering[_lphi] = Lphi_Default;
metering[_ngain] = Ngain_Default;
metering[_nphi] = Nphi_Default;
metering[_pstartth] = PStartTh_Default;
metering[_pnolth] = PNolTh_Default;
metering[_qstartth] = QStartTh_Default;
metering[_qnolth] = QNolTh_Default;
metering[_mmode] = MMode_Default;
_crc1 = 0x4A34;
measurement[_ugain] = 0xD464;
measurement[_igain] = 0x6E49;
measurement[_igainn] = IgainN_Default;
measurement[_uoffset] = Uoffset_Default;
measurement[_ioffestl] = IoffsetL_Default;
measurement[_ioffsetn] = IoffsetN_Default;
measurement[_poffestl] = PoffsetL_Default;
measurement[_qoffsetl] = QoffsetL_Default;
measurement[_poffsetn] = PoffsetN_Default;
measurement[_qoffsetn] = QoffsetN_Default;
_crc2 = 0xD294;
}
void ATM90E26_SPI::SetLGain(unsigned short lgain) { metering[_lgain] = lgain; }
void ATM90E26_SPI::SetUGain(unsigned short ugain) {
measurement[_ugain] = ugain;
}
void ATM90E26_SPI::SetIGain(unsigned short igain) {
measurement[_igain] = igain;
}
unsigned short ATM90E26_SPI::CalcCheckSum(int checksum_id) {
//#CS1: metering
// L2C=MOD(H21+H22+...+H2B+L21+L22+...+L2B, 2^8)
// H2C=H21 XOR H22 XOR ... XOR H2B XOR L21 XOR L22 XOR ... XORL2
if (checksum_id == 1) {
unsigned char l2c = 0;
unsigned char h2c = 0;
for (int i = 0; i < 11; i++) {
l2c += metering[i];
l2c += metering[i] >> 8;
h2c ^= metering[i];
h2c ^= metering[i] >> 8;
}
return ((unsigned short)h2c << 8) | l2c;
}
//#CS2: measurement
// L3B=MOD(H31+H32+...+H3A+L31+L32+...+L3A, 2^8)
// H3B=H31 XOR H32 XOR ... XOR H3A XOR L31 XOR L32 XOR ... XORL3A
else if (checksum_id == 2) {
unsigned char l3b = 0;
unsigned char h3b = 0;
for (int i = 0; i < 10; i++) {
l3b += measurement[i];
l3b += measurement[i] >> 8;
h3b ^= measurement[i];
h3b ^= measurement[i] >> 8;
}
return ((unsigned short)h3b << 8) | l3b;
}
return 0;
}
unsigned short ATM90E26_SPI::CommEnergyIC(unsigned char RW,
unsigned char address,
unsigned short val) {
unsigned char *data = (unsigned char *)&val;
unsigned short output;
// SPI interface rate is 200 to 160k bps. It Will need to be slowed down for
// EnergyIC
#if !defined(ENERGIA) && !defined(ESP8266) && !defined(ARDUINO_ARCH_SAMD)
SPISettings settings(200000, MSBFIRST, SPI_MODE3);
#else
SPISettings settings(200000, MSBFIRST, SPI_MODE3);
#endif
// switch MSB and LSB of value
output = (val >> 8) | (val << 8);
val = output;
// Set read write flag
address |= RW << 7;
// Transmit and receive data
#if !defined(ENERGIA)
SPI.beginTransaction(settings);
#endif
// Disable LoRa chip on M0-LoRa
digitalWrite(8, HIGH);
digitalWrite(_cs, LOW);
delayMicroseconds(10);
SPI.transfer(address);
/* Must wait 4 us for data to become valid */
delayMicroseconds(4);
// Read data
// Do for each byte in transfer
if (RW) {
for (byte i = 0; i < 2; i++) {
*data = SPI.transfer(0x00);
data++;
}
// Transfer16 is not valid on Energia
// val = SPI.transfer16(0x00);
} else {
for (byte i = 0; i < 2; i++) {
SPI.transfer(*data); // write all the bytes
data++;
}
// Transfer16 is not valid on Energia
// SPI.transfer16(val);
}
digitalWrite(_cs, HIGH);
// Reenable LoRa chip on M0-LoRa
digitalWrite(8, LOW);
delayMicroseconds(10);
#if !defined(ENERGIA)
SPI.endTransaction();
#endif
output = (val >> 8) | (val << 8); // reverse MSB and LSB
return output;
// Use with transfer16
// return val;
}
double ATM90E26_SPI::GetLineVoltage() {
unsigned short voltage = CommEnergyIC(1, Urms, 0xFFFF);
return (double)voltage / 100;
}
unsigned short ATM90E26_SPI::GetMeterStatus() {
return CommEnergyIC(1, EnStatus, 0xFFFF);
}
double ATM90E26_SPI::GetLineCurrent() {
unsigned short current = CommEnergyIC(1, Irms, 0xFFFF);
return (double)current / 1000;
}
double ATM90E26_SPI::GetActivePower() {
short int apower = (short int)CommEnergyIC(
1, Pmean, 0xFFFF); // Complement, MSB is signed bit
return (double)apower;
}
double ATM90E26_SPI::GetReactivePower() {
short int apower = (short int)CommEnergyIC(
1, Qmean, 0xFFFF); // Complement, MSB is signed bit
return (double)apower;
}
double ATM90E26_SPI::GetApparentPower() {
short int apower = (short int)CommEnergyIC(
1, Smean, 0xFFFF); // Complement, MSB is signed bit
return (double)apower;
}
double ATM90E26_SPI::GetPhaseAngle() {
short int apower = (short int)CommEnergyIC(
1, Pangle, 0xFFFF); // Complement, MSB is signed bit
return (double)apower;
}
double ATM90E26_SPI::GetFrequency() {
unsigned short freq = CommEnergyIC(1, Freq, 0xFFFF);
return (double)freq / 100;
}
double ATM90E26_SPI::GetPowerFactor() {
short int pf = (short int)CommEnergyIC(1, PowerF, 0xFFFF); // MSB is signed
// bit
// if negative
if (pf & 0x8000) {
pf = (pf & 0x7FFF) * -1;
}
return (double)pf / 1000;
}
double ATM90E26_SPI::GetImportEnergy() {
// Register is cleared after reading
unsigned short ienergy = CommEnergyIC(1, APenergy, 0xFFFF);
return (double)ienergy *
0.0001; // returns kWh if PL constant set to 1000imp/kWh
}
double ATM90E26_SPI::GetExportEnergy() {
// Register is cleared after reading
unsigned short eenergy = CommEnergyIC(1, ANenergy, 0xFFFF);
return (double)eenergy *
0.0001; // returns kWh if PL constant set to 1000imp/kWh
}
unsigned short ATM90E26_SPI::GetSysStatus() {
return CommEnergyIC(1, SysStatus, 0xFFFF);
}
void ATM90E26_SPI::CalibrateEnergyIC() {
unsigned short systemstatus;
// Calculate checksums
_crc1 = CalcCheckSum(1);
_crc2 = CalcCheckSum(2);
// Set metering calibration values
CommEnergyIC(0, CalStart, 0x5678); // Metering calibration startup command.
// Register 21 to 2B need to be set
CommEnergyIC(0, PLconstH, metering[_plconsth]); // PL Constant MSB
CommEnergyIC(0, PLconstL, metering[_plconstl]); // PL Constant LSB
CommEnergyIC(0, Lgain, metering[_lgain]); // Line calibration gain
CommEnergyIC(0, CSOne, _crc1); // Write CSOne, as self calculated
Serial.print("Checksum 1:");
Serial.println(
CommEnergyIC(1, CSOne, 0x0000),
HEX); // Checksum 1. Needs to be calculated based off the above values.
// Set measurement calibration values
CommEnergyIC(
0, AdjStart,
0x5678); // Measurement calibration startup command, registers 31-3A
CommEnergyIC(0, Ugain, measurement[_ugain]); // Voltage rms gain
CommEnergyIC(0, IgainL, measurement[_igain]); // L line current gain
CommEnergyIC(0, CSTwo, _crc2); // Write CSTwo, as self calculated
Serial.print("Checksum 2:");
Serial.println(
CommEnergyIC(1, CSTwo, 0x0000),
HEX); // Checksum 2. Needs to be calculated based off the above values.
CommEnergyIC(0, CalStart, 0x8765); // Checks correctness of 21-2B registers
// and starts normal metering if ok
CommEnergyIC(0, AdjStart, 0x8765); // Checks correctness of 31-3A registers
// and starts normal measurement if ok
systemstatus = GetSysStatus();
if (systemstatus & 0xC000) {
// checksum 1 error
Serial.println("Checksum 1 Error!!");
}
if (systemstatus & 0x3000) {
// checksum 2 error
Serial.println("Checksum 2 Error!!");
}
}
void ATM90E26_SPI::InitEnergyIC() {
// pinMode(energy_IRQ,INPUT );
pinMode(_cs, OUTPUT);
digitalWrite(_cs, HIGH);
delay(10);
// pinMode(energy_WO,INPUT );
/* Enable SPI */
SPI.begin();
#if defined(ENERGIA)
SPI.setBitOrder(MSBFIRST);
SPI.setDataMode(SPI_MODE3);
SPI.setClockDivider(SPI_CLOCK_DIV16);
#endif
CommEnergyIC(0, SoftReset, 0x789A); // Perform soft reset
CommEnergyIC(0, FuncEn, 0x0030); // Voltage sag irq=1, report on warnout
// pin=1, energy dir change irq=0
CommEnergyIC(0, SagTh, 0x1F2F); // Voltage sag threshhold
CalibrateEnergyIC();
}

@ -0,0 +1,179 @@
/* ATM90E26 Energy Monitor Demo Application
The MIT License (MIT)
Copyright (c) 2016 whatnick and Ryzee
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all
copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
SOFTWARE.
*/
#ifndef __ATM90E26_SPI_H__
#define __ATM90E26_SPI_H__
#include <Arduino.h>
#define SoftReset 0x00 // Software Reset
#define SysStatus 0x01 // System Status
#define FuncEn 0x02 // Function Enable
#define SagTh 0x03 // Voltage Sag Threshold
#define SmallPMod 0x04 // Small-Power Mode
#define LastData 0x06 // Last Read/Write SPI/UART Value
#define LSB 0x08 // RMS/Power 16-bit LSB
#define CalStart 0x20 // Calibration Start Command
#define PLconstH 0x21 // High Word of PL_Constant
#define PLconstH_Default 0x0015
#define PLconstL 0x22 // Low Word of PL_Constant
#define PLconstL_Default 0xD174
#define Lgain 0x23 // L Line Calibration Gain
#define Lgain_Default 0x0000
#define Lphi 0x24 // L Line Calibration Angle
#define Lphi_Default 0x0000
#define Ngain 0x25 // N Line Calibration Gain
#define Ngain_Default 0x0000
#define Nphi 0x26 // N Line Calibration Angle
#define Nphi_Default 0x0000
#define PStartTh 0x27 // Active Startup Power Threshold
#define PStartTh_Default 0x08BD
#define PNolTh 0x28 // Active No-Load Power Threshold
#define PNolTh_Default 0x0000
#define QStartTh 0x29 // Reactive Startup Power Threshold
#define QStartTh_Default 0x0AEC
#define QNolTh 0x2A // Reactive No-Load Power Threshold
#define QNolTh_Default 0x0000
#define MMode 0x2B // Metering Mode Configuration
#define MMode_Default 0x9422
#define CSOne 0x2C // Checksum 1
#define AdjStart 0x30 // Measurement Calibration Start Command
#define Ugain 0x31 // Voltage rms Gain
#define Ugain_Default 0x6720
#define IgainL 0x32 // L Line Current rms Gain
#define IgainL_Default 0x7A13
#define IgainN 0x33 // N Line Current rms Gain
#define IgainN_Default 0x7530
#define Uoffset 0x34 // Voltage Offset
#define Uoffset_Default 0x0000
#define IoffsetL 0x35 // L Line Current Offset
#define IoffsetL_Default 0x0000
#define IoffsetN 0x36 // N Line Current Offse
#define IoffsetN_Default 0x0000
#define PoffsetL 0x37 // L Line Active Power Offset
#define PoffsetL_Default 0x0000
#define QoffsetL 0x38 // L Line Reactive Power Offset
#define QoffsetL_Default 0x0000
#define PoffsetN 0x39 // N Line Active Power Offset
#define PoffsetN_Default 0x0000
#define QoffsetN 0x3A // N Line Reactive Power Offset
#define QoffsetN_Default 0x0000
#define CSTwo 0x3B // Checksum 2
#define APenergy 0x40 // Forward Active Energy
#define ANenergy 0x41 // Reverse Active Energy
#define ATenergy 0x42 // Absolute Active Energy
#define RPenergy 0x43 // Forward (Inductive) Reactive Energy
#define Rnenerg 0x44 // Reverse (Capacitive) Reactive Energy
#define Rtenergy 0x45 // Absolute Reactive Energy
#define EnStatus 0x46 // Metering Status
#define Irms 0x48 // L Line Current rms
#define Urms 0x49 // Voltage rms
#define Pmean 0x4A // L Line Mean Active Power
#define Qmean 0x4B // L Line Mean Reactive Power
#define Freq 0x4C // Voltage Frequency
#define PowerF 0x4D // L Line Power Factor
#define Pangle 0x4E // Phase Angle between Voltage and L Line Current
#define Smean 0x4F // L Line Mean Apparent Power
#define IrmsTwo 0x68 // N Line Current rms
#define PmeanTwo 0x6A // N Line Mean Active Power
#define QmeanTwo 0x6B // N Line Mean Reactive Power
#define PowerFTwo 0x6D // N Line Power Factor
#define PangleTwo 0x6E // Phase Angle between Voltage and N Line Current
#define SmeanTwo 0x6F // N Line Mean Apparent Power
// pins used for the connection with the sensor
// the other you need are controlled by the SPI library):
// const int energy_IRQ = 2;
#if defined(ARDUINO_ESP8266_WEMOS_D1MINI) // WeMos mini and D1 R2
const int energy_CS = D8; // WEMOS SS pin
#elif defined(ARDUINO_ESP8266_ESP12) // Adafruit Huzzah
const int energy_CS = 15; // HUZZAH SS pins ( 0 or 15)
#elif defined(ARDUINO_ARCH_SAMD) // M0 board
const int energy_CS = 10; // M0 SS pin
#elif defined(__AVR_ATmega32U4__) // 32u4 board
const int energy_CS = 10; // 32u4 SS pin
#else
const int energy_CS = SS; // Use default SS pin for unknown Arduino
#endif // defined(ARDUINO_ESP8266_WEMOS_D1MINI)
class ATM90E26_SPI {
public:
ATM90E26_SPI(int pin = energy_CS);
double GetLineVoltage();
double GetLineCurrent();
double GetActivePower();
double GetReactivePower();
double GetApparentPower();
double GetPhaseAngle();
double GetFrequency();
double GetPowerFactor();
double GetImportEnergy();
double GetExportEnergy();
void SetUGain(unsigned short);
void SetLGain(unsigned short);
void SetIGain(unsigned short);
void InitEnergyIC();
void CalibrateEnergyIC();
unsigned short GetSysStatus();
unsigned short GetMeterStatus();
private:
unsigned short CommEnergyIC(unsigned char RW, unsigned char address,
unsigned short val);
unsigned short CalcCheckSum(int checksum_id);
int _cs;
unsigned short metering[11];
enum metering_values {
_plconsth,
_plconstl,
_lgain,
_lphi,
_ngain,
_nphi,
_pstartth,
_pnolth,
_qstartth,
_qnolth,
_mmode
};
unsigned short _crc1;
unsigned short measurement[10];
enum measurement_values {
_ugain,
_igain,
_igainn,
_uoffset,
_ioffestl,
_ioffsetn,
_poffestl,
_qoffsetl,
_poffsetn,
_qoffsetn
};
unsigned short _crc2;
};
#endif

@ -0,0 +1,203 @@
/* ATM90E26 Energy Monitor Demo Application
The MIT License (MIT)
Copyright (c) 2016 whatnick and Ryzee
Permission is hereby granted, free of charge, to any person obtaining a copy of
this software and associated documentation files (the "Software"), to deal in
the Software without restriction, including without limitation the rights to
use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies
of the Software, and to permit persons to whom the Software is furnished to do
so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all
copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
SOFTWARE.
*/
#include <energyic_UART.h>
ATM90E26_UART::ATM90E26_UART(Stream *UART) { ATM_UART = UART; }
unsigned short ATM90E26_UART::CommEnergyIC(unsigned char RW,
unsigned char address,
unsigned short val) {
unsigned short output;
// Set read write flag
address |= RW << 7;
byte host_chksum = address;
if (!RW) {
unsigned short chksum_short = (val >> 8) + (val & 0xFF) + address;
host_chksum = chksum_short & 0xFF;
}
// Clear out any data left in the buffer so it does not interfere later
ATM_UART->read();
// begin UART command
ATM_UART->write(0xFE);
ATM_UART->write(address);
if (!RW) {
byte MSBWrite = val >> 8;
byte LSBWrite = val & 0xFF;
ATM_UART->write(MSBWrite);
ATM_UART->write(LSBWrite);
}
ATM_UART->write(host_chksum);
#if defined(ESP32)
delay(40); // Somehow, Arduino framework for ESP32 needs this delay
#else
delay(10);
#endif
// Read register only
if (RW) {
byte MSByte = ATM_UART->read();
byte LSByte = ATM_UART->read();
byte atm90_chksum = ATM_UART->read();
if (atm90_chksum == ((LSByte + MSByte) & 0xFF)) {
output = (MSByte << 8) | LSByte; // join MSB and LSB;
return output;
}
Serial.println("Read failed");
delay(20); // Delay from failed transaction
return 0xFFFF;
}
// Write register only
else {
byte atm90_chksum = ATM_UART->read();
if (atm90_chksum != host_chksum) {
Serial.println("Write failed");
delay(20); // Delay from failed transaction
}
}
return 0xFFFF;
}
double ATM90E26_UART::GetLineVoltage() {
unsigned short voltage = CommEnergyIC(1, Urms, 0xFFFF);
return (double)voltage / 100;
}
unsigned short ATM90E26_UART::GetMeterStatus() {
return CommEnergyIC(1, EnStatus, 0xFFFF);
}
double ATM90E26_UART::GetLineCurrent() {
unsigned short current = CommEnergyIC(1, Irms, 0xFFFF);
return (double)current / 1000;
}
double ATM90E26_UART::GetActivePower() {
short int apower = (short int)CommEnergyIC(
1, Pmean, 0xFFFF); // Complement, MSB is signed bit
return (double)apower;
}
double ATM90E26_UART::GetFrequency() {
unsigned short freq = CommEnergyIC(1, Freq, 0xFFFF);
return (double)freq / 100;
}
double ATM90E26_UART::GetPowerFactor() {
short int pf = (short int)CommEnergyIC(1, PowerF, 0xFFFF); // MSB is signed
// bit
// if negative
if (pf & 0x8000) {
pf = (pf & 0x7FFF) * -1;
}
return (double)pf / 1000;
}
double ATM90E26_UART::GetImportEnergy() {
// Register is cleared after reading
unsigned short ienergy = CommEnergyIC(1, APenergy, 0xFFFF);
return (double)ienergy *
0.0001; // returns kWh if PL constant set to 1000imp/kWh
}
double ATM90E26_UART::GetExportEnergy() {
// Register is cleared after reading
unsigned short eenergy = CommEnergyIC(1, ANenergy, 0xFFFF);
return (double)eenergy *
0.0001; // returns kWh if PL constant set to 1000imp/kWh
}
unsigned short ATM90E26_UART::GetSysStatus() {
return CommEnergyIC(1, SysStatus, 0xFFFF);
}
/*
Initialise Energy IC, assume UART has already began in the main code
*/
void ATM90E26_UART::InitEnergyIC() {
unsigned short systemstatus;
CommEnergyIC(0, SoftReset, 0x789A); // Perform soft reset
CommEnergyIC(0, FuncEn, 0x0030); // Voltage sag irq=1, report on warnout
// pin=1, energy dir change irq=0
CommEnergyIC(0, SagTh, 0x1F2F); // Voltage sag threshhold
// Set metering calibration values
CommEnergyIC(0, CalStart, 0x5678); // Metering calibration startup command.
// Register 21 to 2B need to be set
CommEnergyIC(0, PLconstH, 0x00B9); // PL Constant MSB
CommEnergyIC(0, PLconstL, 0xC1F3); // PL Constant LSB
CommEnergyIC(0, Lgain, 0x1D39); // Line calibration gain
CommEnergyIC(0, Lphi, 0x0000); // Line calibration angle
CommEnergyIC(0, PStartTh, 0x08BD); // Active Startup Power Threshold
CommEnergyIC(0, PNolTh, 0x0000); // Active No-Load Power Threshold
CommEnergyIC(0, QStartTh, 0x0AEC); // Reactive Startup Power Threshold
CommEnergyIC(0, QNolTh, 0x0000); // Reactive No-Load Power Threshold
CommEnergyIC(0, MMode, 0x9422); // Metering Mode Configuration. All defaults.
// See pg 31 of datasheet.
CommEnergyIC(0, CSOne, 0x4A34); // Write CSOne, as self calculated
Serial.print("Checksum 1:");
Serial.println(
CommEnergyIC(1, CSOne, 0x0000),
HEX); // Checksum 1. Needs to be calculated based off the above values.
// Set measurement calibration values
CommEnergyIC(
0, AdjStart,
0x5678); // Measurement calibration startup command, registers 31-3A
CommEnergyIC(0, Ugain, 0xD464); // Voltage rms gain
CommEnergyIC(0, IgainL, 0x6E49); // L line current gain
CommEnergyIC(0, Uoffset, 0x0000); // Voltage offset
CommEnergyIC(0, IoffsetL, 0x0000); // L line current offset
CommEnergyIC(0, PoffsetL, 0x0000); // L line active power offset
CommEnergyIC(0, QoffsetL, 0x0000); // L line reactive power offset
CommEnergyIC(0, CSTwo, 0xD294); // Write CSTwo, as self calculated
Serial.print("Checksum 2:");
Serial.println(
CommEnergyIC(1, CSTwo, 0x0000),
HEX); // Checksum 2. Needs to be calculated based off the above values.
CommEnergyIC(0, CalStart, 0x8765); // Checks correctness of 21-2B registers
// and starts normal metering if ok
CommEnergyIC(0, AdjStart, 0x8765); // Checks correctness of 31-3A registers
// and starts normal measurement if ok
systemstatus = GetSysStatus();
if (systemstatus & 0xC000) {
// checksum 1 error
Serial.println("Checksum 1 Error!!");
}
if (systemstatus & 0x3000) {
// checksum 2 error
Serial.println("Checksum 2 Error!!");
}
}

@ -0,0 +1,105 @@
/* ATM90E26 Energy Monitor Demo Application
The MIT License (MIT)
Copyright (c) 2016 whatnick and Ryzee
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all
copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
SOFTWARE.
*/
#ifndef __ATM90E26_UART_H__
#define __ATM90E26_UART_H__
#include <Arduino.h>
#define SoftReset 0x00 // Software Reset
#define SysStatus 0x01 // System Status
#define FuncEn 0x02 // Function Enable
#define SagTh 0x03 // Voltage Sag Threshold
#define SmallPMod 0x04 // Small-Power Mode
#define LastData 0x06 // Last Read/Write SPI/UART Value
#define LSB 0x08 // RMS/Power 16-bit LSB
#define CalStart 0x20 // Calibration Start Command
#define PLconstH 0x21 // High Word of PL_Constant
#define PLconstL 0x22 // Low Word of PL_Constant
#define Lgain 0x23 // L Line Calibration Gain
#define Lphi 0x24 // L Line Calibration Angle
#define Ngain 0x25 // N Line Calibration Gain
#define Nphi 0x26 // N Line Calibration Angle
#define PStartTh 0x27 // Active Startup Power Threshold
#define PNolTh 0x28 // Active No-Load Power Threshold
#define QStartTh 0x29 // Reactive Startup Power Threshold
#define QNolTh 0x2A // Reactive No-Load Power Threshold
#define MMode 0x2B // Metering Mode Configuration
#define CSOne 0x2C // Checksum 1
#define AdjStart 0x30 // Measurement Calibration Start Command
#define Ugain 0x31 // Voltage rms Gain
#define IgainL 0x32 // L Line Current rms Gain
#define IgainN 0x33 // N Line Current rms Gain
#define Uoffset 0x34 // Voltage Offset
#define IoffsetL 0x35 // L Line Current Offset
#define IoffsetN 0x36 // N Line Current Offse
#define PoffsetL 0x37 // L Line Active Power Offset
#define QoffsetL 0x38 // L Line Reactive Power Offset
#define PoffsetN 0x39 // N Line Active Power Offset
#define QoffsetN 0x3A // N Line Reactive Power Offset
#define CSTwo 0x3B // Checksum 2
#define APenergy 0x40 // Forward Active Energy
#define ANenergy 0x41 // Reverse Active Energy
#define ATenergy 0x42 // Absolute Active Energy
#define RPenergy 0x43 // Forward (Inductive) Reactive Energy
#define Rnenerg 0x44 // Reverse (Capacitive) Reactive Energy
#define Rtenergy 0x45 // Absolute Reactive Energy
#define EnStatus 0x46 // Metering Status
#define Irms 0x48 // L Line Current rms
#define Urms 0x49 // Voltage rms
#define Pmean 0x4A // L Line Mean Active Power
#define Qmean 0x4B // L Line Mean Reactive Power
#define Freq 0x4C // Voltage Frequency
#define PowerF 0x4D // L Line Power Factor
#define Pangle 0x4E // Phase Angle between Voltage and L Line Current
#define Smean 0x4F // L Line Mean Apparent Power
#define IrmsTwo 0x68 // N Line Current rms
#define PmeanTwo 0x6A // N Line Mean Active Power
#define QmeanTwo 0x6B // N Line Mean Reactive Power
#define PowerFTwo 0x6D // N Line Power Factor
#define PangleTwo 0x6E // Phase Angle between Voltage and N Line Current
#define SmeanTwo 0x6F // N Line Mean Apparent Power
class ATM90E26_UART {
public:
ATM90E26_UART(Stream *UART);
double GetLineVoltage();
double GetLineCurrent();
double GetActivePower();
double GetFrequency();
double GetPowerFactor();
double GetImportEnergy();
double GetExportEnergy();
void InitEnergyIC();
unsigned short GetSysStatus();
unsigned short GetMeterStatus();
private:
unsigned short CommEnergyIC(unsigned char RW, unsigned char address,
unsigned short val);
Stream *ATM_UART;
};
#endif

@ -0,0 +1,290 @@
/*
* This sketch sends ATM90E26 Energy Monitor data via HTTP POST request to thingspeak server.
* It needs the following libraries to work (besides the esp8266 standard libraries supplied with the IDE):
*
* - https://github.com/whatnick/ATM90E26_Arduino
* - https://github.com/adafruit/Adafruit_SSD1306
* - https://github.com/adafruit/Adafruit_GFX
* - https://github.com/bblanchon/ArduinoJson
* - https://github.com/tzapu/WiFiManager
*
* designed to run directly on Adafruit Feather Huzzah, to where it can be uploaded using this marvelous piece of software:
*
* https://github.com/esp8266/Arduino
*
* 2017 Tisham Dhar
* licensed under MIT
*/
#include <FS.h> //this needs to be first, or it all crashes and burns..
#include <ESP8266WiFi.h>
#include <DNSServer.h> //Local DNS Server used for redirecting all requests to the configuration portal
#include <ESP8266WebServer.h> //Local WebServer used to serve the configuration portal
#include <WiFiManager.h> //https://github.com/tzapu/WiFiManager WiFi Configuration Magic
#include <ArduinoJson.h> //https://github.com/bblanchon/ArduinoJson
//flag for saving data
bool shouldSaveConfig = false;
#include <Wire.h>
#include <energyic_SPI.h>
#include <Adafruit_GFX.h>
#include <Adafruit_SSD1306.h>
#define OLED_RESET 16
Adafruit_SSD1306 display(OLED_RESET);
#if (SSD1306_LCDHEIGHT != 32)
#error("Height incorrect, please fix Adafruit_SSD1306.h!");
#endif
#ifdef ESP8266
#include <pgmspace.h>
#else
#include <avr/pgmspace.h>
#endif
char server[50] = "api.thingspeak.com";
// Sign up on thingspeak and get WRITE API KEY.
char auth[36] = "THINGSPEAK_KEY";
WiFiClient client;
ATM90E26_SPI eic1;
ATM90E26_SPI eic2(0);
//callback notifying us of the need to save config
void saveConfigCallback () {
Serial.println("Should save config");
shouldSaveConfig = true;
}
void readTSConfig()
{
//clean FS, for testing
//SPIFFS.format();
//read configuration from FS json
//Serial.println("mounting FS...");
if (SPIFFS.begin()) {
//Serial.println("mounted file system");
if (SPIFFS.exists("/config.json")) {
//file exists, reading and loading
//Serial.println("reading config file");
File configFile = SPIFFS.open("/config.json", "r");
if (configFile) {
//Serial.println("opened config file");
size_t size = configFile.size();
// Allocate a buffer to store contents of the file.
std::unique_ptr<char[]> buf(new char[size]);
configFile.readBytes(buf.get(), size);
DynamicJsonBuffer jsonBuffer;
JsonObject& json = jsonBuffer.parseObject(buf.get());
json.printTo(Serial);
if (json.success()) {
//Serial.println("\nparsed json");
strcpy(auth, json["auth"]);
strcpy(server, json["server"]);
} else {
//Serial.println("failed to load json config");
}
}
}
} else {
//Serial.println("failed to mount FS");
}
//end read
}
void saveTSConfig()
{
//save the custom parameters to FS
if (shouldSaveConfig) {
//Serial.println("saving config");
DynamicJsonBuffer jsonBuffer;
JsonObject& json = jsonBuffer.createObject();
json["auth"] = auth;
json["server"] = server;
File configFile = SPIFFS.open("/config.json", "w");
if (!configFile) {
//Serial.println("failed to open config file for writing");
}
json.printTo(Serial);
json.printTo(configFile);
configFile.close();
//end save
}
}
void setup() {
Serial.begin(115200);
Wire.begin();
display.begin(SSD1306_SWITCHCAPVCC, 0x3C); // initialize with the I2C addr 0x3C (for the 128x32)
// init done
// Clear the buffer.
display.clearDisplay();
display.display();
display.setTextSize(1);
display.setTextColor(WHITE);
//Read previous config
readTSConfig();
// The extra parameters to be configured (can be either global or just in the setup)
// After connecting, parameter.getValue() will get you the configured value
// id/name placeholder/prompt default length
WiFiManagerParameter custom_ts_token("ts", "Thingspeak Key", auth, 33);
WiFiManagerParameter custom_server("serv", "Server", server, 50);
//Use wifi manager to get config
WiFiManager wifiManager;
wifiManager.setDebugOutput(false);
//set config save notify callback
wifiManager.setSaveConfigCallback(saveConfigCallback);
//add all your parameters here
wifiManager.addParameter(&custom_ts_token);
wifiManager.addParameter(&custom_server);
display.setCursor(0,0);
display.println("Connecting to Wifi ");
display.display();
//first parameter is name of access point, second is the password
wifiManager.autoConnect("EnergyMonitor", "whatnick");
//if you get here you have connected to the WiFi
Serial.println("connected...yeey :)");
Serial.print("Key:");
Serial.println(auth);
Serial.print("Server:");
Serial.println(server);
display.println("Wifi Connected!!");
display.display();
//read updated parameters
strcpy(auth, custom_ts_token.getValue());
strcpy(server, custom_server.getValue());
saveTSConfig();
Serial.print("Start ATM90");
eic1.InitEnergyIC();
eic2.InitEnergyIC();
delay(1000);
}
void loop() {
/*Repeatedly fetch some values from the ATM90E26 */
unsigned short s_status = eic1.GetSysStatus();
if(s_status == 0xFFFF)
{
#if defined(ESP8266)
//Read failed reset ESP, this is heavy
ESP.restart();
#endif
}
s_status = eic2.GetSysStatus();
if(s_status == 0xFFFF)
{
#if defined(ESP8266)
//Read failed reset ESP, this is heavy
ESP.restart();
#endif
}
float Vrms1 = eic1.GetLineVoltage();
float Crms1 = eic1.GetLineCurrent();
float realPower1 = eic1.GetActivePower();
float powerFactor1 = eic1.GetPowerFactor();
float Vrms2 = eic2.GetLineVoltage();
float Crms2 = eic2.GetLineCurrent();
float realPower2 = eic2.GetActivePower();
float powerFactor2 = eic2.GetPowerFactor();
Serial.print(realPower1);
Serial.print(",");
Serial.print(Crms1);
Serial.print(",");
Serial.print(Vrms1);
Serial.print(",");
Serial.print(powerFactor1);
Serial.print(realPower2);
Serial.print(",");
Serial.print(Crms2);
Serial.print(",");
Serial.print(Vrms2);
Serial.print(",");
Serial.println(powerFactor2);
if (client.connect(server,80)) { // "184.106.153.149" or api.thingspeak.com
String postStr = String(auth);
postStr +="&field1=";
postStr += String(Vrms1);
postStr +="&field2=";
postStr += String(realPower1);
postStr +="&field3=";
postStr += String(Crms1);
postStr +="&field4=";
postStr += String(powerFactor1);
postStr +="&field5=";
postStr += String(Vrms2);
postStr +="&field6=";
postStr += String(realPower2);
postStr +="&field7=";
postStr += String(Crms2);
postStr +="&field8=";
postStr += String(powerFactor2);
postStr += "\r\n\r\n";
client.print("POST /update HTTP/1.1\n");
client.print("Host: api.thingspeak.com\n");
client.print("Connection: close\n");
client.print("X-THINGSPEAKAPIKEY: "+String(auth)+"\n");
client.print("Content-Type: application/x-www-form-urlencoded\n");
client.print("Content-Length: ");
client.print(postStr.length());
client.print("\n\n");
client.print(postStr);
}
client.stop();
display.clearDisplay();
display.setCursor(0,0);
display.print("Vrms: ");
display.print(Vrms1);
display.print(",");
display.println(Vrms2);
display.print("Irms: ");
display.print(Crms1);
display.print(",");
display.println(Crms2);
display.print("Power: ");
display.print(realPower1);
display.print(",");
display.println(realPower2);
display.print("p.f.: ");
display.print(powerFactor1);
display.print(",");
display.println(powerFactor2);
display.display();
delay(2000);
//Clear display to prevent burn in
display.clearDisplay();
display.display();
delay(14000);
}

@ -0,0 +1,55 @@
/* ATM90E26 Energy Monitor Demo Application
The MIT License (MIT)
Copyright (c) 2016 whatnick and Ryzee
Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
*/
// the sensor communicates using SPI, so include the library:
#include <SPI.h>
/*******************
* WEMOS SPI Pins:
* SCLK - D5
* MISO - D6
* MOSI - D7
* SS - D8
*******************/
#include "energyic_SPI.h"
ATM90E26_SPI eic;
void setup() {
/* Initialize the serial port to host */
Serial.begin(115200);
/*Initialise the ATM90E26 + SPI port */
eic.InitEnergyIC();
}
void loop() {
/*Repeatedly fetch some values from the ATM90E26 */
Serial.print("Sys Status:");
Serial.println(eic.GetSysStatus(),HEX);
yield();
Serial.print("Meter Status:");
Serial.println(eic.GetMeterStatus(),HEX);
yield();
Serial.print("Voltage:");
Serial.println(eic.GetLineVoltage());
yield();
Serial.print("Current:");
Serial.println(eic.GetLineCurrent());
yield();
Serial.print("Active power:");
Serial.println(eic.GetActivePower());
yield();
Serial.print("p.f.:");
Serial.println(eic.GetPowerFactor());
delay(1000);
}

@ -0,0 +1,104 @@
#include <energyic_UART.h>
#if !defined(ARDUINO_ARCH_SAMD) && !defined(ESP32)
#include <SoftwareSerial.h>
#else
#endif
#if defined(ESP8266)
//NOTE: Version 1.0 and 1.1 of featherwing use pins 14,12
//version 1.2 and above using pins 13,14
//SoftwareSerial ATMSerial(14, 12, false, 256); //RX, TX v1.0-1.1
//SoftwareSerial ATMSerial(13, 14, false, 256); //RX, TX v1.2+
SoftwareSerial ATMSerial(D4, D3, false, 256); //NodeMCU v1.0
#endif
#ifdef __AVR_ATmega32U4__ //32u4 board
SoftwareSerial ATMSerial(11, 13); //RX, TX
#endif
#if defined(STM32F1)//Bluepill board
//SoftwareSerial ATMSerial(PA10, PA11); // RX, TX
HardwareSerial ATMSerial(USART3); // PB11 (RX), PB10 (TX)
#endif
#if defined(ARDUINO_ARCH_SAMD)
#include "wiring_private.h" // pinPeripheral() function
//Feather M0
#define PIN_SerialATM_RX 12ul
#define PIN_SerialATM_TX 11ul
#define PAD_SerialATM_RX (SERCOM_RX_PAD_3)
#define PAD_SerialATM_TX (UART_TX_PAD_0)
// Using SERCOM1 on M0 to communicate with ATM90E26
Uart ATMSerial(&sercom1, PIN_SerialATM_RX, PIN_SerialATM_TX, PAD_SerialATM_RX, PAD_SerialATM_TX);
#endif
#if defined(ESP32)
#define PIN_SerialATM_RX 19 //RX pin, CHANGE IT according to your board
#define PIN_SerialATM_TX 23 //TX pin, CHANGE IT according to your board
HardwareSerial ATMSerial(1); //1 = just hardware serial number. ESP32 supports 3 hardware serials. UART 0 usually for flashing.
#endif
ATM90E26_UART eic(&ATMSerial);
void setup() {
Serial.begin(115200);
Serial.println("\nATM90E26 UART Test Started");
#if defined(ARDUINO_ARCH_SAMD)
pinPeripheral(PIN_SerialATM_RX, PIO_SERCOM);
pinPeripheral(PIN_SerialATM_TX, PIO_SERCOM);
#endif
#if defined(ESP32)
//Must begin ATMSerial before IC init supplying baud rate, serial config, and RX TX pins
ATMSerial.begin(9600, SERIAL_8N1, PIN_SerialATM_RX, PIN_SerialATM_TX);
#else
//Must begin ATMSerial before IC init
ATMSerial.begin(9600);
#endif
eic.InitEnergyIC();
delay(1000);
}
void loop() {
/*Repeatedly fetch some values from the ATM90E26 */
Serial.print("Sys Status:");
unsigned short s_status = eic.GetSysStatus();
if(s_status == 0xFFFF)
{
#if defined(ESP8266)
//Read failed reset ESP, this is heavy
ESP.restart();
#endif
}
Serial.println(eic.GetSysStatus(),HEX);
delay(10);
Serial.print("Meter Status:");
Serial.println(eic.GetMeterStatus(),HEX);
delay(10);
Serial.print("Voltage:");
#if defined(ESP32)
//ESP32 or maybe another MCU support formatting float/double value
Serial.printf("%.4f V\n", eic.GetLineVoltage());
#else
Serial.println(eic.GetLineVoltage());
#endif
delay(10);
Serial.print("Current:");
#if defined(ESP32)
//ESP32 or maybe another MCU support formatting float/double value
Serial.printf("%.4f A\n", eic.GetLineCurrent());
#else
Serial.println(eic.GetLineCurrent());
#endif
delay(10);
Serial.print("Active power:");
Serial.println(eic.GetActivePower());
delay(10);
Serial.print("p.f.:");
Serial.println(eic.GetPowerFactor());
delay(1000);
}

@ -0,0 +1,9 @@
name=ATM90E26 Arduino
version=0.1
author=Tisham (whatnick) Dhar
maintainer=Tisham <tisham@whatnick.com>
sentence=ATM90E26 Energy Monitor Support for Arduino
paragraph=ATM90E26 Energy Monitor Support for Arduino
category=Sensors
architectures=avr,esp32,esp8266,stm32
url=https://github.com/whatnick/ATM90E26_Arduino

@ -9,7 +9,7 @@ HardwareSerial ATMSerial(1); //1 = just hardware serial number. ESP32 sup
ATM90E26_UART eic(&ATMSerial);
void setup() {
Serial.begin(115200);
Serial.begin(9600);
while (!Serial){}
Serial.println("\nATM90E26 UART Test Started");
@ -36,7 +36,7 @@ void loop() {
while (1);
}
Serial.println(eic.GetSysStatus(),HEX);
Serial.println(eic.GetSysStatus());
delay(10);
Serial.print("Meter Status:");
Serial.println(eic.GetMeterStatus(),HEX);

@ -152,11 +152,12 @@ void loop()
xQueueReceive(eicDataQueue, &mqttSensorData, portMAX_DELAY);
char timeBuffer[32];
strftime(timeBuffer, sizeof(timeBuffer), "%FT%TZ", mqttSensorData.timeInfo);
// Sensor is not working
if (mqttSensorData.sysStatus == 6555 || mqttSensorData.sysStatus == 0)
if (mqttSensorData.sysStatus == 0xFFFF)
{
// Sensor is not working - set LED red
setLEDColor(255,0,0);
} else {
// Sensor is working - set LED green
setLEDColor(0,255,0);
}
@ -167,13 +168,12 @@ void loop()
mqttJsonData["sysStatus"] = mqttSensorData.sysStatus;
mqttJsonData["current"] = mqttSensorData.lineCurrent;
mqttJsonData["neutralCurrent"] = mqttSensorData.neutralCurrent;
mqttJsonData["voltage"] = mqttSensorData.lineCurrent;
powerObj["active"] = mqttSensorData.power.active;
powerObj["apparent"] = mqttSensorData.power.apparent;
powerObj["factor"] = mqttSensorData.power.factor;
powerObj["reactive"] = mqttSensorData.power.reactive;
tempObj["oil"] = mqttSensorData.temps.oil;
tempObj["cabinet"] = mqttSensorData.temps.cabinet;

Loading…
Cancel
Save