mirror of
https://github.com/dalathegreat/Battery-Emulator.git
synced 2025-10-03 17:59:27 +02:00
Improve RTU handling
This commit is contained in:
parent
2f7e5fb1fa
commit
9c694058cb
9 changed files with 819 additions and 822 deletions
|
@ -33,18 +33,22 @@ long LB_Wh_Remaining = 0; //Amount of energy in battery, in Wh
|
|||
int LB_GIDS = 0;
|
||||
int LB_MAX = 0;
|
||||
int LB_Max_GIDS = 273; //Startup in 24kWh mode
|
||||
int LB_Current = 0; //Current in kW going in/out of battery
|
||||
int LB_Total_Voltage = 0; //Battery voltage (0-450V)
|
||||
int16_t LB_Current = 0; //Current in kW going in/out of battery
|
||||
int LB_Total_Voltage = 370; //Battery voltage (0-450V)
|
||||
|
||||
// global Modbus memory registers
|
||||
const int intervalModbusTask = 10000; //Interval at which to refresh modbus registers
|
||||
const int intervalModbusTask = 4800; //Interval at which to refresh modbus registers
|
||||
unsigned long previousMillisModbus = 0; //will store last time a modbus register refresh
|
||||
uint16_t mbPV[30000]; // process variable memory: produced by sensors, etc., cyclic read by PLC via modbus TCP
|
||||
// ModbusRTU Server
|
||||
#define MB_RTU_NUM_VALUES 30000
|
||||
//#define MB_RTU_DIVICE_ID 21
|
||||
uint16_t mbPV[MB_RTU_NUM_VALUES]; // process variable memory: produced by sensors, etc., cyclic read by PLC via modbus TCP
|
||||
|
||||
uint16_t capacity_Wh_startup = BATTERY_WH_MAX;
|
||||
uint16_t MaxPower = 40960; //41kW TODO, fetch from LEAF battery (or does it matter, polled after startup?)
|
||||
uint16_t MaxVoltage = 4672; //(467.2V), if higher charging is not possible (goes into forced discharge)
|
||||
uint16_t MinVoltage = 3200; //Min Voltage (320.0V), if lower Gen24 disables battery
|
||||
uint16_t Status = 3; //ACTIVE - [0..5]<>[STANDBY,INACTIVE,DARKSTART,ACTIVE,FAULT,UPDATING]
|
||||
|
||||
uint16_t SOC = 5000; //SOC 0-100.00% //Updates later on from CAN
|
||||
uint16_t capacity_Wh = BATTERY_WH_MAX; //Updates later on from CAN
|
||||
uint16_t remaining_capacity_Wh = BATTERY_WH_MAX; //Updates later on from CAN
|
||||
|
@ -53,34 +57,8 @@ uint16_t max_target_charge_power = 4312;
|
|||
//4.3kW (during charge), both 307&308 can be set (>0) at the same time //Updates later on from CAN
|
||||
uint16_t TemperatureMax = 50; //Todo, read from LEAF pack, uint not ok
|
||||
uint16_t TemperatureMin = 60; //Todo, read from LEAF pack, uint not ok
|
||||
|
||||
// Store the data into the array
|
||||
//16-bit int in these modbus-register, two letters at a time. Example p101[1]....(ascii for S) * 256 + (ascii for I) = 21321
|
||||
//uint16_t p101_data[] = {21321, 1, 16985, 17408, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16985, 17408, 16993, 29812, 25970, 31021, 17007, 30720, 20594, 25965, 26997, 27904, 18518, 0, 0, 0, 13614, 12288, 0, 0, 0, 0, 0, 0, 13102, 12598, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0};
|
||||
//Delete the following lines once we know this works :)
|
||||
uint16_t p101_data[] = {21321, 1}; //SI
|
||||
uint16_t p103_data[] = {16985, 17408, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; //BY D
|
||||
uint16_t p119_data[] = {
|
||||
16985, 17440, 16993, 29812, 25970, 31021, 17007, 30752, 20594, 25965, 26997, 27936, 18518, 0, 0, 0
|
||||
}; //BY D Ba tt er y- Bo x Pr em iu m HV
|
||||
uint16_t p135_data[] = {13614, 12288, 0, 0, 0, 0, 0, 0, 13102, 12598, 0, 0, 0, 0, 0, 0}; //5.0 3.16
|
||||
uint16_t p151_data[] = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; //Serial number for battery
|
||||
uint16_t p167_data[] = {1, 0};
|
||||
uint16_t p201_data[] = {
|
||||
0, 0, capacity_Wh_startup, MaxPower, MaxPower, MaxVoltage, MinVoltage, 53248, 10, 53248, 10, 0, 0
|
||||
};
|
||||
uint16_t p301_data[] = {
|
||||
Status, 0, 128, SOC, capacity_Wh, remaining_capacity_Wh, max_target_discharge_power, max_target_charge_power, 0, 0,
|
||||
2058, 0, TemperatureMin, TemperatureMax, 0, 0, 16, 22741, 0, 0, 13, 52064, 80, 9900
|
||||
};
|
||||
//These registers get written to
|
||||
uint16_t p401_data[] = {1, 255, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
|
||||
uint16_t p1001_data[] = {
|
||||
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
|
||||
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
|
||||
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0
|
||||
};
|
||||
uint16_t i;
|
||||
uint16_t bms_char_dis_status; //0 idle, 1 discharging, 2, charging
|
||||
uint16_t bms_status = 0; //ACTIVE - [0..5]<>[STANDBY,INACTIVE,DARKSTART,ACTIVE,FAULT,UPDATING]
|
||||
|
||||
// Create a ModbusRTU server instance listening on Serial2 with 2000ms timeout
|
||||
ModbusServerRTU MBserver(Serial2, 2000);
|
||||
|
@ -99,7 +77,15 @@ void setup()
|
|||
ESP32Can.CANInit();
|
||||
Serial.println(CAN_cfg.speed);
|
||||
|
||||
//Modbus pins
|
||||
// Init Serial monitor
|
||||
Serial.begin(9600);
|
||||
while (!Serial)
|
||||
{
|
||||
}
|
||||
Serial.println("__ OK __");
|
||||
|
||||
//Set up Modbus RTU Server
|
||||
Serial.println("Set ModbusRtu PIN");
|
||||
pinMode(RS485_EN_PIN, OUTPUT);
|
||||
digitalWrite(RS485_EN_PIN, HIGH);
|
||||
|
||||
|
@ -108,24 +94,22 @@ void setup()
|
|||
|
||||
pinMode(PIN_5V_EN, OUTPUT);
|
||||
digitalWrite(PIN_5V_EN, HIGH);
|
||||
// Init Serial monitor
|
||||
Serial.begin(9600);
|
||||
while (!Serial)
|
||||
{
|
||||
}
|
||||
Serial.println("__ OK __");
|
||||
|
||||
// Init Static data to the RTU Modbus
|
||||
handle_StaticDataModbus();
|
||||
handle_static_data_modbus();
|
||||
|
||||
// Init Serial2 connected to the RTU Modbus
|
||||
// (Fill in your data here!)
|
||||
RTUutils::prepareHardwareSerial(Serial2);
|
||||
Serial2.begin(9600, SERIAL_8N1, RS485_RX_PIN, RS485_TX_PIN);
|
||||
// Register served function code worker for server id 21, FC 0x03
|
||||
|
||||
// Register served function code worker for server
|
||||
MBserver.registerWorker(MBTCP_ID, READ_HOLD_REGISTER, &FC03);
|
||||
MBserver.registerWorker(MBTCP_ID, WRITE_HOLD_REGISTER, &FC06);
|
||||
MBserver.registerWorker(MBTCP_ID, WRITE_MULT_REGISTERS, &FC16);
|
||||
MBserver.registerWorker(MBTCP_ID, R_W_MULT_REGISTERS, &FC23);
|
||||
|
||||
// Start ModbusRTU background task
|
||||
MBserver.start();
|
||||
MBserver.begin(Serial2);
|
||||
}
|
||||
|
||||
// perform main program functions
|
||||
|
@ -137,7 +121,8 @@ void loop()
|
|||
{
|
||||
previousMillisModbus = millis();
|
||||
update_values();
|
||||
handle_UpdateDataModbus();
|
||||
handle_update_data_modbusp201(); //Updata for ModbusRTU Server for GEN24
|
||||
handle_update_data_modbusp301(); //Updata for ModbusRTU Server for GEN24
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -153,57 +138,88 @@ void update_values()
|
|||
TemperatureMax = 60; //hardcoded, todo, read from 5C0
|
||||
}
|
||||
|
||||
void handle_StaticDataModbus()
|
||||
{
|
||||
i = 100;
|
||||
// --- Copy the contents of the static data from the original arrays to the new modbus array ---
|
||||
for (uint16_t j = 0; j < sizeof(p101_data) / sizeof(uint16_t); j++)
|
||||
{
|
||||
mbPV[i] = p101_data[j];
|
||||
i++;
|
||||
}
|
||||
for (uint16_t j = 0; j < sizeof(p103_data) / sizeof(uint16_t); j++)
|
||||
{
|
||||
mbPV[i] = p103_data[j];
|
||||
i++;
|
||||
}
|
||||
for (uint16_t j = 0; j < sizeof(p119_data) / sizeof(uint16_t); j++)
|
||||
{
|
||||
mbPV[i] = p119_data[j];
|
||||
i++;
|
||||
}
|
||||
for (uint16_t j = 0; j < sizeof(p135_data) / sizeof(uint16_t); j++)
|
||||
{
|
||||
mbPV[i] = p135_data[j];
|
||||
i++;
|
||||
}
|
||||
for (uint16_t j = 0; j < sizeof(p151_data) / sizeof(uint16_t); j++)
|
||||
{
|
||||
mbPV[i] = p151_data[j];
|
||||
i++;
|
||||
}
|
||||
for (uint16_t j = 0; j < sizeof(p167_data) / sizeof(uint16_t); j++)
|
||||
{
|
||||
mbPV[i] = p167_data[j];
|
||||
i++;
|
||||
void handle_static_data_modbus() {
|
||||
// Store the data into the array
|
||||
static uint16_t si_data[] = { 21321, 1 };
|
||||
static uint16_t byd_data[] = { 16985, 17408, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
|
||||
static uint16_t battery_data[] = { 16985, 17440, 16993, 29812, 25970, 31021, 17007, 30752, 20594, 25965, 26997, 27936, 18518, 0, 0, 0 };
|
||||
static uint16_t volt_data[] = { 13614, 12288, 0, 0, 0, 0, 0, 0, 13102, 12598, 0, 0, 0, 0, 0, 0 };
|
||||
static uint16_t serial_data[] = { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 };
|
||||
static uint16_t static_data[] = { 1, 0 };
|
||||
static uint16_t* data_array_pointers[] = { si_data, byd_data, battery_data, volt_data, serial_data, static_data };
|
||||
static uint16_t data_sizes[] = { sizeof(si_data), sizeof(byd_data), sizeof(battery_data), sizeof(volt_data), sizeof(serial_data), sizeof(static_data) };
|
||||
static uint16_t i = 100;
|
||||
for (uint8_t arr_idx = 0; arr_idx < sizeof(data_array_pointers) / sizeof(uint16_t*); arr_idx++) {
|
||||
uint16_t data_size = data_sizes[arr_idx];
|
||||
memcpy(&mbPV[i], data_array_pointers[arr_idx], data_size);
|
||||
i += data_size / sizeof(uint16_t);
|
||||
}
|
||||
}
|
||||
|
||||
void handle_UpdateDataModbus()
|
||||
{
|
||||
i = 200;
|
||||
// --- Copy the data contents arrays to the new modbus array ---
|
||||
for (uint16_t j = 0; j < sizeof(p201_data) / sizeof(uint16_t); j++)
|
||||
{
|
||||
mbPV[i] = p201_data[j];
|
||||
i++;
|
||||
void handle_update_data_modbusp201() {
|
||||
// Store the data into the array
|
||||
static uint16_t system_data[13];
|
||||
system_data[0] = 0; // Id.: p201 Value.: 0 Scaled value.: 0 Comment.: Always 0
|
||||
system_data[1] = 0; // Id.: p202 Value.: 0 Scaled value.: 0 Comment.: Always 0
|
||||
system_data[2] = (capacity_Wh_startup); // Id.: p203 Value.: 32000 Scaled value.: 32kWh Comment.: Capacity rated
|
||||
system_data[3] = (capacity_Wh_startup); // Id.: p204 Value.: 32000 Scaled value.: 32kWh Comment.: Nominal capacity
|
||||
system_data[4] = (MaxPower); // Id.: p205 Value.: 14500 Scaled value.: 30,42kW Comment.: Max Charge/Discharge Power=10.24kW
|
||||
system_data[5] = (MaxVoltage); // Id.: p206 Value.: 3667 Scaled value.: 362,7VDC Comment.: Max Voltage, if higher charging is not possible (goes into forced discharge)
|
||||
system_data[6] = (MinVoltage); // Id.: p207 Value.: 2776 Scaled value.: 277,6VDC Comment.: Min Voltage, if lower Gen24 disables battery
|
||||
system_data[7] = 53248; // Id.: p208 Value.: 53248 Scaled value.: 53248 Comment.: Always 53248 for this BYD, Peak Charge power?
|
||||
system_data[8] = 10; // Id.: p209 Value.: 10 Scaled value.: 10 Comment.: Always 10
|
||||
system_data[9] = 53248; // Id.: p210 Value.: 53248 Scaled value.: 53248 Comment.: Always 53248 for this BYD, Peak Discharge power?
|
||||
system_data[10] = 10; // Id.: p211 Value.: 10 Scaled value.: 10 Comment.: Always 10
|
||||
system_data[11] = 0; // Id.: p212 Value.: 0 Scaled value.: 0 Comment.: Always 0
|
||||
system_data[12] = 0; // Id.: p213 Value.: 0 Scaled value.: 0 Comment.: Always 0
|
||||
static uint16_t i = 200;
|
||||
memcpy(&mbPV[i], system_data, sizeof(system_data));
|
||||
}
|
||||
i = 300;
|
||||
for (uint16_t j = 0; j < sizeof(p301_data) / sizeof(uint16_t); j++)
|
||||
{
|
||||
mbPV[i] = p301_data[j];
|
||||
i++;
|
||||
|
||||
void handle_update_data_modbusp301() {
|
||||
// Store the data into the array
|
||||
static uint16_t battery_data[23];
|
||||
if (LB_Current > 0) {
|
||||
bms_char_dis_status = 1; //Discharging
|
||||
} else if (LB_Current < 0) {
|
||||
bms_char_dis_status = 2; //Charging
|
||||
} else { //LB_Current == 0
|
||||
bms_char_dis_status = 0;
|
||||
}
|
||||
|
||||
bms_status = 3; //Todo add logic here
|
||||
|
||||
if (bms_status == 3) {
|
||||
battery_data[8] = LB_Total_Voltage; // Id.: p309 Value.: 3161 Scaled value.: 316,1VDC Comment.: Batt Voltage outer (0 if status !=3, maybe a contactor closes when active): 173.4V
|
||||
} else {
|
||||
battery_data[8] = 0;
|
||||
}
|
||||
battery_data[0] = bms_status; // Id.: p301 Value.: 3 Scaled value.: 3 Comment.: status(*): ACTIVE - [0..5]<>[STANDBY,INACTIVE,DARKSTART,ACTIVE,FAULT,UPDATING]
|
||||
battery_data[1] = 0; // Id.: p302 Value.: 0 Scaled value.: 0 Comment.: always 0
|
||||
battery_data[2] = 128 + bms_char_dis_status; // Id.: p303 Value.: 130 Scaled value.: 130 Comment.: mode(*): normal
|
||||
battery_data[3] = SOC; // Id.: p304 Value.: 1700 Scaled value.: 17% Comment.: soc: 32%
|
||||
battery_data[4] = capacity_Wh; // Id.: p305 Value.: 32000 Scaled value.: 32kWh Comment.: tot cap:
|
||||
battery_data[5] = remaining_capacity_Wh; // Id.: p306 Value.: 13260 Scaled value.: 13,26kWh Comment.: remaining cap: 7.68kWh
|
||||
battery_data[6] = max_target_discharge_power; // Id.: p307 Value.: 25604 Scaled value.: 25,604kW Comment.: max/target discharge power: 0W (0W > restricts to no discharge)
|
||||
battery_data[7] = max_target_charge_power; // Id.: p308 Value.: 25604 Scaled value.: 25,604kW Comment.: max/target charge power: 4.3kW (during charge), both 307&308 can be set (>0) at the same time
|
||||
//Battery_data[8] set previously in function // Id.: p309 Value.: 3161 Scaled value.: 316,1VDC Comment.: Batt Voltage outer (0 if status !=3, maybe a contactor closes when active): 173.4V
|
||||
battery_data[9] = 2000; // Id.: p310 Value.: 64121 Scaled value.: 6412,1W Comment.: Current Power to API: if>32768... -(65535-61760)=3775W
|
||||
battery_data[10] = LB_Total_Voltage; // Id.: p311 Value.: 3161 Scaled value.: 316,1VDC Comment.: Batt Voltage inner: 173.2V
|
||||
battery_data[11] = 2000; // Id.: p312 Value.: 64121 Scaled value.: 6412,1W Comment.: p310
|
||||
battery_data[12] = TemperatureMin; // Id.: p313 Value.: 75 Scaled value.: 7,5 Comment.: temp min: 14 degrees (if below 0....65535-t)
|
||||
battery_data[13] = TemperatureMax; // Id.: p314 Value.: 95 Scaled value.: 9,5 Comment.: temp max: 15 degrees (if below 0....65535-t)
|
||||
battery_data[14] = 0; // Id.: p315 Value.: 0 Scaled value.: 0 Comment.: always 0
|
||||
battery_data[15] = 0; // Id.: p316 Value.: 0 Scaled value.: 0 Comment.: always 0
|
||||
battery_data[16] = 16; // Id.: p317 Value.: 0 Scaled value.: 0 Comment.: counter charge hi
|
||||
battery_data[17] = 22741; // Id.: p318 Value.: 0 Scaled value.: 0 Comment.: counter charge lo....65536*101+9912 = 6629048 Wh?
|
||||
battery_data[18] = 0; // Id.: p319 Value.: 0 Scaled value.: 0 Comment.: always 0
|
||||
battery_data[19] = 0; // Id.: p320 Value.: 0 Scaled value.: 0 Comment.: always 0
|
||||
battery_data[20] = 13; // Id.: p321 Value.: 0 Scaled value.: 0 Comment.: counter discharge hi
|
||||
battery_data[21] = 52064; // Id.: p322 Value.: 0 Scaled value.: 0 Comment.: counter discharge lo....65536*92+7448 = 6036760 Wh?
|
||||
battery_data[22] = 80; // Id.: p323 Value.: 0 Scaled value.: 0 Comment.: temp? (23 degrees)
|
||||
battery_data[23] = 9900; // Id.: p324 Value.: 0 Scaled value.: 0 Comment.: unknown
|
||||
static uint16_t i = 300;
|
||||
memcpy(&mbPV[i], battery_data, sizeof(battery_data));
|
||||
}
|
||||
|
||||
void handle_can()
|
||||
|
@ -220,8 +236,14 @@ void handle_can()
|
|||
switch (rx_frame.MsgID)
|
||||
{
|
||||
case 0x1DB:
|
||||
//printf("1DB \n");
|
||||
LB_Current = (rx_frame.data.u8[0] << 3) | (rx_frame.data.u8[1] & 0xe0) >> 5;
|
||||
printf("1DB \n");
|
||||
LB_Current = (rx_frame.data.u8[0] << 3) | (rx_frame.data.u8[1] & 0xe0) >> 5; //TODO TEST THIS
|
||||
if (LB_Current & 0x0400)//TODO TEST THIS
|
||||
{
|
||||
// negative so extend the sign bit
|
||||
LB_Current |= 0xf800; //TODO TEST THIS
|
||||
}
|
||||
Serial.println(LB_Current);//TODO TEST THIS
|
||||
LB_Total_Voltage = ((rx_frame.data.u8[2] << 2) | (rx_frame.data.u8[3] & 0xc0) >> 6) / 2;
|
||||
break;
|
||||
case 0x1DC:
|
||||
|
|
|
@ -11,9 +11,9 @@
|
|||
#include "Logging.h"
|
||||
|
||||
// Constructor takes Serial reference and optional DE/RE pin
|
||||
ModbusClientRTU::ModbusClientRTU(HardwareSerial& serial, int8_t rtsPin, uint16_t queueLimit) :
|
||||
ModbusClientRTU::ModbusClientRTU(int8_t rtsPin, uint16_t queueLimit) :
|
||||
ModbusClient(),
|
||||
MR_serial(serial),
|
||||
MR_serial(nullptr),
|
||||
MR_lastMicros(micros()),
|
||||
MR_interval(2000),
|
||||
MR_rtsPin(rtsPin),
|
||||
|
@ -33,9 +33,9 @@ ModbusClientRTU::ModbusClientRTU(HardwareSerial& serial, int8_t rtsPin, uint16_t
|
|||
}
|
||||
|
||||
// Alternative constructor takes Serial reference and RTS callback function
|
||||
ModbusClientRTU::ModbusClientRTU(HardwareSerial& serial, RTScallback rts, uint16_t queueLimit) :
|
||||
ModbusClientRTU::ModbusClientRTU(RTScallback rts, uint16_t queueLimit) :
|
||||
ModbusClient(),
|
||||
MR_serial(serial),
|
||||
MR_serial(nullptr),
|
||||
MR_lastMicros(micros()),
|
||||
MR_interval(2000),
|
||||
MTRSrts(rts),
|
||||
|
@ -53,18 +53,29 @@ ModbusClientRTU::~ModbusClientRTU() {
|
|||
end();
|
||||
}
|
||||
|
||||
// begin: start worker task
|
||||
void ModbusClientRTU::begin(int coreID, uint32_t interval) {
|
||||
// Only start worker if HardwareSerial has been initialized!
|
||||
if (MR_serial.baudRate()) {
|
||||
// begin: start worker task - general version
|
||||
void ModbusClientRTU::begin(Stream& serial, uint32_t baudRate, int coreID) {
|
||||
MR_serial = &serial;
|
||||
doBegin(baudRate, coreID);
|
||||
}
|
||||
|
||||
// begin: start worker task - HardwareSerial version
|
||||
void ModbusClientRTU::begin(HardwareSerial& serial, int coreID) {
|
||||
MR_serial = &serial;
|
||||
uint32_t baudRate = serial.baudRate();
|
||||
serial.setRxFIFOFull(1);
|
||||
doBegin(baudRate, coreID);
|
||||
}
|
||||
|
||||
void ModbusClientRTU::doBegin(uint32_t baudRate, int coreID) {
|
||||
// Task already running? End it in case
|
||||
end();
|
||||
|
||||
// Pull down RTS toggle, if necessary
|
||||
MTRSrts(LOW);
|
||||
|
||||
// Set minimum interval time
|
||||
MR_interval = RTUutils::calculateInterval(MR_serial, interval);
|
||||
|
||||
// Switch serial FIFO buffer copy threshold to 1 byte (normally is 112!)
|
||||
RTUutils::UARTinit(MR_serial, 1);
|
||||
MR_interval = RTUutils::calculateInterval(baudRate);
|
||||
|
||||
// Create unique task name
|
||||
char taskName[18];
|
||||
|
@ -72,10 +83,7 @@ void ModbusClientRTU::begin(int coreID, uint32_t interval) {
|
|||
// Start task to handle the queue
|
||||
xTaskCreatePinnedToCore((TaskFunction_t)&handleConnection, taskName, 4096, this, 6, &worker, coreID >= 0 ? coreID : NULL);
|
||||
|
||||
LOG_D("Worker task %d started. Interval=%d\n", (uint32_t)worker, MR_interval);
|
||||
} else {
|
||||
LOG_E("Worker task could not be started! HardwareSerial not initialized?\n");
|
||||
}
|
||||
LOG_D("Client task %d started. Interval=%d\n", (uint32_t)worker, MR_interval);
|
||||
}
|
||||
|
||||
// end: stop worker task
|
||||
|
@ -93,7 +101,7 @@ void ModbusClientRTU::end() {
|
|||
}
|
||||
// Kill task
|
||||
vTaskDelete(worker);
|
||||
LOG_D("Worker task %d killed.\n", (uint32_t)worker);
|
||||
LOG_D("Client task %d killed.\n", (uint32_t)worker);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -227,7 +235,7 @@ bool ModbusClientRTU::addToQueue(uint32_t token, ModbusMessage request, bool syn
|
|||
// This was created in begin() to handle the queue entries
|
||||
void ModbusClientRTU::handleConnection(ModbusClientRTU *instance) {
|
||||
// initially clean the serial buffer
|
||||
while (instance->MR_serial.available()) instance->MR_serial.read();
|
||||
while (instance->MR_serial->available()) instance->MR_serial->read();
|
||||
delay(100);
|
||||
|
||||
// Loop forever - or until task is killed
|
||||
|
@ -240,7 +248,7 @@ void ModbusClientRTU::handleConnection(ModbusClientRTU *instance) {
|
|||
LOG_D("Pulled request from queue\n");
|
||||
|
||||
// Send it via Serial
|
||||
RTUutils::send(instance->MR_serial, instance->MR_lastMicros, instance->MR_interval, instance->MTRSrts, request.msg, instance->MR_useASCII);
|
||||
RTUutils::send(*(instance->MR_serial), instance->MR_lastMicros, instance->MR_interval, instance->MTRSrts, request.msg, instance->MR_useASCII);
|
||||
|
||||
LOG_D("Request sent.\n");
|
||||
// HEXDUMP_V("Data", request.msg.data(), request.msg.size());
|
||||
|
@ -249,7 +257,8 @@ void ModbusClientRTU::handleConnection(ModbusClientRTU *instance) {
|
|||
if (request.msg.getServerID() != 0 || ((request.token & 0xFF000000) != 0xBC000000)) {
|
||||
// This is a regular request, Get the response - if any
|
||||
ModbusMessage response = RTUutils::receive(
|
||||
instance->MR_serial,
|
||||
'C',
|
||||
*(instance->MR_serial),
|
||||
instance->MR_timeoutValue,
|
||||
instance->MR_lastMicros,
|
||||
instance->MR_interval,
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
#if HAS_FREERTOS
|
||||
|
||||
#include "ModbusClient.h"
|
||||
#include "HardwareSerial.h"
|
||||
#include "Stream.h"
|
||||
#include "RTUutils.h"
|
||||
#include <queue>
|
||||
#include <vector>
|
||||
|
@ -22,16 +22,18 @@ using std::queue;
|
|||
class ModbusClientRTU : public ModbusClient {
|
||||
public:
|
||||
// Constructor takes Serial reference and optional DE/RE pin and queue limit
|
||||
explicit ModbusClientRTU(HardwareSerial& serial, int8_t rtsPin = -1, uint16_t queueLimit = 100);
|
||||
explicit ModbusClientRTU(int8_t rtsPin = -1, uint16_t queueLimit = 100);
|
||||
|
||||
// Alternative Constructor takes Serial reference and RTS line toggle callback
|
||||
explicit ModbusClientRTU(HardwareSerial& serial, RTScallback rts, uint16_t queueLimit = 100);
|
||||
explicit ModbusClientRTU(RTScallback rts, uint16_t queueLimit = 100);
|
||||
|
||||
// Destructor: clean up queue, task etc.
|
||||
~ModbusClientRTU();
|
||||
|
||||
// begin: start worker task
|
||||
void begin(int coreID = -1, uint32_t interval = 0);
|
||||
void begin(Stream& serial, uint32_t baudrate, int coreID = -1);
|
||||
// Special variant for HardwareSerial
|
||||
void begin(HardwareSerial& serial, int coreID = -1);
|
||||
|
||||
// end: stop the worker
|
||||
void end();
|
||||
|
@ -81,12 +83,15 @@ protected:
|
|||
// receive: get response via Serial
|
||||
ModbusMessage receive(const ModbusMessage request);
|
||||
|
||||
// start background task
|
||||
void doBegin(uint32_t baudRate, int coreID);
|
||||
|
||||
void isInstance() { return; } // make class instantiable
|
||||
queue<RequestEntry> requests; // Queue to hold requests to be processed
|
||||
#if USE_MUTEX
|
||||
mutex qLock; // Mutex to protect queue
|
||||
#endif
|
||||
HardwareSerial& MR_serial; // Ptr to the serial interface used
|
||||
Stream *MR_serial; // Ptr to the serial interface used
|
||||
unsigned long MR_lastMicros; // Microseconds since last bus activity
|
||||
uint32_t MR_interval; // Modbus RTU bus quiet time
|
||||
int8_t MR_rtsPin; // GPIO pin to toggle RS485 DE/RE line. -1 if none.
|
||||
|
|
|
@ -13,12 +13,12 @@
|
|||
uint8_t ModbusServerRTU::instanceCounter = 0;
|
||||
|
||||
// Constructor with RTS pin GPIO (or -1)
|
||||
ModbusServerRTU::ModbusServerRTU(HardwareSerial& serial, uint32_t timeout, int rtsPin) :
|
||||
ModbusServerRTU::ModbusServerRTU(uint32_t timeout, int rtsPin) :
|
||||
ModbusServer(),
|
||||
serverTask(nullptr),
|
||||
serverTimeout(timeout),
|
||||
MSRserial(serial),
|
||||
MSRinterval(2000), // will be calculated in start()!
|
||||
MSRserial(nullptr),
|
||||
MSRinterval(2000), // will be calculated in begin()!
|
||||
MSRlastMicros(0),
|
||||
MSRrtsPin(rtsPin),
|
||||
MSRuseASCII(false),
|
||||
|
@ -40,12 +40,12 @@ ModbusServerRTU::ModbusServerRTU(HardwareSerial& serial, uint32_t timeout, int r
|
|||
}
|
||||
|
||||
// Constructor with RTS callback
|
||||
ModbusServerRTU::ModbusServerRTU(HardwareSerial& serial, uint32_t timeout, RTScallback rts) :
|
||||
ModbusServerRTU::ModbusServerRTU(uint32_t timeout, RTScallback rts) :
|
||||
ModbusServer(),
|
||||
serverTask(nullptr),
|
||||
serverTimeout(timeout),
|
||||
MSRserial(serial),
|
||||
MSRinterval(2000), // will be calculated in start()!
|
||||
MSRserial(nullptr),
|
||||
MSRinterval(2000), // will be calculated in begin()!
|
||||
MSRlastMicros(0),
|
||||
MRTSrts(rts),
|
||||
MSRuseASCII(false),
|
||||
|
@ -63,22 +63,26 @@ ModbusServerRTU::ModbusServerRTU(HardwareSerial& serial, uint32_t timeout, RTSca
|
|||
ModbusServerRTU::~ModbusServerRTU() {
|
||||
}
|
||||
|
||||
// start: create task with RTU server
|
||||
bool ModbusServerRTU::start(int coreID, uint32_t interval) {
|
||||
// Task already running?
|
||||
if (serverTask != nullptr) {
|
||||
// Yes. stop it first
|
||||
stop();
|
||||
LOG_D("Server task was running - stopped.\n");
|
||||
// start: create task with RTU server - general version
|
||||
void ModbusServerRTU::begin(Stream& serial, uint32_t baudRate, int coreID) {
|
||||
MSRserial = &serial;
|
||||
doBegin(baudRate, coreID);
|
||||
}
|
||||
|
||||
// start only if serial interface is initialized!
|
||||
if (MSRserial.baudRate()) {
|
||||
// Set minimum interval time
|
||||
MSRinterval = RTUutils::calculateInterval(MSRserial, interval);
|
||||
// start: create task with RTU server - HardwareSerial versions
|
||||
void ModbusServerRTU::begin(HardwareSerial& serial, int coreID) {
|
||||
MSRserial = &serial;
|
||||
uint32_t baudRate = serial.baudRate();
|
||||
serial.setRxFIFOFull(1);
|
||||
doBegin(baudRate, coreID);
|
||||
}
|
||||
|
||||
// Set the UART FIFO copy threshold to 1 byte
|
||||
RTUutils::UARTinit(MSRserial, 1);
|
||||
void ModbusServerRTU::doBegin(uint32_t baudRate, int coreID) {
|
||||
// Task already running? Stop it in case.
|
||||
end();
|
||||
|
||||
// Set minimum interval time
|
||||
MSRinterval = RTUutils::calculateInterval(baudRate);
|
||||
|
||||
// Create unique task name
|
||||
char taskName[18];
|
||||
|
@ -88,22 +92,15 @@ bool ModbusServerRTU::start(int coreID, uint32_t interval) {
|
|||
xTaskCreatePinnedToCore((TaskFunction_t)&serve, taskName, 4096, this, 8, &serverTask, coreID >= 0 ? coreID : NULL);
|
||||
|
||||
LOG_D("Server task %d started. Interval=%d\n", (uint32_t)serverTask, MSRinterval);
|
||||
} else {
|
||||
LOG_E("Server task could not be started. HardwareSerial not initialized?\n");
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// stop: kill server task
|
||||
bool ModbusServerRTU::stop() {
|
||||
// end: kill server task
|
||||
void ModbusServerRTU::end() {
|
||||
if (serverTask != nullptr) {
|
||||
vTaskDelete(serverTask);
|
||||
LOG_D("Server task %d stopped.\n", (uint32_t)serverTask);
|
||||
serverTask = nullptr;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
// Toggle protocol to ModbusASCII
|
||||
|
@ -163,7 +160,8 @@ void ModbusServerRTU::serve(ModbusServerRTU *myServer) {
|
|||
|
||||
// Wait for and read an request
|
||||
request = RTUutils::receive(
|
||||
myServer->MSRserial,
|
||||
'S',
|
||||
*(myServer->MSRserial),
|
||||
myServer->serverTimeout,
|
||||
myServer->MSRlastMicros,
|
||||
myServer->MSRinterval,
|
||||
|
@ -236,7 +234,7 @@ void ModbusServerRTU::serve(ModbusServerRTU *myServer) {
|
|||
// Do we have gathered a valid response now?
|
||||
if (response.size() >= 3) {
|
||||
// Yes. send it back.
|
||||
RTUutils::send(myServer->MSRserial, myServer->MSRlastMicros, myServer->MSRinterval, myServer->MRTSrts, response, myServer->MSRuseASCII);
|
||||
RTUutils::send(*(myServer->MSRserial), myServer->MSRlastMicros, myServer->MSRinterval, myServer->MRTSrts, response, myServer->MSRuseASCII);
|
||||
LOG_D("Response sent.\n");
|
||||
// Count it, in case we had an error response
|
||||
if (response.getError() != SUCCESS) {
|
||||
|
|
|
@ -10,7 +10,7 @@
|
|||
#if HAS_FREERTOS
|
||||
|
||||
#include <Arduino.h>
|
||||
#include "HardwareSerial.h"
|
||||
#include "Stream.h"
|
||||
#include "ModbusServer.h"
|
||||
#include "RTUutils.h"
|
||||
|
||||
|
@ -25,17 +25,18 @@ using MSRlistener = std::function<void(ModbusMessage msg)>;
|
|||
class ModbusServerRTU : public ModbusServer {
|
||||
public:
|
||||
// Constructors
|
||||
explicit ModbusServerRTU(HardwareSerial& serial, uint32_t timeout=20000, int rtsPin = -1);
|
||||
ModbusServerRTU(HardwareSerial& serial, uint32_t timeout, RTScallback rts);
|
||||
explicit ModbusServerRTU(uint32_t timeout, int rtsPin = -1);
|
||||
ModbusServerRTU(uint32_t timeout, RTScallback rts);
|
||||
|
||||
// Destructor
|
||||
~ModbusServerRTU();
|
||||
|
||||
// start: create task with RTU server to accept requests
|
||||
bool start(int coreID = -1, uint32_t interval = 0);
|
||||
// begin: create task with RTU server to accept requests
|
||||
void begin(Stream& serial, uint32_t baudRate, int coreID = -1);
|
||||
void begin(HardwareSerial& serial, int coreID = -1);
|
||||
|
||||
// stop: kill server task
|
||||
bool stop();
|
||||
// end: kill server task
|
||||
void end();
|
||||
|
||||
// Toggle protocol to ModbusASCII
|
||||
void useModbusASCII(unsigned long timeout = 1000);
|
||||
|
@ -62,6 +63,9 @@ protected:
|
|||
|
||||
inline void isInstance() { } // Make class instantiable
|
||||
|
||||
// internal common begin function
|
||||
void doBegin(uint32_t baudRate, int coreID);
|
||||
|
||||
static uint8_t instanceCounter; // Number of RTU servers created (for task names)
|
||||
TaskHandle_t serverTask; // task of the started server
|
||||
uint32_t serverTimeout; // given timeout for receive. Does not really
|
||||
|
@ -69,7 +73,7 @@ protected:
|
|||
// RTUutils. After timeout without any message
|
||||
// the server will pause ~1ms and start
|
||||
// receive again.
|
||||
HardwareSerial& MSRserial; // The serial interface to use
|
||||
Stream *MSRserial; // The serial interface to use
|
||||
uint32_t MSRinterval; // Bus quiet time between messages
|
||||
unsigned long MSRlastMicros; // microsecond time stamp of last bus activity
|
||||
int8_t MSRrtsPin; // GPIO number of the RS485 module's RE/DE line
|
||||
|
|
|
@ -102,65 +102,18 @@ void RTUutils::addCRC(ModbusMessage& raw) {
|
|||
}
|
||||
|
||||
// calculateInterval: determine the minimal gap time between messages
|
||||
uint32_t RTUutils::calculateInterval(HardwareSerial& s, uint32_t overwrite) {
|
||||
uint32_t RTUutils::calculateInterval(uint32_t baudRate) {
|
||||
uint32_t interval = 0;
|
||||
|
||||
// silent interval is at least 3.5x character time
|
||||
interval = 35000000UL / s.baudRate(); // 3.5 * 10 bits * 1000 µs * 1000 ms / baud
|
||||
interval = 35000000UL / baudRate; // 3.5 * 10 bits * 1000 µs * 1000 ms / baud
|
||||
if (interval < 1750) interval = 1750; // lower limit according to Modbus RTU standard
|
||||
// User overwrite?
|
||||
if (overwrite > interval) {
|
||||
interval = overwrite;
|
||||
}
|
||||
LOG_V("Calc interval(%u)=%u\n", baudRate, interval);
|
||||
return interval;
|
||||
}
|
||||
|
||||
// UARTinit: modify the UART FIFO copy trigger threshold
|
||||
// This is normally set to 112 by default, resulting in short messages not being
|
||||
// recognized fast enough for higher Modbus bus speeds
|
||||
// Our default is 1 - every single byte arriving will have the UART FIFO
|
||||
// copied to the serial buffer.
|
||||
int RTUutils::UARTinit(HardwareSerial& serial, int thresholdBytes) {
|
||||
int rc = 0;
|
||||
#if NEED_UART_PATCH
|
||||
// Is the threshold value valid? The UART FIFO is 128 bytes only
|
||||
if (thresholdBytes > 0 && thresholdBytes < 128) {
|
||||
// Yes, it is. Try to identify the Serial/Serial1/Serial2 the user has provided.
|
||||
uart_dev_t *uart = nullptr;
|
||||
uint8_t uart_num = 99;
|
||||
if (&serial == &Serial) {
|
||||
uart_num = 0;
|
||||
uart = &UART0;
|
||||
} else {
|
||||
if (&serial == &Serial1) {
|
||||
uart_num = 1;
|
||||
uart = &UART1;
|
||||
} else {
|
||||
if (&serial == &Serial2) {
|
||||
uart_num = 2;
|
||||
uart = &UART2;
|
||||
}
|
||||
}
|
||||
}
|
||||
// Is it a defined serial?
|
||||
if (uart_num != 99) {
|
||||
// Yes. get the current value and set ours instead
|
||||
rc = uart->conf1.rxfifo_full_thrhd;
|
||||
uart->conf1.rxfifo_full_thrhd = thresholdBytes;
|
||||
LOG_D("Serial%u FIFO threshold set to %d (was %d)\n", uart_num, thresholdBytes, rc);
|
||||
} else {
|
||||
LOG_W("Unable to identify serial\n");
|
||||
}
|
||||
} else {
|
||||
LOG_E("Threshold must be between 1 and 127! (was %d)", thresholdBytes);
|
||||
}
|
||||
#endif
|
||||
// Return the previous value in case someone likes to see it.
|
||||
return rc;
|
||||
}
|
||||
|
||||
// send: send a message via Serial, watching interval times - including CRC!
|
||||
void RTUutils::send(HardwareSerial& serial, unsigned long& lastMicros, uint32_t interval, RTScallback rts, const uint8_t *data, uint16_t len, bool ASCIImode) {
|
||||
void RTUutils::send(Stream& serial, unsigned long& lastMicros, uint32_t interval, RTScallback rts, const uint8_t *data, uint16_t len, bool ASCIImode) {
|
||||
// Clear serial buffers
|
||||
while (serial.available()) serial.read();
|
||||
|
||||
|
@ -223,12 +176,12 @@ void RTUutils::send(HardwareSerial& serial, unsigned long& lastMicros, uint32_t
|
|||
}
|
||||
|
||||
// send: send a message via Serial, watching interval times - including CRC!
|
||||
void RTUutils::send(HardwareSerial& serial, unsigned long& lastMicros, uint32_t interval, RTScallback rts, ModbusMessage raw, bool ASCIImode) {
|
||||
void RTUutils::send(Stream& serial, unsigned long& lastMicros, uint32_t interval, RTScallback rts, ModbusMessage raw, bool ASCIImode) {
|
||||
send(serial, lastMicros, interval, rts, raw.data(), raw.size(), ASCIImode);
|
||||
}
|
||||
|
||||
// receive: get (any) message from Serial, taking care of timeout and interval
|
||||
ModbusMessage RTUutils::receive(HardwareSerial& serial, uint32_t timeout, unsigned long& lastMicros, uint32_t interval, bool ASCIImode, bool skipLeadingZeroBytes) {
|
||||
ModbusMessage RTUutils::receive(uint8_t caller, Stream& serial, uint32_t timeout, unsigned long& lastMicros, uint32_t interval, bool ASCIImode, bool skipLeadingZeroBytes) {
|
||||
// Allocate initial receive buffer size: 1 block of BUFBLOCKSIZE bytes
|
||||
const uint16_t BUFBLOCKSIZE(512);
|
||||
uint8_t *buffer = new uint8_t[BUFBLOCKSIZE];
|
||||
|
@ -270,6 +223,7 @@ ModbusMessage RTUutils::receive(HardwareSerial& serial, uint32_t timeout, unsign
|
|||
// Do we need to skip it, if it is zero?
|
||||
if (b > 0 || !skipLeadingZeroBytes) {
|
||||
// No, we can go process it regularly
|
||||
buffer[bufferPtr++] = b;
|
||||
state = IN_PACKET;
|
||||
}
|
||||
} else {
|
||||
|
@ -283,17 +237,12 @@ ModbusMessage RTUutils::receive(HardwareSerial& serial, uint32_t timeout, unsign
|
|||
break;
|
||||
// IN_PACKET: read data until a gap of at least _interval time passed without another byte arriving
|
||||
case IN_PACKET:
|
||||
// Are we past the interval gap without another byte?
|
||||
if (micros() - lastMicros >= interval) {
|
||||
// Yes, terminate reading
|
||||
LOG_V("%ldus without data\n", micros() - lastMicros);
|
||||
state = DATA_READ;
|
||||
} else {
|
||||
// No, still in reading sequence
|
||||
// Did we get a byte?
|
||||
if (b >= 0) {
|
||||
// tight loop until finished reading or error
|
||||
while (state == IN_PACKET) {
|
||||
// Is there a byte?
|
||||
while (serial.available()) {
|
||||
// Yes, collect it
|
||||
buffer[bufferPtr++] = b;
|
||||
buffer[bufferPtr++] = serial.read();
|
||||
// Mark time of last byte
|
||||
lastMicros = micros();
|
||||
// Buffer full?
|
||||
|
@ -304,14 +253,23 @@ ModbusMessage RTUutils::receive(HardwareSerial& serial, uint32_t timeout, unsign
|
|||
break;
|
||||
}
|
||||
}
|
||||
// Buffer has space left - try to read another byte
|
||||
b = serial.read();
|
||||
// No more byte read
|
||||
if (state == IN_PACKET) {
|
||||
// Are we past the interval gap?
|
||||
if (micros() - lastMicros >= interval) {
|
||||
// Yes, terminate reading
|
||||
LOG_V("%c/%ldus without data after %u\n", (const char)caller, micros() - lastMicros, bufferPtr);
|
||||
state = DATA_READ;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
break;
|
||||
// DATA_READ: successfully gathered some data. Prepare return object.
|
||||
case DATA_READ:
|
||||
// Did we get a sensible buffer length?
|
||||
HEXDUMP_D("Raw buffer received", buffer, bufferPtr);
|
||||
LOG_V("%c/", (const char)caller);
|
||||
HEXDUMP_V("Raw buffer received", buffer, bufferPtr);
|
||||
if (bufferPtr >= 4)
|
||||
{
|
||||
// Yes. Check CRC
|
||||
|
@ -431,7 +389,8 @@ ModbusMessage RTUutils::receive(HardwareSerial& serial, uint32_t timeout, unsign
|
|||
case A_WAIT_LEAD_OUT:
|
||||
if (b == 0xF2) {
|
||||
// Lead-out byte 2 received. Transfer buffer to returned message
|
||||
HEXDUMP_D("Raw buffer received", buffer, bufferPtr);
|
||||
LOG_V("%c/", (const char)caller);
|
||||
HEXDUMP_V("Raw buffer received", buffer, bufferPtr);
|
||||
// Did we get a sensible buffer length?
|
||||
if (bufferPtr >= 3)
|
||||
{
|
||||
|
@ -474,6 +433,7 @@ ModbusMessage RTUutils::receive(HardwareSerial& serial, uint32_t timeout, unsign
|
|||
// Deallocate buffer
|
||||
delete[] buffer;
|
||||
|
||||
LOG_D("%c/", (const char)caller);
|
||||
HEXDUMP_D("Received packet", rv.data(), rv.size());
|
||||
|
||||
return rv;
|
||||
|
|
|
@ -9,7 +9,7 @@
|
|||
#include <soc/uart_struct.h>
|
||||
#endif
|
||||
#include <vector>
|
||||
#include "HardwareSerial.h"
|
||||
#include "Stream.h"
|
||||
#include "ModbusTypeDefs.h"
|
||||
#include <functional>
|
||||
|
||||
|
@ -47,11 +47,17 @@ public:
|
|||
static void addCRC(ModbusMessage& raw);
|
||||
|
||||
// calculateInterval: determine the minimal gap time between messages
|
||||
static uint32_t calculateInterval(HardwareSerial& s, uint32_t overwrite);
|
||||
static uint32_t calculateInterval(uint32_t baudRate);
|
||||
|
||||
// RTSauto: dummy callback for auto half duplex RS485 boards
|
||||
inline static void RTSauto(bool level) { return; } // NOLINT
|
||||
|
||||
// Necessary preparations for a HardwareSerial
|
||||
static void prepareHardwareSerial(HardwareSerial& s, uint16_t bufferSize = 260) {
|
||||
s.setRxBufferSize(bufferSize);
|
||||
s.setTxBufferSize(bufferSize);
|
||||
}
|
||||
|
||||
protected:
|
||||
// Printable characters for ASCII protocol: 012345678ABCDEF
|
||||
static const char ASCIIwrite[];
|
||||
|
@ -59,15 +65,12 @@ protected:
|
|||
|
||||
RTUutils() = delete;
|
||||
|
||||
// UARTinit: modify the UART FIFO copy trigger threshold
|
||||
static int UARTinit(HardwareSerial& serial, int thresholdBytes = 1);
|
||||
|
||||
// receive: get a Modbus message from serial, maintaining timeouts etc.
|
||||
static ModbusMessage receive(HardwareSerial& serial, uint32_t timeout, unsigned long& lastMicros, uint32_t interval, bool ASCIImode, bool skipLeadingZeroBytes = false);
|
||||
static ModbusMessage receive(uint8_t caller, Stream& serial, uint32_t timeout, unsigned long& lastMicros, uint32_t interval, bool ASCIImode, bool skipLeadingZeroBytes = false);
|
||||
|
||||
// send: send a Modbus message in either format (ModbusMessage or data/len)
|
||||
static void send(HardwareSerial& serial, unsigned long& lastMicros, uint32_t interval, RTScallback r, const uint8_t *data, uint16_t len, bool ASCIImode);
|
||||
static void send(HardwareSerial& serial, unsigned long& lastMicros, uint32_t interval, RTScallback r, ModbusMessage raw, bool ASCIImode);
|
||||
static void send(Stream& serial, unsigned long& lastMicros, uint32_t interval, RTScallback r, const uint8_t *data, uint16_t len, bool ASCIImode);
|
||||
static void send(Stream& serial, unsigned long& lastMicros, uint32_t interval, RTScallback r, ModbusMessage raw, bool ASCIImode);
|
||||
};
|
||||
|
||||
#endif
|
||||
|
|
|
@ -5,10 +5,6 @@
|
|||
#ifndef _EMODBUS_OPTIONS_H
|
||||
#define _EMODBUS_OPTIONS_H
|
||||
|
||||
#ifndef RXFIFO_FULL_THRHD_PATCHED
|
||||
#define RXFIFO_FULL_THRHD_PATCHED 0
|
||||
#endif
|
||||
|
||||
/* === ESP32 DEFINITIONS AND MACROS === */
|
||||
#if defined(ESP32)
|
||||
#include <Arduino.h>
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue