diff --git a/NTCWiFiS/BoardCFG.h b/NTCWiFiS/BoardCFG.h index 8d2e029..3d94906 100644 --- a/NTCWiFiS/BoardCFG.h +++ b/NTCWiFiS/BoardCFG.h @@ -1,3 +1,5 @@ + + #define DEBUG_DISABLED 0 #define DEBUG_ENABLED 1 #define DEBUG_MODE DEBUG_ENABLED @@ -15,7 +17,8 @@ #define NTC4_Pin ADC1_CH0 #define PS1_Pin ADC1_CH5 #define PS2_Pin ADC1_CH4 - +#define VREF_Pin 0 +#define PWR_Pin 1 #define ADC_pin ADC1_CH5 #define SA0_Pin 27 /* OUTPUT */ @@ -23,3 +26,25 @@ #define SA2_Pin 22 /* OUTPUT */ #define UART_Debug Serial +#define UART1 Serial1 + +#define NTC_SR_OC /*NTC open circuit*/ +#define NTC_SR_DRDY /*NTC Data ready*/ +typedef struct +{ + int ADC_Raw; /*ADC raw value*/ + float ADC_Value; /*ADC Value after 50Hz notch filter*/ + float Resistance; /*Resistance (Ohm unit)*/ + float Temperature_C; /*Temperature value in C*/ + uint8_t SR; /*Status register*/ +} NTC_Typedef; +typedef struct +{ + int ADC_Raw; /*ADC raw value*/ + float ADC_Value; /*ADC Value after 50Hz notch filter*/ + float Resistance; + float Voltage; /*Voltage (mV)*/ + float Current; /*Current (mA)*/ + float Pressure; /*Pressure in Bar*/ + uint8_t SR; /*Status register*/ +} PS_Typedef; diff --git a/NTCWiFiS/Crc16.cpp b/NTCWiFiS/Crc16.cpp new file mode 100644 index 0000000..1731b01 --- /dev/null +++ b/NTCWiFiS/Crc16.cpp @@ -0,0 +1,66 @@ +/* + * Crc16.c + * + * Created on: 2 thg 8, 2021 + * Author: iFactory + */ +#include "Crc16.h" + +uint16_t ifacCRC::crc16_str(char *ptr, uint8_t len) +{ + uint16_t crc =CRC16_START; + while(len--) + { + crc = crc16_byte(crc , *ptr++); + } + return crc; +} +uint16_t ifacCRC::crc16_byte(uint16_t crcValue, uint8_t newByte) +{ + unsigned char i; + + for (i = 0; i < 8; i++) { + + if (((crcValue & 0x8000) >> 8) ^ (newByte & 0x80)){ + crcValue = (crcValue << 1) ^ POLYNOM; + }else{ + crcValue = (crcValue << 1); + } + + newByte <<= 1; + } + + return crcValue; +} +/** + * @brief Calculate CRC16 Modbus. + * @note Polynomial calculations 0x8005. + * @param uc_pBuffer pointer buffer to check CRC. + * @retval ul_Length Length of string is needs checking. + */ +uint16_t ifacCRC::CRC16_Modbus(uint8_t *uc_pBuffer, uint16_t ul_Length) +{ + uint8_t Luc_Index_Buff; + uint8_t Luc_Index_Bit; + uint16_t Lus_Tmp_Bit; + uint8_t Luc_Tmp_Val; + uint16_t Lul_CRC_Val; + /* Initialize value for Crc16 Modbus */ + Lul_CRC_Val = 0xFFFF; + + for (Luc_Index_Buff = 0; Luc_Index_Buff < ul_Length; Luc_Index_Buff++) + { + Luc_Tmp_Val = (uint8_t)*uc_pBuffer++; + Lul_CRC_Val ^= Luc_Tmp_Val; + for (Luc_Index_Bit = 0; Luc_Index_Bit < 8; Luc_Index_Bit++ ) + { + Lus_Tmp_Bit = Lul_CRC_Val & 0x0001; + Lul_CRC_Val >>= 1; + if ( Lus_Tmp_Bit != 0 ) + { + Lul_CRC_Val ^= 0xA001; + } + } + } + return Lul_CRC_Val; +} diff --git a/NTCWiFiS/Crc16.h b/NTCWiFiS/Crc16.h new file mode 100644 index 0000000..57c1a2c --- /dev/null +++ b/NTCWiFiS/Crc16.h @@ -0,0 +1,35 @@ +/* + * Crc16.h + * + * Created on: 2 thg 8, 2021 + * Author: iFactory + */ + +#ifndef INC_CRC16_H_ +#define INC_CRC16_H_ +#include + +#define CRC16_START 0xFFFF +#define CRC16_DNP 0x3D65 // DNP, IEC 870, M-BUS, wM-BUS, ... +#define CRC16_CCITT 0x1021 // X.25, V.41, HDLC FCS, Bluetooth, ... + + +#define CRC16_IBM 0x8005 // ModBus, USB, Bisync, CRC-16, CRC-16-ANSI, ... +#define CRC16_T10_DIF 0x8BB7 // SCSI DIF +#define CRC16_DECT 0x0589 // Cordeless Telephones +#define CRC16_ARINC 0xA02B // ACARS Aplications + +#define POLYNOM CRC16_CCITT // Define the used polynom from one of the aboves + +class ifacCRC +{ + public: + uint16_t CRC16_Modbus(uint8_t *uc_pBuffer, uint16_t ul_Length); + + private: + uint16_t crc16_str(char *ptr, uint8_t len); + uint16_t crc16_byte(uint16_t crcValue, uint8_t newByte); +}; + + +#endif /* INC_CRC16_H_ */ diff --git a/NTCWiFiS/MCP3208.cpp b/NTCWiFiS/MCP3208.cpp new file mode 100644 index 0000000..19b43e0 --- /dev/null +++ b/NTCWiFiS/MCP3208.cpp @@ -0,0 +1,133 @@ +/***************************************************************************//** + * @file AD7793.c + * @brief Implementation of AD7793 Driver. + * @author Bancisor MIhai +******************************************************************************** + * Copyright 2012(c) Analog Devices, Inc. + * + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * - Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * - Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * - Neither the name of Analog Devices, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * - The use of this software may or may not infringe the patent rights + * of one or more patent holders. This license does not release you + * from the requirement that you obtain separate licenses from these + * patent holders to use this software. + * - Use of the software either in source or binary form, must be run + * on or directly connected to an Analog Devices Inc. component. + * + * THIS SOFTWARE IS PROVIDED BY ANALOG DEVICES "AS IS" AND ANY EXPRESS OR + * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, NON-INFRINGEMENT, + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. + * IN NO EVENT SHALL ANALOG DEVICES BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT + * LIMITED TO, INTELLECTUAL PROPERTY RIGHTS, PROCUREMENT OF SUBSTITUTE GOODS OR + * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + * +******************************************************************************** + * SVN Revision: 500 +*******************************************************************************/ + +/******************************************************************************/ +/* Include Files */ +/******************************************************************************/ +#include "MCP3208.h" + +iMCP3208::iMCP3208(uint8_t csPin, uint32_t spiFrequency) +{ + _cs = csPin; + //Should be MODE3 + spiSettings = SPISettings(spiFrequency,MSBFIRST,SPI_MODE3); +} + +iMCP3208::iMCP3208(uint8_t sckPin, uint8_t misoPin, uint8_t mosiPin,uint8_t csPin, uint32_t spiFrequency) +{ + _cs = csPin; + _sck = sckPin; + _miso = misoPin; + _mosi = mosiPin; + //Should be MODE3 + spiSettings = SPISettings(spiFrequency,MSBFIRST,SPI_MODE3); +} + +void iMCP3208::begin() +{ + /* Initialize CS pin and set high level */ + pinMode(_cs, OUTPUT); + digitalWrite(_cs,HIGH); + + SPI.begin(_sck,_miso,_mosi,_cs); + SPI.beginTransaction(spiSettings); + /* Must waiting about 500us before accessing any of the on-chip registers. */ + delayMicroseconds(500); +} +uint16_t iMCP3208::read(iMCP3208_CH ch) +{ + uint16_t retVal; + uint8_t pByte1 = 0, pByte2 = 0; + uint8_t rByte1, rbyte2; + pByte1 = (ch>>2)|0x04; + pByte2 = ch<<6; + digitalWrite(_cs, LOW); + spiWriteByte(pByte1); + rByte1 = spiByteTransfer(pByte2); + rbyte2 = spiByteTransfer(0xFF); + digitalWrite(_cs, HIGH); + delayMicroseconds(1); + retVal = ((uint16_t)(rByte1&0x0F)<<8)|(uint16_t)rbyte2; + return retVal; +} +void iMCP3208::spiWriteByte(unsigned char oneByte) +{ + SPI.transfer(oneByte); +} + +void iMCP3208::spiWriteByte(unsigned char *nByte, uint8_t size) +{ + SPI.transfer(nByte,size); +} + +uint8_t iMCP3208::spiReadByte() +{ + uint8_t retByte; + digitalWrite(_cs, LOW); + // Send a dumy byte + retByte = SPI.transfer(0xFF); + digitalWrite(_cs, HIGH); + + return retByte; +} +uint8_t iMCP3208::spiByteTransfer(unsigned char oneByte) +{ + uint8_t retByte; + // Send a dumy byte + retByte = SPI.transfer(oneByte); + return retByte; +} + + +uint8_t iMCP3208::spiReadByte(uint8_t *retData, uint8_t numByte) +{ + uint8_t retByte; + digitalWrite(_cs, LOW); + for(int i=0; i +#include + +/******************************************************************************/ +/* MCP3208 */ +/******************************************************************************/ +enum iMCP3208_CH { + SINGLE_0 = 0b1000, /**< single channel 0 */ + SINGLE_1 = 0b1001, /**< single channel 1 */ + SINGLE_2 = 0b1010, /**< single channel 2 */ + SINGLE_3 = 0b1011, /**< single channel 3 */ + SINGLE_4 = 0b1100, /**< single channel 4 */ + SINGLE_5 = 0b1101, /**< single channel 5 */ + SINGLE_6 = 0b1110, /**< single channel 6 */ + SINGLE_7 = 0b1111, /**< single channel 7 */ + DIFF_0PN = 0b0000, /**< differential channel 0 (input 0+,1-) */ + DIFF_0NP = 0b0001, /**< differential channel 0 (input 0-,1+) */ + DIFF_1PN = 0b0010, /**< differential channel 1 (input 2+,3-) */ + DIFF_1NP = 0b0011, /**< differential channel 1 (input 2-,3+) */ + DIFF_2PN = 0b0100, /**< differential channel 2 (input 4+,5-) */ + DIFF_2NP = 0b0101, /**< differential channel 2 (input 5-,5+) */ + DIFF_3PN = 0b0110, /**< differential channel 3 (input 6+,7-) */ + DIFF_3NP = 0b0111 /**< differential channel 3 (input 6-,7+) */ +}; + +/******************************************************************************/ +/* Functions Prototypes */ +/******************************************************************************/ + +class iMCP3208 +{ + + public: + iMCP3208(uint8_t csPin, uint32_t spiFrequency); + iMCP3208(uint8_t sckPin, uint8_t misoPin, uint8_t mosiPin,uint8_t csPin, uint32_t spiFrequency); + void begin(); + uint16_t read(iMCP3208_CH ch); + + private: + void spiWriteByte(uint8_t oneByte); + void spiWriteByte(unsigned char *nByte, uint8_t size); + uint8_t spiReadByte(); + uint8_t spiReadByte(uint8_t *retData, uint8_t numByte); + uint8_t spiByteTransfer(unsigned char oneByte); + + + /* SPI define Pin hardware */ + uint8_t _mosi; + uint8_t _miso; + uint8_t _sck; + uint8_t _cs; + + uint8_t currentCh; + float vRef; + + SPISettings spiSettings; + + uint16_t modeReg; //holds value for 16 bit mode register + uint16_t confReg; //holds value for 16 bit configuration register + + bool isSnglConvMode; + + const uint16_t convTimeout = 480; // This should be set based on update rate eventually + +}; +#endif // _AD7793_H_ diff --git a/NTCWiFiS/NTCWiFiS.ino b/NTCWiFiS/NTCWiFiS.ino index 8e936f6..b6b91b8 100644 --- a/NTCWiFiS/NTCWiFiS.ino +++ b/NTCWiFiS/NTCWiFiS.ino @@ -1,41 +1,190 @@ extern "C"{ #include "circular_buffer.h" } + #include "BoardCFG.h" +#include "MCP3208.h" +#include "Crc16.h" + +#include +#include +#include +#include +#include + +#define NSS 26 +#define FLASH_MEMORY_SIZE 512 + /*ADC Variables*/ -uint16_t ADC_Value; /*ADC value Read from ADC_pin ( analog mltiplexer)*/ -uint16_t NTC1_ADC_Val; /*NTC1 ADC value Read from NTC1_Pin or analog mltiplexer (ouput SB2 = 0, SB1 = 0, SB0 = 0) */ -uint16_t NTC2_ADC_Val; /*NTC2 ADC value Read from NTC2_Pin or analog mltiplexer (ouput SB2 = 0, SB1 = 0, SB0 = 1) */ -uint16_t NTC3_ADC_Val; /*NTC3 ADC value Read from NTC3_Pin or analog mltiplexer (ouput SB2 = 0, SB1 = 1, SB0 = 0) */ -uint16_t NTC4_ADC_Val; /*NTC4 ADC value Read from NTC4_Pin or analog mltiplexer (ouput SB2 = 0, SB1 = 1, SB0 = 1) */ -uint16_t PS1_ADC_Val; /*PS1 ADC value Read from PS1_Pin or analog mltiplexer (ouput SB2 = 1, SB1 = 0, SB0 = 0) */ -uint16_t PS2_ADC_Val; /*PS2 ADC value Read from PS2_Pin or analog mltiplexer (ouput SB2 = 1, SB1 = 0, SB0 = 1) */ -uint16_t VREF_ADC_Val; /*VREF ADC value Read from analog mltiplexer (ouput SB2 = 1, SB1 = 1, SB0 = 1) */ -float NTC1, NTC2, NTC3, NTC4, PS1, PS2, I1, I2; - - -/***************/ +static const int spiClk = 1000000; /*SPI clock 1 MHz*/ +iMCP3208 ADCi(14,12,13,NSS,spiClk); +const float _Vref = 3300; /*Vref mV*/ +const float _ADC_MAX = 4095; /* ADC 12bit */ +const float _R1 = 10000.0; +const float _R25 = 100000.0; +const float _R50 = 35899.9; +const float _R100 = 6710.0; +const float _R150 = 1770.0; +const float _R300 = 105.6; + +const float BETA25_50 = 3948.06; +const float BETA50_100 = 4044.69; +const float BETA100_150 = 4208.37; +const float BETA150_300 = 4504.0; + +const float Comfilter = 0.999; + +NTC_Typedef NTC1; +NTC_Typedef NTC2; +NTC_Typedef NTC3; +NTC_Typedef NTC4; + +PS_Typedef PS1; +PS_Typedef PS2; + +float TC_K_Temperature; +uint32_t smps,c_smps; +uint32_t micro; +/********************************************************************************/ +/*CRC Variables*/ +ifacCRC CRC; +uint16_t CRC16_Val; +/********************************************************************************/ +/*ESP NOW Variables*/ +esp_now_peer_info_t peerInfo; +uint8_t Broadcast_MAC[]={0xFF,0xFF,0xFF,0xFF,0xFF,0xFF}; +uint8_t Master_MAC[]={0x24,0x62,0xAB,0xE4,0x06,0x20}; +uint8_t MAC_Dest[]={0x24,0x00,0x00,0x00,0x00,0x00}; + +const uint8_t outcomData_maxlen=250; +uint8_t outcomData[outcomData_maxlen]; +uint8_t incomData[250]; +uint8_t ESPNOW_Data_Received; +uint8_t ESPNOW_Data_len; +uint8_t MACS_Received = 0; +/********************************************************************************/ +/*UART Variables*/ +CIRC_BUFF_INIT(Uart_Circ_Buff1, 2047); +uint8_t uart_rx1; +uint8_t Uart_Receive_Cmd_Buff1[255],Uart_Receive_Cmd_Buff_Index1; +uint8_t Uart_buff_cmd_status1; +uint8_t Uart_rx1,Uart_Start_Frame_Flag1; +uint8_t lucaEndByte1[2] = {'\r','\n'}; +uint8_t lucCountEndByte1 = 0; +uint8_t Luc_Ret1; +/********************************************************************************/ +void InitESPNow(void); +void ADC_InitValue(void); +float map_value(float x, float in_min, float in_max, float out_min, float out_max); + void ADC_Process(void * parameter) { vTaskDelay(1000 / portTICK_PERIOD_MS); /*Delay 1000ms*/ UART_Debug.printf("ADC_Process is running on CPU %d\n", xPortGetCoreID()); for(;;) { - NTC1_ADC_Val = analogRead(NTC1_Pin); - NTC2_ADC_Val = analogRead(NTC2_Pin); - NTC3_ADC_Val = analogRead(NTC3_Pin); - NTC4_ADC_Val = analogRead(NTC4_Pin); - PS1_ADC_Val = analogRead(PS1_Pin); - PS1_ADC_Val = analogRead(PS2_Pin); -// vTaskDelay(1000 / portTICK_PERIOD_MS); /*Delay 1000ms*/ + NTC1.ADC_Raw = ADCi.read(SINGLE_7); + NTC1.ADC_Value = Comfilter*NTC1.ADC_Value + (1-Comfilter)*NTC1.ADC_Raw; + NTC1.Resistance =((float)(NTC1.ADC_Value)*_ADC_MAX*_R1)/(_ADC_MAX*(_ADC_MAX-(float)NTC1.ADC_Value)); + NTC1.Temperature_C = R_To_Temperature(NTC1.Resistance); + + NTC2.ADC_Raw = ADCi.read(SINGLE_6); + NTC2.ADC_Value = Comfilter*NTC2.ADC_Value + (1-Comfilter)*NTC2.ADC_Raw; + NTC2.Resistance =((float)(NTC2.ADC_Value)*_ADC_MAX*_R1)/(_ADC_MAX*(_ADC_MAX-(float)NTC2.ADC_Value)); + NTC2.Temperature_C = R_To_Temperature(NTC2.Resistance); + + NTC3.ADC_Raw = ADCi.read(SINGLE_5); + NTC3.ADC_Value = Comfilter*NTC3.ADC_Value + (1-Comfilter)*NTC3.ADC_Raw; + NTC3.Resistance =((float)(NTC3.ADC_Value)*_ADC_MAX*_R1)/(_ADC_MAX*(_ADC_MAX-(float)NTC3.ADC_Value)); + NTC3.Temperature_C = R_To_Temperature(NTC3.Resistance); + + NTC4.ADC_Raw = ADCi.read(SINGLE_4); + NTC4.ADC_Value = Comfilter*NTC4.ADC_Value + (1-Comfilter)*NTC4.ADC_Raw; + NTC4.Resistance =((float)(NTC4.ADC_Value)*_ADC_MAX*_R1)/(_ADC_MAX*(_ADC_MAX-(float)NTC4.ADC_Value)); + NTC4.Temperature_C = R_To_Temperature(NTC4.Resistance); + + PS1.ADC_Raw = ADCi.read(SINGLE_0); + PS1.ADC_Value = Comfilter*PS1.ADC_Value + (1-Comfilter)*PS1.ADC_Raw; + PS1.Voltage = PS1.ADC_Value*_Vref/_ADC_MAX; + PS1.Current = PS1.Voltage / PS1.Resistance; + + PS2.ADC_Raw = ADCi.read(SINGLE_1); + PS2.ADC_Value = Comfilter*PS2.ADC_Value + (1-Comfilter)*PS2.ADC_Raw; + PS2.Voltage = PS2.ADC_Value*_Vref/_ADC_MAX; + PS2.Current = PS2.Voltage / PS2.Resistance; + + TC_K_Temperature = map_value(PS1.Current,4.0,20.0,0,800); + c_smps++; + if(millis() - micro >= 1000) + { + micro = millis(); + smps = c_smps; + c_smps = 0; + } + +// vTaskDelay(1 / portTICK_PERIOD_MS); /*Delay 1000ms*/ } } +void OnDataSent(const uint8_t *mac_addr, esp_now_send_status_t status) { + char macStr[18]; + snprintf(macStr, sizeof(macStr), "%02x:%02x:%02x:%02x:%02x:%02x", + mac_addr[0], mac_addr[1], mac_addr[2], mac_addr[3], mac_addr[4], mac_addr[5]); +// Serial.print("Last Packet Sent to: "); Serial.println(macStr); +// Serial.print("Last Packet Send Status: "); Serial.println(status == ESP_NOW_SEND_SUCCESS ? "Delivery Success" : "Delivery Fail"); +} +void data_receive(const uint8_t * mac, const uint8_t *incomingData, int len) +{ + memset(&incomData[0],0,250); + memcpy(&incomData[0],incomingData,len); + ESPNOW_Data_len = len; + ESPNOW_Data_Received = 1; + if(incomData[0]=='M' && incomData[1]=='A' && incomData[2]=='C'&& incomData[3]=='D'&& incomData[4]==':') + { + memcpy(MAC_Dest,&incomData[5],6); + EEPROM.write(0,MAC_Dest[0]); + EEPROM.write(1,MAC_Dest[1]); + EEPROM.write(2,MAC_Dest[2]); + EEPROM.write(3,MAC_Dest[3]); + EEPROM.write(4,MAC_Dest[4]); + EEPROM.write(5,MAC_Dest[5]); + EEPROM.commit(); + MACS_Received = 1; + } +} void setup() { // put your setup code here, to run once: UART_Debug.begin(115200); - delay(500); - UART_Debug.println("Hello World"); + UART1.begin(115200, SERIAL_8N1,33,32); + delay(1000); + UART_Debug.println("Initialize UART_debug: UART0 115200 8N1"); + UART_Debug.println(WiFi.macAddress()); UART_Debug.printf("Setup is running on CPU %d\n", xPortGetCoreID()); + + EEPROM.begin(FLASH_MEMORY_SIZE); + MAC_Dest[0] = EEPROM.readByte(0); + MAC_Dest[1] = EEPROM.readByte(1); + MAC_Dest[2] = EEPROM.readByte(2); + MAC_Dest[3] = EEPROM.readByte(3); + MAC_Dest[4] = EEPROM.readByte(4); + MAC_Dest[5] = EEPROM.readByte(5); + + + ADCi.begin(); + esp_wifi_set_ps(WIFI_PS_NONE); /* No power save */ + PS1.Resistance = 150.0; + PS2.Resistance = 150.0; + + InitESPNow(); + esp_now_register_send_cb(OnDataSent); + esp_now_register_recv_cb(data_receive); + memcpy(peerInfo.peer_addr, MAC_Dest, 6); + peerInfo.channel = 1; + peerInfo.encrypt = false; + if (esp_now_add_peer(&peerInfo) != ESP_OK){ + UART_Debug.println("Failed to add peer"); + return; + } + ADC_InitValue(); xTaskCreatePinnedToCore( ADC_Process, "ADC_Process", // Task name @@ -45,12 +194,251 @@ void setup() { NULL, // Task handle 1 // CPU ID ); - + xTaskCreatePinnedToCore( + Serial_Process, + "Serial_Process", // Task name + 5000, // Stack size (bytes) + NULL, // Parameter + 1, // Task priority + NULL, // Task handle + 1 // CPU ID + ); } void loop() { // put your main code here, to run repeatedly: -// UART_Debug.printf("NTC %f\n",NTC1,NTC2,NTC3,NTC4); - vTaskDelay(100 / portTICK_PERIOD_MS); + static uint32_t tick_espnow = 0; + if(millis() - tick_espnow >= 1000) + { + memset(outcomData,0,outcomData_maxlen); + sprintf((char*)outcomData,"04NTCPS: %08.2f %08.2f %08.2f %08.2f %08.4f %08.4f %08.2f ",NTC1.Temperature_C,NTC2.Temperature_C + ,NTC3.Temperature_C,NTC4.Temperature_C,PS1.Current,PS2.Current,TC_K_Temperature); + uint16_t len_tmp = strlen((char*)outcomData); + CRC16_Val = CRC.CRC16_Modbus(outcomData,len_tmp); + sprintf((char*)&outcomData[len_tmp],"%05d\r\n",CRC16_Val); + UART_Debug.println((char*)outcomData); + esp_err_t result = esp_now_send(MAC_Dest, (uint8_t *) &outcomData[0], strlen((char*)outcomData)); + if (result != ESP_OK) + { + UART_Debug.print("Send Status: "); + if (result == ESP_ERR_ESPNOW_NOT_INIT) { + // How did we get so far!! + UART_Debug.println("ESPNOW not Init."); + } else if (result == ESP_ERR_ESPNOW_ARG) { + UART_Debug.println("Invalid Argument"); + } else if (result == ESP_ERR_ESPNOW_INTERNAL) { + UART_Debug.println("Internal Error"); + } else if (result == ESP_ERR_ESPNOW_NO_MEM) { + UART_Debug.println("ESP_ERR_ESPNOW_NO_MEM"); + } else if (result == ESP_ERR_ESPNOW_NOT_FOUND) { + UART_Debug.println("Peer not found."); + } else { + UART_Debug.println("Not sure what happened"); + } + } + tick_espnow = millis(); + } +// UART_Debug.printf("ADC = %d %d\n",NTC1.ADC_Raw,(int)NTC1.ADC_Value); + UART_Debug.printf("T = %f %f %f %f %f\n", NTC1.Temperature_C, NTC2.Temperature_C, NTC3.Temperature_C, NTC4.Temperature_C, TC_K_Temperature); +// UART_Debug.printf("ADC = %f %f %f %f\n",PS1.Voltage,PS1.Current,PS2.Voltage,PS2.Current ); + vTaskDelay(100 / portTICK_PERIOD_MS); /*Delay 1000ms*/ +} + +float map_value(float x, float in_min, float in_max, float out_min, float out_max) +{ + return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min; +} +float R_To_Temperature(float Resistance) +{ + float Tb,Rb,Beta; + float retVal; + if(Resistance <= _R150) /*150 300*/ + { + Tb = 150; + Rb = _R150; + Beta = BETA150_300; + } + else if(Resistance <= _R100) /*100 150*/ + { + Tb = 100; + Rb = _R100; + Beta = BETA100_150; + } + else if(Resistance <= _R50) /*50 100*/ + { + Tb = 50; + Rb = _R50; + Beta = BETA50_100; + } + else if(Resistance <= _R25) /*25 50*/ + { + Tb = 25; + Rb = _R25; + Beta = BETA25_50; + } + else if(Resistance > _R25) /*25 50*/ + { + Tb = 25; + Rb = _R25; + Beta = BETA25_50; + } + retVal = (Beta*(273.15 + Tb))/(Beta+((273.15+ Tb)*log(Resistance/Rb)))-273.15; + return retVal; +} +void InitESPNow(void) +{ + WiFi.mode(WIFI_STA); + WiFi.disconnect(); + if (esp_now_init() == ESP_OK) { + UART_Debug.println("ESPNow Init Success"); + } + else { + UART_Debug.println("ESPNow Init Failed"); + // Retry InitESPNow, add a counte and then restart? + // InitESPNow(); + // or Simply Restart + ESP.restart(); + } + esp_wifi_set_channel(1,WIFI_SECOND_CHAN_NONE); +} + +void Process_Data_Serial1(void) +{ + if (strstr((char*)Uart_Receive_Cmd_Buff1,"R FF 00000000") != NULL) + { + + } +} +void Serial_Process(void * parameter) +{ + // ARTISAN_WS_Serial.print("//Serial_Process running on core "); + // ARTISAN_WS_Serial.println(xPortGetCoreID()); + for(;;) + { + /*****************Receive uart and push to circular buffer******************/ + if(UART1.available()) + { + uart_rx1 = UART1.read(); + Circ_Buff_Push(&Uart_Circ_Buff1, uart_rx1); + } + /***************************************************************************/ + /*******************Process data form circular buffer***********************/ + Luc_Ret1 = 0; + Uart_buff_cmd_status1 = Circ_Buff_Pop(&Uart_Circ_Buff1,&Uart_rx1); + while(Uart_buff_cmd_status1 != CIRC_BUFF_EMPTY) + { + /* Check start byte */ + if(Uart_rx1 == '>') + { + memset(Uart_Receive_Cmd_Buff1, '\0', 255); + Uart_Start_Frame_Flag1 = 1; + Uart_Receive_Cmd_Buff_Index1 = 0; + } + else + { + /* No action */ + } + /* Get valid byte cmd and check frame */ + if((Uart_Start_Frame_Flag1 == 1) && (Uart_rx1 != '>')) + { + /* Check end byte and flush */ + if(Uart_rx1 == lucaEndByte1[lucCountEndByte1]) + { + lucCountEndByte1++; + } + /* Check 2 byte lien tiep */ + else if(lucCountEndByte1 == 1) + { + /* Reset counter end byte */ + lucCountEndByte1 = 0; + } + else + { + + } + + /* Get valid byte cmd into buff */ + Uart_Receive_Cmd_Buff1[Uart_Receive_Cmd_Buff_Index1] = Uart_rx1; + Uart_Receive_Cmd_Buff_Index1++; + + /* Check out of range of buffer */ + if(Uart_Receive_Cmd_Buff_Index1 >= 255) + { + Uart_Receive_Cmd_Buff_Index1 = 0; + Uart_Start_Frame_Flag1 = 0; + Luc_Ret1 = 0; + } + + /* Check enough 2 byte end and stop frame data */ + if(lucCountEndByte1 == 2) + { + /* Clear 2 end byte of frame received data */ + memset(Uart_Receive_Cmd_Buff1 + Uart_Receive_Cmd_Buff_Index1 - lucCountEndByte1, '\0', lucCountEndByte1); + + Uart_Start_Frame_Flag1 = 0; + Uart_Receive_Cmd_Buff_Index1 = 0; + Luc_Ret1 = 1; + + /* Break out loop */ + Uart_buff_cmd_status1 = CIRC_BUFF_EMPTY; + /* Reset counter end byte */ + lucCountEndByte1 = 0; + } + else + { + /* No action */ + } + } + else + { + /* No action */ + } + + /* Check empty condition break-out loop above */ + if(Uart_buff_cmd_status1 != CIRC_BUFF_EMPTY) + { + Uart_buff_cmd_status1 = Circ_Buff_Pop(&Uart_Circ_Buff1, &Uart_rx1); + } + } + if(Luc_Ret1 == 1) + { + /*Received buffer cmd successfully*/ + Process_Data_Serial1(); + } + } +} +void ADC_InitValue(void) +{ + NTC1.ADC_Raw = ADCi.read(SINGLE_7); + NTC1.ADC_Value = NTC1.ADC_Raw; + NTC1.Resistance =((float)(NTC1.ADC_Value)*_ADC_MAX*_R1)/(_ADC_MAX*(_ADC_MAX-(float)NTC1.ADC_Value)); + NTC1.Temperature_C = R_To_Temperature(NTC1.Resistance); + + NTC2.ADC_Raw = ADCi.read(SINGLE_6); + NTC2.ADC_Value = NTC2.ADC_Raw; + NTC2.Resistance =((float)(NTC2.ADC_Value)*_ADC_MAX*_R1)/(_ADC_MAX*(_ADC_MAX-(float)NTC2.ADC_Value)); + NTC2.Temperature_C = R_To_Temperature(NTC2.Resistance); + + NTC3.ADC_Raw = ADCi.read(SINGLE_5); + NTC3.ADC_Value = NTC3.ADC_Raw; + NTC3.Resistance =((float)(NTC3.ADC_Value)*_ADC_MAX*_R1)/(_ADC_MAX*(_ADC_MAX-(float)NTC3.ADC_Value)); + NTC3.Temperature_C = R_To_Temperature(NTC3.Resistance); + + NTC4.ADC_Raw = ADCi.read(SINGLE_4); + NTC4.ADC_Value = NTC4.ADC_Raw; + NTC4.Resistance =((float)(NTC4.ADC_Value)*_ADC_MAX*_R1)/(_ADC_MAX*(_ADC_MAX-(float)NTC4.ADC_Value)); + NTC4.Temperature_C = R_To_Temperature(NTC4.Resistance); + + PS1.ADC_Raw = ADCi.read(SINGLE_0); + PS1.ADC_Value = PS1.ADC_Raw; + PS1.Voltage = PS1.ADC_Value*_Vref/_ADC_MAX; + PS1.Current = PS1.Voltage / PS1.Resistance; + + PS2.ADC_Raw = ADCi.read(SINGLE_1); + PS2.ADC_Value = PS2.ADC_Raw; + PS2.Voltage = PS2.ADC_Value*_Vref/_ADC_MAX; + PS2.Current = PS2.Voltage / PS2.Resistance; + + TC_K_Temperature = map_value(PS1.Current,4.0,20.0,0,800); } diff --git a/NTCWiFiS/NTCWiFiS.ino.esp32.bin b/NTCWiFiS/NTCWiFiS.ino.esp32.bin new file mode 100644 index 0000000..84ff1f5 Binary files /dev/null and b/NTCWiFiS/NTCWiFiS.ino.esp32.bin differ