Project: Solar/Wind PIC controlled battery array

Thread Starter

nsaspook

Joined Aug 27, 2009
13,086
Rover Elite 20 amp MPPT

Spent a little time decoding the RS485 hardware on this unit. There is no documentation about it on the vendors side and nothing on the net yet on the hardware.


RJ45 test cable color code. Found after signal tracing for a bit.

Correct A/B pins

Unit signals (half-duplex) on the left. Rx and Tx pairs are connected together inside the DB-25 connector. I should (and will) use RTS to
shutdown the master RS485 Tx converter after sending data (and the master receiver to eliminate local echo) but currently it works without it on the very short test cable. ;)


RS-232 converter to Linux PC with 9vdc battery power for the converter.


RS485 breakout cable for Oscope monitor.


Finally Rover Elite command and response signals on the scope after a little signal tracing. Pretty slow, 9600 8N1 half-duplex will take while to download all of the data from the unit.


24V 20A modbus data from the CC.

Linux Qmodbus testing program slightly modified for this units command structure.




Model data. 52 43 43 32 30 52 56 52 45 2d 47 31 RCC20RVRE-G1


Software, hardware versions. :eek: V01.00.00 and V01.00.00.
 
Last edited:

Thread Starter

nsaspook

Joined Aug 27, 2009
13,086
Modified the QMODBUS program (it uses a internal version of libmodbus that's buggy as hell) for correct RTS toggles to remove the MASTER transceiver from the bus when not talking.

The 2-wire bus goes from idle 'all off' to 'master high' for 5ms, master send data, master high 5ms, back to 'all off', slave send data, 'all off' idle.
C:
#if HAVE_DECL_TIOCSRS485 || HAVE_DECL_TIOCM_RTS
#include <sys/ioctl.h>
#define FAST_RTS_DELAY 5000
#endif
// ...
#if HAVE_DECL_TIOCM_RTS
    modbus_rtu_t *ctx_rtu = ctx->backend_data;
    if (ctx_rtu->rts != MODBUS_RTU_RTS_NONE) {
        ssize_t size;
        if (ctx->debug) {
            fprintf(stderr, "Sending request using RTS signal\n");
        }
        _modbus_rtu_ioctl_rts(ctx->s, ctx_rtu->rts == MODBUS_RTU_RTS_UP);
        usleep(FAST_RTS_DELAY);
        size = write(ctx->s, req, req_length);
        usleep(ctx_rtu->onebyte_time * req_length + FAST_RTS_DELAY);
        _modbus_rtu_ioctl_rts(ctx->s, ctx_rtu->rts != MODBUS_RTU_RTS_UP);
        return size;
    } else {
#endif

#if HAVE_DECL_TIOCM_RTS
static void _modbus_rtu_ioctl_rts(int fd, int on)
{
    //int flags;
    int RTS_flag;

    RTS_flag = TIOCM_RTS;
    if (on) {
        ioctl(fd,TIOCMBIS,&RTS_flag);//Set RTS pin
    } else {
        ioctl(fd,TIOCMBIC,&RTS_flag);//Clear RTS pin
    }
}
#endif
 
Last edited:

Thread Starter

nsaspook

Joined Aug 27, 2009
13,086
I really only need one thing from the charge controller for my battery monitor. The charging state (bulk, absorption, float, etc...) is needed to keep track of battery cycles details. It's much easier to just have the mode instead of having a state machine function on the monitor computer trying to deduce the current charging mode from voltages and currents. My plan is to have a dedicated 8-bit microcontroller (PIC18F1320) on the modbus (using the 5vdc on the RJ485 plug) that decodes the register data and sends an analog voltage (using PWM for a DAC on a digital channel) to one of the battery monitors ADC channels as a series of voltage steps [0,1,3,4,5] for each mode.

Linux libmodbus program (modified from the original temperature sensor measurement example program for my configuration) to read the current charging state/mode.
https://libmodbus.org/docs/v3.1.6/

Changes from 2 to 0 as the AC charge is turned off.

https://techsparx.com/energy-system/modbus/linux-modbus-usb-rs485.html
C:
#include <stdio.h>
#include <unistd.h>
#include <string.h>
#include <stdlib.h>
#include <errno.h>
#include <modbus/modbus.h>

const int EXCEPTION_RC = 2;

enum {
    TCP, TCP_PI, RTU
};

#define SERVER_ID 1

int main(int argc, char *argv[])
{
    modbus_t *ctx = NULL;
    uint16_t *tab_rp_bits = NULL;
    uint32_t old_response_to_sec;
    uint32_t old_response_to_usec;
    int rc;
    int server_id = SERVER_ID;

    // UPDATE THE DEVICE NAME AS NECESSARY
    ctx = modbus_new_rtu("/dev/ttyS0", 9600, 'N', 8, 1);
    if (ctx == NULL) {
        fprintf(stderr, "Could not connect to MODBUS: %s\n", modbus_strerror(errno));
        return -1;
    }

    printf("Setting slave_id %d\n", server_id);
    fflush(stdout);
    rc = modbus_set_slave(ctx, server_id);
    if (rc == -1) {
        fprintf(stderr, "server_id=%d Invalid slave ID: %s\n", server_id, modbus_strerror(errno));
        modbus_free(ctx);
        return -1;
    }
    modbus_set_debug(ctx, TRUE);
    // Not needed for USB-RS485 adapters
    // See: https://github.com/stephane/libmodbus/issues/316
    rc = modbus_rtu_set_rts(ctx, MODBUS_RTU_RTS_UP);
    if (rc == -1) {
        fprintf(stderr, "server_id=%d Failed to set serial mode: %s\n", server_id, modbus_strerror(errno));
        modbus_free(ctx);
        return -1;
    }
    modbus_set_error_recovery(ctx, MODBUS_ERROR_RECOVERY_LINK | MODBUS_ERROR_RECOVERY_PROTOCOL);

    modbus_get_response_timeout(ctx, &old_response_to_sec, &old_response_to_usec);
    if (modbus_connect(ctx) == -1) {
        fprintf(stderr, "Connection failed: %s\n", modbus_strerror(errno));
        modbus_free(ctx);
        return -1;
    }
    printf("timeout values sec %d, usec %d\n", old_response_to_sec, old_response_to_usec);

    tab_rp_bits = (uint16_t *) malloc(2 * sizeof(uint16_t));
    memset(tab_rp_bits, 0, 2 * sizeof(uint16_t));

    while (TRUE) {
        /*
         * get charging state
         */
        rc = modbus_read_registers(ctx, 0x120, 0x1, tab_rp_bits);
        if (rc == -1) {
            fprintf(stderr, "Failed to modbus_read_input_registers: %s\n", modbus_strerror(errno));
            /* modbus_free(ctx);
            return -1; */
        }

        printf("server_id=%d rc=%d Charge Controller mode=%x \n", rc, server_id, tab_rp_bits[0]);
        sleep(1);
    }

    /* Free the memory */
    free(tab_rp_bits);
    // free(tab_rp_registers);

    /* Close the connection */
    modbus_close(ctx);
    modbus_free(ctx);

    return 0;
}
 
Last edited:

Thread Starter

nsaspook

Joined Aug 27, 2009
13,086
Have my prototype MODBUS controller build from a former project board with signal headers and a daughter board.






RS485 transceiver.

I have a proper PCB ordered but it won't be here for a while (China). This allows for software development (in C18) during that time.


PWM (green) and RS485 (red&blue) throughput testing on the PIC18F1320 @40MHz PLL clock.
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,086
Completed the base code for the charge controller MODBUS monitor adapter. I'm only sending and getting one command so the MODBUS side is just a canned sequence/response with a precomputed CRC.

There are three analog output levels for the battery monitor board to process.
offline: <.5 , >4.5 volts for static voltage levels and ~2 volts for monitor running but charge controller offline.
idle: ~1 volt, Received data from the charge controller of a IDLE state.
active: ~ 4 volts, Received data from the chare controller of being in a CHARGE state.



Lots of noise from the charge controller on the signal lines but RS485 has no problem with it.


Still lots of room on the chip for code.
https://github.com/nsaspook/ihc_mon/tree/re20a

The main routine is just an FSM with a few timers to sequence enables and data flow.
C:
int8_t controller_work(void)
{
    switch (cstate) {
    case CLEAR:
        clear_2hz();
        cstate = INIT;
        break;
    case INIT:
        if (get_2hz(FALSE) > QDELAY) {
#ifdef LOCAL_ECHO
            RE_ = 0; // keep receiver active
#else
            RE_ = 1; // shutdown receiver
#endif
            DE = 1;
            V.send_count = 0;
            V.recv_count = 0;
            cstate = SEND;
            clear_500hz();
        }
        break;
    case SEND:
        if (get_500hz(FALSE) > TDELAY) {
            do {
                while (BusyUSART()); // wait for each byte
                TXREG = modbus_cc_mode[V.send_count];
            } while (++V.send_count < sizeof(modbus_cc_mode));
            while (BusyUSART()); // wait for the last byte
            cstate = RECV;
            clear_500hz();
        }
        break;
    case RECV:
        if (get_500hz(FALSE) > TDELAY) {
            DE = 0;
            RE_ = 0;
            if (V.recv_count >= sizeof(re20a_mode)) { // check received data
                if (cc_buffer[4]) {
                    LED1 = ~LED1;
                    V.pwm_volts = CC_ACTIVE;
                } else {
                    LED1 = OFF;
                    V.pwm_volts = CC_IDLE;
                }
                SetDCPWM1(V.pwm_volts);
                cstate = CLEAR;
            } else {
                if (get_500hz(FALSE) > RDELAY) {
                    LED1 = OFF;
                    cstate = CLEAR;
                    V.pwm_volts = CC_OFFLINE;
                    SetDCPWM1(V.pwm_volts);
                }
            }
        }
        break;
    default:
        break;
    }
    return 0;
}

void main(void)
{
    init_ihcmon();
    /* Loop forever */
    while (TRUE) { // busy work
        controller_work();
    }
}
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,086
Received my JCL MODBUS boards today.


Prototype -> PCB


I really like the signal quality of the new RS485 driver chip.
https://www.mouser.com/datasheet/2/609/ADM3095E-EP-1517523.pdf

The prototype board used this: http://www.ti.com/lit/ds/symlink/ds3695a.pdf

It was OK but had problems driving a fully terminated RS485 bus across the full voltage swing.

Added on the fly CRC checks to the software instead of canned CRC checks. The program space was there and it allows for better program structures to handle future enhancements of other command/responses.
C:
            /*
             * check received data for size and format
             */
            if ((V.recv_count >= sizeof(re20a_mode)) && (cc_buffer[0] == 0x01) && (cc_buffer[1] == 0x03)) {
                uint8_t temp;
                uint16_t c_crc, c_crc_rec;
                static uint8_t volts = CC_OFFLINE;

                c_crc = crc16(cc_buffer, 5);
                c_crc_rec = ((uint16_t) (cc_buffer[5] << 8)) | ((uint16_t) cc_buffer[6]);

                if (c_crc == c_crc_rec) {
                    if ((temp = cc_buffer[4])) {
                        LED1 = ~LED1;
                        switch (temp) {
                        case 1:
                            volts = CC_ACT;
                            break;
                        case 2:
                            volts = CC_MPPT;
                            break;
                        case 3:
                            volts = CC_EQUAL;
                            break;
                        case 4:
                            volts = CC_BOOST;
                            break;
                        case 5:
                            volts = CC_FLOAT;
                            break;
                        case 6:
                            volts = CC_LIMIT;
                            break;
                        default:
                            volts = CC_ACT;
                            break;
                        }
                    } else {
                        LED1 = ON;
                        volts = CC_DEACT;
                    }
                } else {
                    crc_error++;
                    LED1 = OFF;
                }
                V.pwm_volts = volts;
                SetDCPWM1(V.pwm_volts);
                cstate = CLEAR;
            } else {
                if (get_500hz(FALSE) > RDELAY) {
                    LED1 = OFF;
                    cstate = CLEAR;
                    V.pwm_volts = CC_OFFLINE;
                    SetDCPWM1(V.pwm_volts);
                }
            }
C18 modified version of the libmodbus CRC16

https://raw.githubusercontent.com/nsaspook/ihc_mon/re20a/crc.h
https://raw.githubusercontent.com/nsaspook/ihc_mon/re20a/crc.c
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,086
This is the final spin of the MODBUS charge controller board. Yes, it's the pretty black and ENIG-RoHS JLC PCB.

Same as the original 1.0 with added digital I/O signals for remote programming of the charge controller via MODBUS and a few more SMD parts.

The remote DEV computer (my old DL-360) and network is running on Solar power.


Idle power, computer unplugged ~30W


Computer active power ~380W. Not bad for an old server class machine.
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,086
Hola nsaspook

Coul you post a block diagram of the whole thing? Interesting.
Solar_diagram.png

The three current sensors (2 100A and one 200A) combined with voltage monitor points at all important system links (10 analog 13-bit ADC channel ports) allow for complete voltage, current, power, efficiency and expected runtime calculations. Digital I/O ports control system relays, controllers and AC power flow. The MODBUS controller enables on-the-fly charge controller state monitoring and control.
 
Last edited:

Thread Starter

nsaspook

Joined Aug 27, 2009
13,086
All of the major sub-components are working as a system. Two blinks on the MODBUS interface indicates MPPT on the charge controller and a 2 display on the main controller MPPT display line means it has that data for the control algorithm.

Info displays from the main controller.


 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,086
Converted the old C18 style code to XC8 2.10 C99. No plib or MCC for this chip so SFR programming is used to configure the needed modules. The code generated is much better and smaller using level 2 optimizations.

The boards and DIN style enclosures.
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,086
Most of the baseline functions are done in the monitor so it's time to check critical timing. An external unit like the DS3231 keeps very accurate Time Of Day but here we need accurate time unit signals (interrupts) every second The system uses two, second clocks. One second clock (tmr5) handles high priority level time of day functions and a few static timing tasks. The other second clock (tmr3) handles low priority compute tasks like battery state tracking , time based power and run-time calculations designed to be safe when preempted by the high priority tasks triggered by tmr5. Both clocks should be as close as possible to the actual time units they represent.

Don't trust a DSO as a precision frequency counter but this is not bad.


CPU clock chip. https://www.mouser.com/datasheet/2/909/kc5032a_cm_e-1771802.pdf


Timing for 1 second interrupts using the MCC code generator for 5ms ticks and callbacks. Period with a 10 second gate. 2.0 exactly is what we are looking for but it's a little over 2.0 due to latency and context saving timing.

By adjusting the number of callbacks slightly we can tune in the correct counts a bit for that 10 second period.

Now the actual time is much closer to the time units used for calculations. It might see a small amount but this unit is expected to run 7/24 for months so any source of errors builds up.
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,086
The difference between a good and a poor IMO current sensor using a precision voltmeter.


Loop for battery wire connection. Disconnected during testing.

Honeywell CSLT6B100 100A zero current voltage. SD of 86 microvolts, very good. https://sensing.honeywell.com/CSLT6B100-open-loop-current-sensors



Tamura 200A zero current voltage. SD ~ 1.6 millivolt. https://www.mouser.com/datasheet/2/397/L01ZXXXS05-274998.pdf
I wanted to use this one because the larger battery wire slips right through but it's just not very good. Both sensors on the same channel with the same software on the controller with the voltmeter on the sensor output connection. I tested two of the Tamura units with about the same results. No idea why it jumps so much but this model seems unusable as a precision current sensor.
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,086
The connector was there (SL2) already there for PWM diversion control on the board design so I finally coded up something for PV side excess power loadin.

C:
/*
* DC PWM diversion for direct PV power before MPPT
*/
bool pv_diversion(bool kill)
{
    static uint16_t pwm_val = 0;
    static bool pwm_active = false;

    if (kill) {
        pwm_val = 0;
        V.mode_pwm = 0;
        pwm_active = false;
        diversion_pwm_set(V.mode_pwm); // 10KHz PWM quick stop
        return false;
    }

    if ((((cc_state(C.v_cmode) == M_FLOAT) || (cc_state(C.v_cmode) == M_BOOST)) && (C.calc[V_PV] > DPWM_LOW_VOLTS))) {
        if (!pwm_active) {
            pwm_active = true;
            /*
             * setup PWM start conditions
             */
            C.start_power = C.p_pv; // save for later possible display
        }
        if (C.p_pv < PWM_MAX_POWER) { // increase power
            if (++pwm_val > DPWM_FULL)
                pwm_val = DPWM_FULL; // max PWM limiter
        }

        if (C.p_pv > PWM_MAX_POWER) { // decrease power
            if (V.mode_pwm)
                V.mode_pwm--;
        }

        V.mode_pwm = pwm_val;
        diversion_pwm_set(V.mode_pwm); // 10KHz PWM ramp up
        return true;
    } else {
        if (V.mode_pwm)
            V.mode_pwm--;

        diversion_pwm_set(V.mode_pwm); // 10KHz PWM ramp down
        pwm_val = 0;
        pwm_active = false;
        return false;
    }
}

/*
* low-pri interrupt ISR the runs every second for simple coulomb counting
*/
void calc_bsoc(void)
{
    uint8_t * log_ptr, lcode = D_CODE;
    static uint8_t log_update_wait = 0;
    float adj = 1.0;

#ifdef DEBUG_BSOC1
    DEBUG1_SetHigh();
#endif

    /*
     * check for excess power and send to DC dump load
     */
    pv_diversion(false);

// rest of code
}
Didn't test it much as I not planning to use load dumping.
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,086
My network host for the monitor is a RPi3 powered from the inverter. It's job is to provide UNIX time updates to the controller for accurate daily logging of events, interface the NFS filesystem for data logging and number crunching for graphs using RRDtool. A 115200 bps RS-232 serial line connects the two units. The simple time protocol, a single command character 'T' from the monitor at boot, sends a formatted ASCII string to the monitor for translation to UTC using the one second tmr6 on the controller to update seconds in UNIX time. The other data from the controller to RPi is comma separated data strings to be reformatted for RRTool and other programs.


Three days of data charted using libreoffice. Top Blue PV voltage, Middle Green battery/charging voltages, Bottom PV/inverter/charger currents.
A section of C code from the time server and data logger on the RPi.
C:
/*
 * read from the serial port, check for time T command and log data to storage file
 */
int get_log(int mode)
{
    char read_buf[256], msg[256];
    int num_bytes, rcode = 0;

    num_bytes = read(serial_port, &read_buf[0], sizeof(read_buf));
    if (num_bytes < 0) {
        printf("Error reading: %s\r\n", strerror(errno));
        return errno;
    }

    file_port = open(LOG_FILE, O_RDWR | O_APPEND);
    if (file_port < 0) {
        printf("File Error %i from open: %s\r\n", errno, strerror(errno));
        return errno;
    } else {
        if (num_bytes) {
            printf("Read %i bytes. Received message: %c\r\n", num_bytes, read_buf[0]);
            if (read_buf[0] == 'T') { // process the T server time command
                int k = 0;
                // Write to serial port
                sprintf(msg, "T%lut", time(0)); // format UNIX time in ASCII
                do {
                    write(serial_port, &msg[k], 1); // use gaps between bytes for slow controller time processing
                    usleep(1000);
                } while (k++ < strlen(msg));

                printf("Send time %s\r\n", msg);
                rcode = 1;
            } else { // just write the serial buffer to the log file
                write(file_port, &read_buf[0], num_bytes);
            }
        }

        close(file_port);
    }
    return rcode;
}
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,086
With temps heading into the high 80's soon, it's time to warm up the old 12vdc battery bank and track the new AGM battery performance with my old software system.



Web frontend on the PIC32, AC unit startup.


Detailed System status from the PIC18 DAQ monitor using the PIC32 telnet host.
 
Last edited:
Top