Added other method of read for vsd
This commit is contained in:
parent
bf95ffed05
commit
dc2b3429a6
306
firmware/modbus-sd-VSD-generic-alt/modbus-sd-VSD-generic-alt.ino
Normal file
306
firmware/modbus-sd-VSD-generic-alt/modbus-sd-VSD-generic-alt.ino
Normal file
@ -0,0 +1,306 @@
|
||||
#include <Wire.h>
|
||||
#include <RTClib.h>
|
||||
|
||||
#include <NeoSWSerial.h>
|
||||
#include <ModbusMaster.h>
|
||||
#include "util.h"
|
||||
#include "register_map_vsd.h"
|
||||
|
||||
// #include <SD.h>
|
||||
|
||||
#include <SPI.h>
|
||||
#include <SdFat.h>
|
||||
#define SD_CS_PIN 10 // Chip Select for SD Card
|
||||
// RS485 pins
|
||||
#define DE_RE_PIN 4
|
||||
#define RX_PIN 8 // SoftwareSerial RX pin
|
||||
#define TX_PIN 7 // SoftwareSerial TX pin
|
||||
#define SLAVE_ID 1
|
||||
#define SERIAL_BAUDRATE 9600
|
||||
#define LED_A_PID 3
|
||||
#define LED_B_PID 5
|
||||
|
||||
// Try to select the best SD card configuration.
|
||||
#define SPI_CLOCK SD_SCK_MHZ(50)
|
||||
#if HAS_SDIO_CLASS
|
||||
#define SD_CONFIG SdioConfig(FIFO_SDIO)
|
||||
#elif ENABLE_DEDICATED_SPI
|
||||
#define SD_CONFIG SdSpiConfig(SD_CS_PIN, DEDICATED_SPI, SPI_CLOCK)
|
||||
#else // HAS_SDIO_CLASS
|
||||
#define SD_CONFIG SdSpiConfig(SD_CS_PIN, SHARED_SPI, SPI_CLOCK)
|
||||
#endif // HAS_SDIO_CLASS
|
||||
|
||||
RTC_DS3231 rtc; // Create an RTC object
|
||||
SdFat32 sd;
|
||||
// SdExFat sd;
|
||||
File dataFile;
|
||||
NeoSWSerial modbusSerial(RX_PIN, TX_PIN); // Create a software serial instance
|
||||
ModbusMaster node;
|
||||
|
||||
unsigned long lastRefreshTime = 0;
|
||||
bool headerWritten = false;
|
||||
bool booted = false;
|
||||
|
||||
void flicker(uint8_t pin, uint8_t times, uint16_t speed)
|
||||
{
|
||||
for (int i = 0; i < times; i++)
|
||||
{
|
||||
delay(speed);
|
||||
digitalWrite(pin, HIGH);
|
||||
delay(speed);
|
||||
digitalWrite(pin, LOW);
|
||||
}
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
booted = false;
|
||||
pinMode(LED_A_PID, OUTPUT);
|
||||
pinMode(LED_B_PID, OUTPUT);
|
||||
digitalWrite(LED_A_PID, LOW);
|
||||
digitalWrite(LED_B_PID, HIGH);
|
||||
|
||||
Serial.begin(SERIAL_BAUDRATE); // For debugging
|
||||
Serial.println(F("Startup \n"));
|
||||
|
||||
// Initialize RTC
|
||||
if (!rtc.begin())
|
||||
{
|
||||
Serial.println(F("Couldn't find RTC\n"));
|
||||
flicker(LED_B_PID, 4, 1000); // 4 times on LED b is RTC Error
|
||||
digitalWrite(LED_B_PID, HIGH);
|
||||
digitalWrite(LED_A_PID, HIGH);
|
||||
return;
|
||||
}
|
||||
|
||||
if (rtc.lostPower())
|
||||
{
|
||||
Serial.println(F("RTC lost power, let's set the time!\n"));
|
||||
// Comment out the following line once the time is set to avoid resetting on every start
|
||||
rtc.adjust(DateTime(F(__DATE__), F(__TIME__)));
|
||||
flicker(LED_B_PID, 4, 500); // 6 times fast on LED b is RTC reset
|
||||
}
|
||||
|
||||
Serial.print(F("Time: "));
|
||||
Serial.print(rtc.now().timestamp());
|
||||
Serial.println(F("\n"));
|
||||
|
||||
// Initialize SD card
|
||||
Serial.println(F("SD card initializing..."));
|
||||
pinMode(SD_CS_PIN, OUTPUT);
|
||||
|
||||
// if (!SD.begin(SPI_HALF_SPEED, SD_CS_PIN ))
|
||||
// {
|
||||
// Serial.println(F("SD card initialization failed!\n"));
|
||||
// return;
|
||||
// }
|
||||
// Initialize the SD.
|
||||
if (!sd.begin(SD_CONFIG))
|
||||
{
|
||||
flicker(LED_B_PID, 2, 1000);
|
||||
digitalWrite(LED_B_PID, HIGH);
|
||||
sd.initErrorHalt(&Serial);
|
||||
|
||||
// 2 Times slow and stay on, SD Card initilize error
|
||||
return;
|
||||
}
|
||||
Serial.println(F("SD card initialized.\n"));
|
||||
|
||||
Serial.println(F("Initialize RS485 module / Modbus \n"));
|
||||
|
||||
pinMode(DE_RE_PIN, OUTPUT);
|
||||
digitalWrite(DE_RE_PIN, LOW); // Set to LOW for receiving mode initially
|
||||
modbusSerial.begin(SERIAL_BAUDRATE);
|
||||
|
||||
node.begin(SLAVE_ID, modbusSerial);
|
||||
node.preTransmission(preTransmission);
|
||||
node.postTransmission(postTransmission);
|
||||
flicker(LED_B_PID, 10, 100);
|
||||
digitalWrite(LED_B_PID, LOW);
|
||||
booted = true;
|
||||
}
|
||||
|
||||
void preTransmission()
|
||||
{
|
||||
// Serial.println(F("Transmitting Start"));
|
||||
digitalWrite(DE_RE_PIN, HIGH); // Enable RS485 transmit
|
||||
digitalWrite(LED_A_PID, HIGH);
|
||||
}
|
||||
|
||||
void postTransmission()
|
||||
{
|
||||
|
||||
digitalWrite(DE_RE_PIN, LOW); // Disable RS485 transmit
|
||||
digitalWrite(LED_A_PID, LOW);
|
||||
// Serial.println(F("Transmitting End"));
|
||||
}
|
||||
|
||||
void primeFileDate()
|
||||
{
|
||||
if (!dataFile)
|
||||
{
|
||||
Serial.println(F("Error opening file"));
|
||||
return;
|
||||
}
|
||||
DateTime now = rtc.now();
|
||||
// Log the current date and time
|
||||
dataFile.print("\n");
|
||||
dataFile.print(now.year(), DEC);
|
||||
dataFile.print('-');
|
||||
dataFile.print(now.month(), DEC);
|
||||
dataFile.print('-');
|
||||
dataFile.print(now.day(), DEC);
|
||||
dataFile.print(" ");
|
||||
dataFile.print(now.hour(), DEC);
|
||||
dataFile.print(':');
|
||||
dataFile.print(now.minute(), DEC);
|
||||
dataFile.print(':');
|
||||
dataFile.print(now.second(), DEC);
|
||||
dataFile.print(F(","));
|
||||
}
|
||||
|
||||
String getFilename()
|
||||
{
|
||||
DateTime now = rtc.now();
|
||||
String mb = F("pm8k_");
|
||||
mb += now.year();
|
||||
mb += now.month();
|
||||
mb += now.day();
|
||||
mb += F(".csv");
|
||||
|
||||
return mb;
|
||||
}
|
||||
|
||||
// const char[20] filename = "20240523.csv";
|
||||
|
||||
void loop()
|
||||
{
|
||||
if (!booted)
|
||||
{
|
||||
Serial.print(F("\nBoot failed, cycle "));
|
||||
|
||||
delay(10000);
|
||||
digitalWrite(LED_A_PID, LOW);
|
||||
return;
|
||||
}
|
||||
delay(100);
|
||||
String writebuffer;
|
||||
|
||||
if (millis() - lastRefreshTime >= 1000)
|
||||
{
|
||||
lastRefreshTime += 1000;
|
||||
|
||||
Serial.print(F("\nTime: "));
|
||||
Serial.print(rtc.now().timestamp());
|
||||
// Serial.print("\nHeep:");
|
||||
// Serial.print(ESP.getFreeHeap());
|
||||
const uint16_t totalReg = sizeof(registers) / sizeof(registers[0]);
|
||||
// Open File
|
||||
String filename = getFilename();
|
||||
Serial.print(F("Open Card "));
|
||||
Serial.print(filename.c_str());
|
||||
Serial.print("\n");
|
||||
if (!dataFile.open(filename.c_str(), FILE_WRITE))
|
||||
{
|
||||
flicker(LED_B_PID, 6, 500); // Six quick flickers. SD Card error
|
||||
Serial.println(F("Failed to Open Card "));
|
||||
}
|
||||
if (!headerWritten)
|
||||
{
|
||||
dataFile.print("\nDate Time,");
|
||||
for (int i = 0; i < totalReg; i++)
|
||||
{
|
||||
const uint16_t regaddr = pgm_read_word(®isters[i].regaddr);
|
||||
dataFile.print("@");
|
||||
dataFile.print(regaddr);
|
||||
dataFile.print(",");
|
||||
}
|
||||
headerWritten = true;
|
||||
flicker(LED_A_PID, 50, 10); // 10 flickers, written header
|
||||
}
|
||||
primeFileDate();
|
||||
Serial.print("\n");
|
||||
|
||||
Serial.println(totalReg);
|
||||
// Modbus Data Loop
|
||||
for (int i = 0; i < totalReg; i++)
|
||||
{
|
||||
const uint16_t regaddr = pgm_read_word(®isters[i].regaddr);
|
||||
const uint8_t regtype = pgm_read_word(®isters[i].regtype);
|
||||
|
||||
Serial.print(F("Reg Read: "));
|
||||
Serial.println(regtype);
|
||||
Serial.println(regaddr);
|
||||
|
||||
if (regaddr > 0)
|
||||
{
|
||||
delay(25); // Gives the pending communication a little delay
|
||||
uint8_t result = node.readHoldingRegisters(regaddr - 1, 2);
|
||||
delay(25); // Delay the read for a little bit so that the buffer can be read
|
||||
|
||||
if (result == node.ku8MBSuccess)
|
||||
{
|
||||
if (regtype == 2)
|
||||
{
|
||||
dataFile.print(getRegisterFloat(node.getResponseBuffer(0), node.getResponseBuffer(1)));
|
||||
}
|
||||
else if (regtype == 1)
|
||||
{
|
||||
dataFile.print(node.getResponseBuffer(0));
|
||||
}
|
||||
// else if (regtype == 3)
|
||||
// {
|
||||
// dataFile.print(getRegisterInt64(node.getResponseBuffer(0), node.getResponseBuffer(1), node.getResponseBuffer(2), node.getResponseBuffer(3)));
|
||||
// }
|
||||
else if (regtype == 0)
|
||||
{
|
||||
dataFile.print(getRegisterInt32(node.getResponseBuffer(0), node.getResponseBuffer(1)));
|
||||
}
|
||||
else if (regtype == 5)
|
||||
{
|
||||
for (uint8_t j = 0; j < 20; j++)
|
||||
{
|
||||
uint8_t v = node.getResponseBuffer(j);
|
||||
char a = v;
|
||||
if (v == 0) {
|
||||
break;
|
||||
}
|
||||
dataFile.print(a);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
dataFile.print(F("null"));
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
Serial.print(F("Reg Error: "));
|
||||
Serial.print(result, HEX);
|
||||
Serial.print("\n");
|
||||
dataFile.print(F("E"));
|
||||
dataFile.print(result, HEX);
|
||||
flicker(LED_B_PID, 2, 250);
|
||||
}
|
||||
dataFile.print(",");
|
||||
}
|
||||
}
|
||||
|
||||
Serial.print(F("\nRead buffer: "));
|
||||
delay(10);
|
||||
|
||||
if (dataFile)
|
||||
{
|
||||
dataFile.close(); // Close the file
|
||||
Serial.print(F("Data written to SD card: "));
|
||||
Serial.print(filename.c_str());
|
||||
Serial.print(F("\n"));
|
||||
}
|
||||
|
||||
Serial.print(F("\n\n"));
|
||||
|
||||
flicker(LED_A_PID, 4, 100); // Cycle written 4 quick flickers
|
||||
}
|
||||
|
||||
// // Check if the read was successful
|
||||
}
|
120
firmware/modbus-sd-VSD-generic-alt/modbus-sd-vsd.md
Normal file
120
firmware/modbus-sd-VSD-generic-alt/modbus-sd-vsd.md
Normal file
@ -0,0 +1,120 @@
|
||||
# Modbus Reading for Generic VSD Device
|
||||
|
||||
This is a specification and implementation of the Arduino-based Modbus data logger for a Generic VSD Device.
|
||||
This software is designed for Vivarox EMS and only Vivarox has right to use and modify this software.
|
||||
|
||||
## Arduino Implementation:
|
||||
|
||||
This project uses an Arduino to connect to Modbus devices, read information, and log it onto an SD card with timestamps.
|
||||
|
||||
### Hardware needed:
|
||||
|
||||
1. Arduino Board
|
||||
Recommended: Arduino MEGA 2560 (for more memory and I/O pins) or Arduino UNO (for simpler projects).
|
||||
- [Arduino MEGA @ R377.20](https://www.robotics.org.za/MEGA-16U2?search=Arduino%20MEGA%202560)
|
||||
- [UNO R3 with 16U2 USB Interface @ R151.00](https://www.robotics.org.za/UNOR3-16U2?search=%20Arduino%20UNO)
|
||||
|
||||
2. RS485 to TTL Module
|
||||
Allows communication between the Arduino and Modbus devices using the RS485 protocol.
|
||||
- [RS485 Module (TTL -> RS485) @ R25.30](https://www.robotics.org.za/RS485-MOD)
|
||||
- [MAX485 Bus Transceiver (4 Pack) @ R16.00](https://www.robotics.org.za/MAX485-DIP?search=MAX485)
|
||||
|
||||
3. SD Card Module
|
||||
Allows the Arduino to read from and write data to an SD card.
|
||||
- [Micro SD Card Module @ R25.00](https://www.diyelectronics.co.za/store/memory/512-micro-sd-card-module.html?srsltid=AfmBOoptww8c6kx53xbZWiP2_C_qOE3r9xinyoCO-AZHrZkNQiyxU17c)
|
||||
|
||||
4. RTC Module
|
||||
To keep track of the current date and time, even when the Arduino is powered off.
|
||||
- [DS3231 Real Time Clock Module @ R55.20](https://www.robotics.org.za/DS3231-MOD?search=DS3231)
|
||||
|
||||
5. Power Supply
|
||||
To power the Arduino and connected peripherals.
|
||||
- [AC Adapter 9V with barrel jack @ R60](https://www.robotics.org.za/AC-9V-2A-2155?search=%20Power%20Supply)
|
||||
|
||||
6. LED Indicators
|
||||
Two LEDs for status indication (not included in original cost estimate).
|
||||
|
||||
### Wiring
|
||||
|
||||
#### RS485 Module to Arduino:
|
||||
1. RO (Receiver Output) to Arduino RX (pin 8)
|
||||
2. DI (Driver Input) to Arduino TX (pin 7)
|
||||
3. DE (Driver Enable) & RE (Receiver Enable) to Arduino digital pin 4
|
||||
4. VCC to 5V on Arduino
|
||||
5. GND to GND on Arduino
|
||||
6. A & B (RS485 differential pair) to Modbus device
|
||||
|
||||
#### SD Card Module to Arduino:
|
||||
1. VCC to 5V on Arduino
|
||||
2. GND to GND on Arduino
|
||||
3. MOSI to MOSI (pin 51 on MEGA, pin 11 on UNO)
|
||||
4. MISO to MISO (pin 50 on MEGA, pin 12 on UNO)
|
||||
5. SCK to SCK (pin 52 on MEGA, pin 13 on UNO)
|
||||
6. CS (Chip Select) to digital pin 10
|
||||
|
||||
#### RTC Module to Arduino:
|
||||
1. VCC to 5V on the Arduino
|
||||
2. GND to GND on the Arduino
|
||||
3. SDA to SDA (pin 20 on MEGA, pin A4 on UNO)
|
||||
4. SCL to SCL (pin 21 on MEGA, pin A5 on UNO)
|
||||
|
||||
#### LED Indicators:
|
||||
1. LED A to digital pin 3
|
||||
2. LED B to digital pin 5
|
||||
|
||||
### Software
|
||||
|
||||
- Modbus Library: ModbusMaster
|
||||
- SD Library: SdFat (more advanced than the standard SD library)
|
||||
- RTC Library: RTClib by Adafruit
|
||||
- NeoSWSerial: For better latency on software serial communication
|
||||
|
||||
### Implementation Details
|
||||
|
||||
1. Modbus Configuration:
|
||||
- Slave ID: 101
|
||||
- Baud Rate: 9600
|
||||
- Register map: Defined in separate "register_map_pm8000.h" file
|
||||
|
||||
2. Data Logging:
|
||||
- Frequency: Readings taken every second
|
||||
- File Format: CSV (Comma-Separated Values)
|
||||
- Filename: "pm8k_YYYYMMDD.csv" (generated daily based on current date)
|
||||
- Data Structure: Timestamp, followed by register values
|
||||
- Header Row: Includes register addresses for easy identification
|
||||
|
||||
3. Register Types Supported:
|
||||
- Float (32-bit)
|
||||
- Integer (32-bit)
|
||||
- Long (64-bit)
|
||||
- String (up to 20 characters)
|
||||
|
||||
4. Error Handling and Status Indication:
|
||||
- LED A: Indicates successful data writing and transmission
|
||||
- LED B: Indicates errors (e.g., SD card issues, RTC problems, Modbus communication errors)
|
||||
- Serial output for debugging (9600 baud)
|
||||
|
||||
5. Special Features:
|
||||
- Automatic creation of new log file on date change
|
||||
- Header row written only once per file
|
||||
- Robust error handling for SD card, RTC, and Modbus communication
|
||||
|
||||
### Programming Workflow
|
||||
|
||||
1. Initialize hardware (RTC, SD card, RS485 module)
|
||||
2. Set up Modbus communication parameters
|
||||
3. Enter main loop:
|
||||
- Read current time from RTC
|
||||
- Read data from Modbus registers
|
||||
- Write timestamped data to SD card
|
||||
- Handle any errors and provide status indication via LEDs
|
||||
- Delay for 1 second before next reading
|
||||
|
||||
## Best Practices
|
||||
|
||||
- Start by commenting out registers you don't need before adding new ones.
|
||||
- If you're using an Arduino UNO, you may need to be more selective about which registers to include due to memory constraints.
|
||||
- Test your modifications incrementally to ensure the Arduino can handle the memory load.
|
||||
- If you need to read a large number of registers, consider using an Arduino MEGA or a more powerful microcontroller.
|
||||
|
||||
By carefully managing the registers in the `register_map_vsd.h` file, you can customize this Modbus reader to suit your specific requirements while staying within the memory limitations of your Arduino board.
|
63
firmware/modbus-sd-VSD-generic-alt/register_map_vsd.h
Normal file
63
firmware/modbus-sd-VSD-generic-alt/register_map_vsd.h
Normal file
@ -0,0 +1,63 @@
|
||||
|
||||
#include <stdint.h>
|
||||
#ifndef REGISTER_MAP_VSD_H
|
||||
#define REGISTER_MAP_VSD_H
|
||||
struct RegisterMap {
|
||||
uint16_t regaddr;
|
||||
uint8_t regtype; // 1=UINT16, 2=FLOAT32, 3=INT64, 4=Status, 5=Thermal, 6=Power, 7=RPM
|
||||
float scale;
|
||||
};
|
||||
|
||||
const PROGMEM RegisterMap registers[] = {
|
||||
{2910, 4, 1.0}, // Status Word
|
||||
{2911, 6, 1.0}, // Min Active Value
|
||||
{2912, 5, 1.0}, // Thermal Sense
|
||||
{2913, 2, 10.0}, // Frequency
|
||||
{2914, 1, 1.0}, // Running Hours
|
||||
{2916, 1, 1.0}, // Operating Hours
|
||||
{2918, 2, 1.0}, // kWh Counter
|
||||
{2920, 2, 100.0}, // Input Power kW
|
||||
{2922, 6, 134.102}, // Input Power HP
|
||||
{2924, 2, 100.0}, // Motor Current
|
||||
{2926, 2, 100.0}, // Phase I1
|
||||
{2928, 2, 100.0}, // Phase I2
|
||||
{2930, 2, 100.0}, // Phase I3
|
||||
{2932, 7, 60.0}, // Motor RPM
|
||||
{2934, 2, 10.0}, // Motor Voltage
|
||||
{2935, 6, 1.0}, // Torque Nm
|
||||
{2936, 5, 1.0}, // Motor Thermal
|
||||
{2937, 5, 1.0}, // Heatsink Temp
|
||||
{2938, 5, 1.0}, // Card Temp
|
||||
{2939, 5, 1.0}, // Inverter Thermal
|
||||
{2940, 2, 1.0}, // DC Link Voltage
|
||||
{2941, 6, 1.0}, // Motor Torque %
|
||||
{2942, 2, 100.0}, // Inverter Nominal Current
|
||||
{2944, 2, 100.0}, // Inverter Max Current
|
||||
{2946, 4, 1.0}, // Alarm Word 1
|
||||
{2948, 4, 1.0}, // Alarm Word 2
|
||||
{2950, 4, 1.0}, // Warning Word 1
|
||||
{2952, 4, 1.0}, // Warning Word 2
|
||||
{2954, 4, 1.0}, // Power Ups
|
||||
{3000, 5, 1.0} // Over Temp Counter
|
||||
};
|
||||
|
||||
float calculateStatusWord(float* values) {
|
||||
uint16_t status = 0;
|
||||
if(values[0] > 0) status |= 0x0001; // Running
|
||||
if(values[1] > 100) status |= 0x0002; // Overload
|
||||
return status;
|
||||
}
|
||||
|
||||
float calculateThermal(float* values) {
|
||||
return (values[0] / 100.0) * 100.0;
|
||||
}
|
||||
|
||||
float calculatePower(float* values) {
|
||||
return values[0] * 0.746; // kW to HP conversion
|
||||
}
|
||||
|
||||
float calculateRPM(float* values) {
|
||||
return values[0] * 60.0;
|
||||
}
|
||||
|
||||
#endif
|
27
firmware/modbus-sd-VSD-generic-alt/util.h
Normal file
27
firmware/modbus-sd-VSD-generic-alt/util.h
Normal file
@ -0,0 +1,27 @@
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdio.h>
|
||||
|
||||
uint32_t getRegisterUInt32(uint16_t highWord, uint16_t lowWord) {
|
||||
uint32_t val = (highWord << 16) + lowWord;
|
||||
return val;
|
||||
}
|
||||
|
||||
int32_t getRegisterInt32(uint16_t highWord, uint16_t lowWord) {
|
||||
int32_t val = (highWord << 16) + lowWord;
|
||||
return val;
|
||||
}
|
||||
|
||||
int64_t getRegisterInt64(uint16_t word1, uint16_t word2, uint16_t word3, uint16_t word4) {
|
||||
uint64_t val = ((uint64_t)word1 << 48) + ((uint64_t)word2 << 32) + (word3 << 16) + word4;
|
||||
return val;
|
||||
}
|
||||
|
||||
float getRegisterFloat(uint16_t highWord, uint16_t lowWord) {
|
||||
uint32_t floatRaw = ((uint32_t)highWord << 16) | lowWord;
|
||||
float floatValue;
|
||||
|
||||
memcpy(&floatValue, &floatRaw, sizeof(float));
|
||||
return floatValue;
|
||||
}
|
||||
|
@ -16,7 +16,7 @@
|
||||
#define MODBUS_SERIAL_BAUDRATE 19200
|
||||
#define LED_A_PID 3
|
||||
#define LED_B_PID 5
|
||||
#define MAX_RETRIES 3
|
||||
#define MAX_RETRIES 1
|
||||
#define ERROR_VALUE -999.99
|
||||
|
||||
#define SPI_CLOCK SD_SCK_MHZ(50)
|
||||
@ -125,7 +125,7 @@ void getFilename(char* buffer) {
|
||||
|
||||
float readRegisterWithRetry(uint16_t addr, uint8_t regtype) {
|
||||
for(uint8_t retry = 0; retry < MAX_RETRIES; retry++) {
|
||||
delay(10);
|
||||
delay(5);
|
||||
uint8_t result = node.readHoldingRegisters(addr - 1, 2);
|
||||
if(result == node.ku8MBSuccess) {
|
||||
switch(regtype) {
|
||||
@ -147,7 +147,7 @@ float readRegisterWithRetry(uint16_t addr, uint8_t regtype) {
|
||||
Serial.print(F(", error code: "));
|
||||
Serial.println(result);
|
||||
|
||||
delay(50 * (retry + 1));
|
||||
delay(5 * (retry + 1));
|
||||
flicker(LED_B_PID, 1, 50);
|
||||
}
|
||||
return ERROR_VALUE;
|
||||
|
Loading…
Reference in New Issue
Block a user