PIC32MK MCJ motor controller and sensor node for CANBUS

Thread Starter

nsaspook

Joined Aug 27, 2009
13,081
It's mini 4 layer PCB design using the PIC32MK0512MCJ048 controller. Programmed using Mplabx, XC32 and the Harmony3 framework. The CANBUS host is the MCJ dev board.

1664063973804.png
Test board with I/O breakout.
1664064033696.png
1664064108007.png
1664064148399.png
Onboard support for BMA490L, SCA3300 and SCL3300 with the SLC3300 being the device of choice.
https://www.mouser.com/datasheet/2/281/1/datasheet_scl3300_d01-1532018.pdf

I/O support via microsockets: https://www.mouser.com/datasheet/2/527/mle_sm-2854426.pdf
1664065638903.png
Sensor data capture via the serial port.

SPI, TTL UART, QEI encoder, motor control PWW, 12-bit ADC and DAC with precision VREF, GPIO, reset and ICSP/CANBUS on 0.100 connectors.
1664065696055.png
A demo test of the CANBUS capability moving sensor data to the host using CAN-FD 1MHz header and 2MHz data. https://en.wikipedia.org/wiki/CAN_FD
The external Waveshare SN65HVD230 module is the CAN interface chip for the board.
 
Last edited:

Thread Starter

nsaspook

Joined Aug 27, 2009
13,081
Some software tidbits.
C:
#ifdef BMA490L
/*
 * BMA490L instance
 */
imu_cmd_t imu0 = {
    .tbuf[0] = CHIP_ID | RBIT,
    .online = false,
    .device = IMU_BMA490L, // device type
    .cs = IMU_CS, // chip select number
    .run = false,
    .log_timeout = BMA_LOG_TIMEOUT,
    .update = true,
    .features = false,
    .spi_bytes = 1,
    .op.info_ptr = &bma490_version,
    .op.imu_set_spimode = &bma490l_set_spimode,
    .op.imu_getid = &bma490l_getid,
    .op.imu_getdata = &bma490l_getdata,
    .acc_range = range_4g,
};
#endif

#ifdef SCA3300
/*
 * SCA3300-D01 instance
 */
imu_cmd_t imu0 = {
    .tbuf32[SCA3300_TRM] = SCA3300_SWRESET_32B,
    .online = false,
    .device = IMU_SCA3300, // device type
    .cs = IMU_CS, // chip select number
    .run = false,
    .crc_error = false,
    .log_timeout = SCA_LOG_TIMEOUT,
    .update = true,
    .features = false,
    .spi_bytes = 4,
    .op.info_ptr = &sca3300_version,
    .op.imu_set_spimode = &sca3300_set_spimode,
    .op.imu_getid = &sca3300_getid,
    .op.imu_getdata = &sca3300_getdata,
    .acc_range = range_15gl,
    .acc_range_scl = range_inc1,
    .angles = false,
};
#endif
Each type of 'IMU' has a data/function 'object' for it so we can use a little bit of OOP structure in the main loop.
C:
    /*
     * function pointer templates structure
     * for the device I/O routines and data
     */
    typedef struct _op_t {
        void (*info_ptr)(void);
        void (*imu_set_spimode)(void *);
        bool (*imu_getid)(void *);
        bool (*imu_getdata)(void *);
    } op_t;

    /*
     * IMU data structure for driver
     */
    typedef struct _imu_cmd_t {
        uint8_t device, cs, acc_range, spi_bytes, acc_range_scl;
        uint8_t rbuf[64], tbuf[64];
        uint32_t rbuf32[2], tbuf32[2], log_timeout, rs, ss;
        volatile bool online, run, update, features, crc_error, angles;
        op_t op;
    } imu_cmd_t;

    struct sca3300_data {

        struct {
            int16_t channels[9];
            uint16_t ret_status;
            uint32_t ts;
        } scan;
        uint8_t rs;
        uint8_t ss;
    };
C:
int main(void)
{
    uint8_t rxe, txe, times = 0;
    /* Initialize all modules */
    SYS_Initialize(NULL);

    /* Start system tick timer */
    CORETIMER_Start();
    delay_freq = CORETIMER_FrequencyGet() / 1000000;
    /*
     * software timers interrupt setup
     * using tickCount
     */
    TMR6_CallbackRegister(timer_ms_tick, 0);
    TMR6_Start(); // software timers counter

#ifdef __32MK0512MCJ048__
    TMR9_Start(); // IMU time-stamp counter
#endif
#ifdef __32MZ1025W104132__
    TMR2_Start(); // IMU time-stamp counter
#endif

    printf("\r\nPIC32 %s Controller %s %s %s ---\r\n", IMU_ALIAS, IMU_DRIVER, build_date, build_time);

    /*
     * print the driver version
     */
    imu0.op.info_ptr(); // print driver version on the serial port
    imu0.op.imu_set_spimode(&imu0); // setup the IMU chip for SPI comms, X updates per second @ selected G range

    /*
     * start the graphic LCD driver
     */
    lcd_version();
    init_lcd_drv(D_INIT);
    OledClearBuffer();
    sprintf(buffer, "%s Controller %s", IMU_ALIAS, IMU_DRIVER);
    eaDogM_WriteStringAtPos(15, 0, buffer);
    OledUpdate();

    /*
     * check to see if we actually have a working IMU
     */
    StartTimer(TMR_IMU, IMU_ID_DELAY);
    ADCHS_ChannelConversionStart(ADCHS_CH0);
    ADCHS_ChannelConversionStart(ADCHS_CH1);
    while (!imu0.op.imu_getid(&imu0)) {
        LED_RED_Toggle();
        LED_GREEN_Toggle();
        if (TimerDone(TMR_IMU)) {
            while (true) {
                if (TimerDone(TMR_IMU)) {
                    LED_RED_Toggle();
                    LED_GREEN_Toggle();
                    printf(" IMU NO ID, %d %d \r\n", ADCHS_ChannelResultGet(ADCHS_CH0), ADCHS_ChannelResultGet(ADCHS_CH1));
                    StartTimer(TMR_IMU, 200);
                    ADCHS_ChannelConversionStart(ADCHS_CH0);
                    ADCHS_ChannelConversionStart(ADCHS_CH1);
                }
            }
        }
    };
    printf(" IMU ID OK, device type %d: %d %d \r\n", imu0.device, ADCHS_ChannelResultGet(ADCHS_CH0), ADCHS_ChannelResultGet(ADCHS_CH1));
    LED_RED_Off();
    LED_GREEN_Off();
    WaitMs(500);

    // loop collecting data
    StartTimer(TMR_LOG, imu0.log_timeout);
    while (true) {
        /* Maintain state machines of all polled MPLAB Harmony modules. */
        SYS_Tasks();

        /*
         * data logging routine
         * convert the SPI XYZ response to standard floating point acceleration values and rolling integer time-stamps per measurement
         */
        if (imu0.update || TimerDone(TMR_LOG)) {
            OledClearBuffer();
            imu0.op.imu_getdata(&imu0); // read data from the chip
            imu0.update = false;
            getAllData(&accel, &imu0); // convert data from the chip
We call the device specific operations using function pointers in the imu0.op structure to load raw 16-bit IMU values using SPI. We then convert those raw values to standard gravity units and angles.
C:
/* 
 * File:   imu.h
 * Author: root
 *
 * Created on September 19, 2022, 8:50 AM
 */

#ifndef IMU_H
#define    IMU_H

#ifdef    __cplusplus
extern "C" {
#endif

#include <stddef.h>                     // Defines NULL
#include <stdbool.h>                    // Defines true
#include <stdlib.h>                     // Defines EXIT_FAILURE
#include <math.h>
#include "definitions.h"                // SYS function prototypes
#include "imupic32mcj.h"

#define IMU_DRIVER    "V1.004" 
#define IMU_ALIAS    "IMU"

#define IMU_ID_DELAY    100
    /*
     * what IMU chip are we using
     */
    //#define BMA490L
#define SCA3300 // this includes the SCL3300 device

#define IMU_DATA_RAW_LEN        30
#define IMU_DATA_BUFFER_INDEX        1

    typedef struct {
        double x; /**< X-axis sensor data */
        double y; /**< Y-axis sensor data */
        double z; /**< Z-axis sensor data */
        double xa; /**< X-angle sensor data */
        double ya; /**< Y-angle sensor data */
        double za; /**< Z-angle sensor data */
        uint32_t sensortime; /**< sensor time */
        double sensortemp;
        uint8_t buffer[64]; // can-fd frame buffer space
    } sSensorData_t;

    /*
     * function pointer templates structure
     * for the device I/O routines and data
     */
    typedef struct _op_t {
        void (*info_ptr)(void);
        void (*imu_set_spimode)(void *);
        bool (*imu_getid)(void *);
        bool (*imu_getdata)(void *);
    } op_t;

    /*
     * IMU data structure for driver
     */
    typedef struct _imu_cmd_t {
        uint8_t device, cs, acc_range, spi_bytes, acc_range_scl;
        uint8_t rbuf[64], tbuf[64];
        uint32_t rbuf32[2], tbuf32[2], log_timeout, rs, ss;
        volatile bool online, run, update, features, crc_error, angles;
        op_t op;
    } imu_cmd_t;

    struct sca3300_data {

        struct {
            int16_t channels[9];
            uint16_t ret_status;
            uint32_t ts;
        } scan;
        uint8_t rs;
        uint8_t ss;
    };

    enum device_type {
        IMU_BMA490L = 0, // IMU chip model
        IMU_SCA3300,
        IMU_SCL3300,
    };

    enum accel_g {
        range_2g = 0,
        range_4g,
        range_8g,
        range_16g,
        range_scale,
        range_15g,
        range_3g,
        range_6g,
        range_15gl,
        range_12g,
        range_24g,
        range_inc1,
        range_inc2,
    };

    enum sca3300_scan_indexes {
        SCA3300_ACC_X = 0,
        SCA3300_ACC_Y,
        SCA3300_ACC_Z,
        SCA3300_TEMP,
        SCA3300_TIMESTAMP,
        SCL3300_ANG_X,
        SCL3300_ANG_Y,
        SCL3300_ANG_Z,
    };

    /*! Earth's gravity in m/s^2 */
#define GRAVITY_EARTH            (9.80665)    
    /*
     * device earth gravity range calibration scalars
     */
#define BMA490_ACCEL_MG_LSB_2G        0.000061035    ///< Macro for mg per LSB at +/- 2g sensitivity (1 LSB = 0.000061035mg) */
#define BMA490_ACCEL_MG_LSB_4G        0.000122070    ///< Macro for mg per LSB at +/- 4g sensitivity (1 LSB = 0.000122070mg) */
#define BMA490_ACCEL_MG_LSB_8G        0.000244141    ///< Macro for mg per LSB at +/- 8g sensitivity (1 LSB = 0.000244141mg) */
#define BMA490_ACCEL_MG_LSB_16G        0.000488281    ///< Macro for mg per LSB at +/- 16g sensitivity (1 LSB = 0.000488281mg) */
#define IMU_ACCEL_MG_SCALE        1.000000000
#define SCA3300_ACCEL_MG_LSB_15G    0.000207000    ///< Macro for mg per LSB at +/- 1.5g sensitivity    LSB/g 5400
#define SCA3300_ACCEL_MG_LSB_3G        0.000395000    ///< Macro for mg per LSB at +/- 3g sensitivity        LSB/g 2700
#define SCA3300_ACCEL_MG_LSB_6G        0.000765000    ///< Macro for mg per LSB at +/- 6g sensitivity        LSB/g 1350
#define SCL3300_ACCEL_MG_LSB_12G    0.000167400    ///< Macro for mg per LSB at +/- 1.2g sensitivity    LSB/g 6000
#define SCL3300_ACCEL_MG_LSB_24G    0.000333800    ///< Macro for mg per LSB at +/- 2.4g sensitivity    LSB/g 3000
#define SCL3300_INC1            0.000083700
#define SCL3300_INC2            0.000083700

#define ANGLE_RES1        16384.0
#define ANGLE_RES2        90.0
#define TEMPERATURE_RES        18.9
#define TEMPERATURE_OFFSET    -273.0

    double get_imu_scale(imu_cmd_t *);
    void getAllData(sSensorData_t *, imu_cmd_t *);

#ifdef    __cplusplus
}
#endif

#endif    /* IMU_H */
C:
#include "imu.h"

const double imu_table[] = {
    BMA490_ACCEL_MG_LSB_2G,
    BMA490_ACCEL_MG_LSB_4G,
    BMA490_ACCEL_MG_LSB_8G,
    BMA490_ACCEL_MG_LSB_16G,
    IMU_ACCEL_MG_SCALE,
    SCA3300_ACCEL_MG_LSB_15G,
    SCA3300_ACCEL_MG_LSB_3G,
    SCA3300_ACCEL_MG_LSB_6G,
    SCL3300_ACCEL_MG_LSB_12G,
    SCL3300_ACCEL_MG_LSB_24G,
    SCL3300_INC1,
    SCL3300_INC2,
};

static uint32_t sensortime;

static void move_bma490_transfer_data(uint8_t *, imu_cmd_t *);

extern struct sca3300_data sdata;

double get_imu_scale(imu_cmd_t * imu)
{
    double accelRange = IMU_ACCEL_MG_SCALE;

    if (imu) { // null pointer check
        /*
         * load the proper scaling constants
         */
        switch (imu->acc_range) {
        case range_16g:
            accelRange = BMA490_ACCEL_MG_LSB_16G * GRAVITY_EARTH * IMU_ACCEL_MG_SCALE;
            break;
        case range_8g:
            accelRange = BMA490_ACCEL_MG_LSB_8G * GRAVITY_EARTH * IMU_ACCEL_MG_SCALE;
            break;
        case range_4g:
            accelRange = BMA490_ACCEL_MG_LSB_4G * GRAVITY_EARTH * IMU_ACCEL_MG_SCALE;
            break;
        case range_15g:
        case range_15gl:
            accelRange = SCA3300_ACCEL_MG_LSB_15G * GRAVITY_EARTH * IMU_ACCEL_MG_SCALE;
            break;
        case range_3g:
            accelRange = SCA3300_ACCEL_MG_LSB_3G * GRAVITY_EARTH * IMU_ACCEL_MG_SCALE;
            break;
        case range_6g:
            accelRange = SCA3300_ACCEL_MG_LSB_6G * GRAVITY_EARTH * IMU_ACCEL_MG_SCALE;
            break;
        case range_12g:
            accelRange = SCL3300_ACCEL_MG_LSB_12G * GRAVITY_EARTH * IMU_ACCEL_MG_SCALE;
            break;
        case range_24g:
            accelRange = SCL3300_ACCEL_MG_LSB_24G * GRAVITY_EARTH * IMU_ACCEL_MG_SCALE;
            break;
        case range_inc1:
            accelRange = SCL3300_INC1 * GRAVITY_EARTH * IMU_ACCEL_MG_SCALE;
            break;
        case range_inc2:
            accelRange = SCL3300_INC2 * GRAVITY_EARTH * IMU_ACCEL_MG_SCALE;
            break;
        case range_2g:
            accelRange = BMA490_ACCEL_MG_LSB_2G * GRAVITY_EARTH * IMU_ACCEL_MG_SCALE;
            break;
        default:
            if (imu->device == IMU_BMA490L) {
                accelRange = BMA490_ACCEL_MG_LSB_2G * GRAVITY_EARTH * IMU_ACCEL_MG_SCALE;
                imu->acc_range = range_2g; // update imu data structure
            } else {
                if (imu->device == IMU_SCA3300) {
                    accelRange = SCA3300_ACCEL_MG_LSB_15G * GRAVITY_EARTH * IMU_ACCEL_MG_SCALE;
                    imu->acc_range = range_15g; // update imu data structure
                } else {
                    accelRange = SCL3300_ACCEL_MG_LSB_12G * GRAVITY_EARTH * IMU_ACCEL_MG_SCALE;
                    imu->acc_range = range_12g; // update imu data structure
                }
            }
            break;
        }
    }

    return accelRange;
}

void getAllData(sSensorData_t *accel, imu_cmd_t * imu)
{
    uint8_t data[IMU_DATA_RAW_LEN + 2] = {0}; // add space for dummy data
    int16_t x = 0, y = 0, z = 0;
#ifdef SCA3300
    int16_t xa = 0, ya = 0, za = 0;
#endif
    double accelRange;

    accelRange = get_imu_scale(imu);

    // munge data to proper format for logging
    if (imu) { // null pointer check
        if (accel) { // null pointer check
            if (imu->device == IMU_BMA490L) {
                move_bma490_transfer_data(data, imu);
                sensortime = (data[9] << 16) | (data[8] << 8) | data[7]; // 24-bit sensor time
                sdata.scan.ts = sensortime;
                x = (int16_t) (((uint16_t) data[2] << 8) | data[1]); // 16-bit xyz data
                sdata.scan.channels[SCA3300_ACC_X] = x;
                y = (int16_t) (((uint16_t) data[4] << 8) | data[3]);
                sdata.scan.channels[SCA3300_ACC_Y] = y;
                z = (int16_t) (((uint16_t) data[6] << 8) | data[5]);
                sdata.scan.channels[SCA3300_ACC_Z] = z;
                accel->sensortime = sensortime; // time log each accel measurement from IMU
            }
#ifdef SCA3300
            x = sdata.scan.channels[SCA3300_ACC_X];
            y = sdata.scan.channels[SCA3300_ACC_Y];
            z = sdata.scan.channels[SCA3300_ACC_Z];
            accel->sensortime = sdata.scan.ts; // time log each accel measurement from TIMER
            accel->sensortemp = TEMPERATURE_OFFSET + (sdata.scan.channels[SCA3300_TEMP] / TEMPERATURE_RES);
            if (imu->device == IMU_SCL3300) {
                xa = sdata.scan.channels[SCL3300_ANG_X];
                ya = sdata.scan.channels[SCL3300_ANG_Y];
                za = sdata.scan.channels[SCL3300_ANG_Z];
                accel->xa = xa / ANGLE_RES1 * ANGLE_RES2; // scale angle data
                accel->ya = ya / ANGLE_RES1 * ANGLE_RES2;
                accel->za = za / ANGLE_RES1 * ANGLE_RES2;
            }
#endif
            accel->x = x * accelRange; // scale to the correct units
            accel->y = y * accelRange;
            accel->z = z * accelRange;
        }
    }
}

/*
 * load raw SPI sensor data from IMU and transfer to the logging processing buffer
 */
void move_bma490_transfer_data(uint8_t *pBuf, imu_cmd_t * imu)
{
    if (pBuf && imu) { // null pointer checks
        for (uint32_t i = IMU_DATA_BUFFER_INDEX; i < IMU_DATA_RAW_LEN; i++) {
            pBuf[i - IMU_DATA_BUFFER_INDEX] = imu->rbuf[i];
        }
    }
}
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,081
The CAN-FD module connected to another CAN-FD host sending the received data via USB serial to a Linux host running a JAVA 3D cube data visualization demo.
I can easily get 1000 SPS from the IMU controller over the wire using 2MHz 64 byte data CAN-FD payloads for IMU data.
1664666419611.png

The cube demo data sample rate is more practical. This scope only decodes CAN, not CAN-FD so it can read headers correctly but not the data fields.
1664666624652.png

https://www.ni.com/en-us/innovation...ing-can-with-flexible-data-rate--can-fd-.html
 
Last edited:

Thread Starter

nsaspook

Joined Aug 27, 2009
13,081
Two of the different types of IMU devices the module supports.
1664854444665.png
1664854985023.png
The tiny LGA-12 on the right is the BMA490L that unfortunately is EOL by Bosch. The socket next to the IMU chips in the SPI2 diag port to monitor the communications waveforms seen on the oscope.

1664854590254.png
32-bit SPI comms on the SCL3300

1664854635845.png
8-bit SPI comms on the BMA490L
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,081
PWM motor control with IMU control testing.
1665368684383.png
Using a cheap h-bridge module with a 9v battery to limit motor power during testing. It handles 30kHz 12-bit PWM easily
1665368805956.png
PWM out connector wiring.

 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,081
Motor Control PWM dead-time example:
1665594525848.png

1665594602824.png
Leading and trailing dead-time added. Green/Yellow, PWM signals from controller, Blue/Red open circuit H-bridge motor outputs.

1665594773081.png
H-bridge output shift while driving an inductive motor with dead-time added to minimize pulse overlap and shoot-through.

1665595072937.png
PWM pulses with no dead-time driving a motor with possible shoot-through effects.

https://www.allaboutcircuits.com/te...h-modulation-pwm-shoot-through-dead-time-pwm/

1665595568588.png
http://ww1.microchip.com/downloads/en/DeviceDoc/60001393A.pdf
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,081
Some DSP functions for the sensor node that can be sent via CANBUS. Hardware floating point is nice.

1667930087440.png
Time per 256 8-bit sample FFT transform. The FFT functions use doubles internally but the input samples were scaled down to match low-rez display requirements.
C:
            /*
             * load FFT sample 256 element 8-bit buffer
             * as we process each IMU 3-axis sample
             * This is not a pure FFT as it mixes bin data
             * with sample data for a feedback signature
             */
            inB[ffti] = 128 + (uint8_t) (120.0 * accel.z); // select one axis for display
            sprintf(buffer, "FFTs %3d,%3d ", inB[ffti], ffti);
            eaDogM_WriteStringAtPos(7, 4, buffer);
            ffti++;
            TP3_Set(); // FFT processing timing mark
            do_fft(false); // convert to 128 frequency bins in 8-bit sample buffer
            TP3_Clear(); // end of FFT function
            TP3_Set(); // drawing processing mark
            w = 0;
            while (w < 128) {
                fft_draw(w, inB[w]); // create screen graph from bin data
                w++;
            }
            TP3_Clear(); // end of drawing function
https://raw.githubusercontent.com/nsaspook/wfi32/wfi/firmware/src/fft.c
 

geekoftheweek

Joined Oct 6, 2013
1,201
Pretty interesting. it looks like you probably have more than a couple hours in so far. Is this part of a bigger project or something that can be used by itself?
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,081
Pretty interesting. it looks like you probably have more than a couple hours in so far. Is this part of a bigger project or something that can be used by itself?
It's part of a larger work related sensor network project for some new equipment to predict failures from vibration and a few other factors.
 

geekoftheweek

Joined Oct 6, 2013
1,201
Such a device would have been awesome about 15 years ago when all but one hub bolt broke on a plastic bottle molder I was running broke. There were no apparent warning signs at the time, then it quit running, and a couple hundred gallons of coolant were pumped out onto the floor once the gasket let loose. I didn't notice right away as I was cleaning up bottles that were falling over in the back corner due to things not yet being dialed in after a production change (I just wanted a second to breathe)... boss man gave me a rotten look and went running to the back to turn off the coolant pump.

It's amazing some of the ways people have found to use vibration to monitor various aspects of processes. Some of them I would have never thought possible. Good luck!
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,081
Such a device would have been awesome about 15 years ago when all but one hub bolt broke on a plastic bottle molder I was running broke. There were no apparent warning signs at the time, then it quit running, and a couple hundred gallons of coolant were pumped out onto the floor once the gasket let loose. I didn't notice right away as I was cleaning up bottles that were falling over in the back corner due to things not yet being dialed in after a production change (I just wanted a second to breathe)... boss man gave me a rotten look and went running to the back to turn off the coolant pump.

It's amazing some of the ways people have found to use vibration to monitor various aspects of processes. Some of them I would have never thought possible. Good luck!
As usual today, with advanced sensors and networks, the problem is not getting data, the problem is finding the nugget in the noise and preventing false triggers when there are large numbers of potential monitor points. Each node will have the controller power to process signals for baseline signatures of normal events in the hope that false triggers will be reduced. It's all in the RD stage for now.
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,081
Working on the data host to collect and forward the data from the 3-axis vibration sensors. A PIC32MK MCJ CURIOSITY PRO is the DEV board until a custom PCB is designed once most of the HW/SW functionality is set.
https://ww1.microchip.com/downloads...MCJ-Curiosity-Pro-Users-Guide-DS70005421A.pdf

The data link to the main Linux machine is a USB serial Virtual COM port (VCOM) connection at 115200bps. I plan to use serial attached ethernet on the final CAN-FD host version with the processed data saved in a remote Mysql database as VARCHAR Types with keys for sensor id, processor id, sensor timestamps and local-time.

Currently optimizing some simple data protocols using UART DMA transfers to reduce blocking time on the MCU to increase the number of sensors each can handle. 31 FIFOs Configurable as transmit or receive FIFOs (with interrupts when new messages are received or when messages are transmitted successfully) should easily buffer the incoming CAN-FD data streams but the USB serial external data line is a CPU/time bottleneck currently during testing.

With blocking UART I/O as the default when using STDIO debugging with printf the cpu usage results are not very good.
1668794633132.png
Yellow trace toggles with each new packet received. The purple trace is CPU time sending the processed packet out the serial port. It's the same as transmission time. :eek:


With reworked code for serial port DMA.
1668794858914.png
Yellow trace to serial port data transmission time. Purple trace is cpu usage per serial buffer transmission. A small fraction of serial transmission time without the 115200bps interrupt load on the MPU from simple ring-buffers.

C:
static volatile bool uart1_dma_busy = false;
char uart_buffer[256];

// code frag
                if (*mtype == CAN_FFT_HI) {
                    fft = (sFFTData_t *) rx_message;
                    sprintf(uart_buffer, "%3d,%7X,%3d\r\n", fft->id, rx_messageID, fft_bin_total(fft, 0));
#ifndef SHOW_DATA
#endif
                }
                if (*mtype == CAN_NULL) {
                    sprintf(uart_buffer, "0,NULL Message with 0 ID code\r\n");
                }
                LED_Set(); // cpu trace signal
                LEDY_Set(); // serial trace signal
                UART1DmaWrite(uart_buffer, strlen(uart_buffer));
                LED_Clear(); // cpu trace signal
C:
#ifdef USE_SERIAL_DMA
void UART1DmaChannelHandler_State(DMAC_TRANSFER_EVENT, uintptr_t);
void UART1DmaWrite(char *, uint32_t);

/*
* end of uart buffer complete flag handler callback
* interrupt handler for the completion of buffer transfer.
*/
void UART1DmaChannelHandler_State(DMAC_TRANSFER_EVENT event, uintptr_t contextHandle)
{
    uart1_dma_busy = false;
    LEDY_Clear(); // serial trace signal
}

/*
* DMA uart serial function
* triggers the DMA transfer and returns, only one interrupt happens at the end of transfer
*/
void UART1DmaWrite(char * buffer, uint32_t len)
{
    while (uart1_dma_busy) { // should never wait in normal operation
    };

    uart1_dma_busy = true;  // in process flag
    DMAC_ChannelTransfer(DMAC_CHANNEL_7, (const void *) buffer, (size_t) len, (const void*) &U1TXREG, (size_t) 1, (size_t) 1);
}
#endif

// in main
#ifdef USE_SERIAL_DMA
    DMAC_ChannelCallbackRegister(DMAC_CHANNEL_7, UART1DmaChannelHandler_State, 0); // end of UART buffer transfer interrupt function
#endif
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,081
Now we need to save that serial data on the Linux machine for easy network access on any desktop computer.

First there is a simple Java program on the Linux host to connect to the USB to serial port, buffer that IMU serial data stream into a string and parse the string into data tokens. The data tokens are then used to form a Mysql INSERT statement to add a new row of data to a central remote database using Connector/J.
https://mariadb.com/docs/ent/connect/programming-languages/java/
Code:
package cube;

import java.util.Scanner;
import com.fazecast.jSerialComm.SerialPort;

import java.sql.*;
import java.util.Properties;
import java.sql.Connection;
import java.sql.DriverManager;
import java.sql.SQLException;

/**
*
* @author root
*/
public class Cube {

    public static void main(String[] args) {

        //serial connection
        SerialPort port = SerialPort.getCommPort("ttyACM0"); // USB serial connection
        port.setBaudRate(115200);
        port.setComPortTimeouts(SerialPort.TIMEOUT_SCANNER, 1, 1);
        if (port.openPort() == false) {
            System.err.println("Unable to open the serial port. Exiting.");
            System.exit(1);
        }

        Properties connConfig = new Properties();
        connConfig.setProperty("user", "minty");
        connConfig.setProperty("password", "");

        Scanner s = new Scanner(port.getInputStream()); // eat first line
        s = new Scanner(port.getInputStream());
        System.err.println("Scanner.");
        while (s.hasNextLine()) {
            String fftd = "";
            try {

                String line = s.nextLine();
                String[] token = line.split(",");
//                System.err.println(token[1]);

                if (token[0].equals("  1")) {
                    System.out.println(String.format("dtype = %3s  device = %s : %s", token[0], token[1], line));
                    token[2] = "";
                }
                if (token[0].equals("  2")) {
                    System.out.println(String.format("dtype = %3s  device = %s cpu = %s : %s", token[0], token[1], token[2], line));
                }
                if (token[0].equals("  8")) {
                    System.out.println(String.format("dtype = %3s  device = %s hit  low = %s : %s", token[0], token[1], token[2], line));
                    fftd = token[2];
                    token[2] = "";
                }
                if (token[0].equals("  9")) {
                    System.out.println(String.format("dtype = %3s  device = %s hit high = %s : %s", token[0], token[1], token[2], line));
                    fftd = token[2];
                    token[2] = "";
                }

                try {
                    Connection conn = DriverManager.getConnection("jdbc:mariadb://10.1.1.172/", connConfig);

                    // Prepare INSERT Statement to Add IMU data
                    try ( PreparedStatement prep = conn.prepareStatement(
                            "INSERT INTO hits.imu (dtype, device, cpu, str,fft) VALUES (?, ?, ?, ?, ?)",
                            Statement.RETURN_GENERATED_KEYS)) {
                        // Add IMU packet data
                        prep.setString(1, token[0]);
                        prep.setString(2, token[1]);
                        prep.setString(3, token[2]);
                        prep.setString(4, line);
                        prep.setString(5, fftd);
                        prep.addBatch();

                        // Execute Prepared Statements in Batch
//                        System.out.println("Batch Counts");
                        int[] updateCounts = prep.executeBatch();
                        for (int count : updateCounts) {
                            // Print Counts
//                            System.out.println(count);
                        }
                    }
                    conn.close();
                } catch (SQLException ex) {
                    // handle any errors
                    System.out.println("SQLException: " + ex.getMessage());
                    System.out.println("SQLState: " + ex.getSQLState());
                    System.out.println("VendorError: " + ex.getErrorCode());
                }

            } catch (Exception e) {
            }
        }
        s.close();
        System.err.println("Lost communication with the serial port. Exiting.");
        System.exit(1);
    }

}
1668905955755.png
Java Mysql token parser

Database GUI configuration.
1668904597120.png
Database server stats
1668904657827.png

A 3-axis acceleration data display using saved data in the database with LibreOffic Calc to graph a vibration event caused by me shaking the sensor board.
1668904855103.png
The data was sorted by SERIAL (primary key) timestamp (not imported) , dtype for acceleration data record type 1 'C' and the str data 'string' field converted to CSV data cells 'EFG' for the spreadsheet.
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,081
While testing serial speed increases using the USB comm port to transfer data to the Java Mysql database connector I found this Linux bash script that lists the extend baud speeds on each port.
The current serial speed is 230400 using DMA but I could go faster on ttyUSB0 CP2102 USB dongle or ttyACM0 device from the PIC32 dev board. The top speed on the PIC32MK uart is 30Mbps.
10Mbps over the TTL serial port
1669508399177.png

One full ASCII data packet
Code:
sprintf(uart_buffer, "%3d,%7X,%7.4f,%7.4f,%7.4f,%7.4f,%7.4f,%7.4f,%7.4f,%7.4f,%7.4f,%7.1f\r\n", accel->id, rx_messageID, accel->x, accel->y, accel->z, accel->xa, accel->ya, accel->za, accel->xerr, accel->yerr, accel->zerr, (double) accel->sensortime);
UART2DmaWrite(uart_buffer, strlen(uart_buffer));
1669508607121.png

Code:
listbaud
[ ttyACM0 ]
   57600 yes     230400 yes   500000 yes    921600 yes   1152000 yes    2000000 yes   3000000 yes    4000000 yes
  115200 yes     460800 yes   576000 yes   1000000 yes   1500000 yes    2500000 yes   3500000 yes
[ ttyS0 ]
   57600 yes     230400 no    500000 no     921600 no    1152000 no     2000000 no    3000000 no     4000000 no
  115200 yes     460800 no    576000 no    1000000 no    1500000 no     2500000 no    3500000 no
[ ttyS1 ]
   57600 yes     230400 no    500000 no     921600 no    1152000 no     2000000 no    3000000 no     4000000 no
  115200 yes     460800 no    576000 no    1000000 no    1500000 no     2500000 no    3500000 no
[ ttyS2 ]
   57600 no      230400 no    500000 no     921600 no    1152000 no     2000000 no    3000000 no     4000000 no
  115200 no      460800 no    576000 no    1000000 no    1500000 no     2500000 no    3500000 no
[ ttyS3 ]
   57600 no      230400 no    500000 no     921600 no    1152000 no     2000000 no    3000000 no     4000000 no
  115200 no      460800 no    576000 no    1000000 no    1500000 no     2500000 no    3500000 no
[ ttyUSB0 ]
   57600 yes     230400 yes   500000 yes    921600 yes   1152000 no     2000000 no    3000000 no     4000000 no
  115200 yes     460800 yes   576000 yes   1000000 yes   1500000 no     2500000 no    3500000 no
https://raw.githubusercontent.com/nsaspook/imudatabase/main/listbaud
 
Last edited:

Thread Starter

nsaspook

Joined Aug 27, 2009
13,081
The major parts of the monitoring system prototype are done.
Two PIC32MK acceleration sensors -> SPI ->CAN-FD, to one PIC32MK host connector TTL serial -> ethernet, to Linux host Java mysql connector, to database server.
1669762267720.png
1669762964642.png1669762503170.png1669763550881.png1669763575352.png
https://www.waveshare.com/uart-to-eth.htm

Setup the module in TCP server mode so the Linux Java program can open a socket interface to transfer ethernet data from the PIC32MK CAN-FD server to the database server.
https://raw.githubusercontent.com/nsaspook/imudatabase/eth/src/cube/Cube.java
Code:
/*
* To change this license header, choose License Headers in Project Properties.
* To change this template file, choose Tools | Templates
* and open the template in the editor.
*/
package cube;

import java.util.Scanner;
import java.sql.*;
import java.util.Properties;
import java.net.Socket;

/**
*
* @author root
*/
public class Cube {

    public static void main(String[] args) {

        // source and dest IP configurations
        String ttl_eth_host = "192.168.0.7";
        String mysql_host = "jdbc:mariadb://10.5.2.94/";

        try {
            // Connect to the TTL to ETH server
            Socket socket = new Socket(ttl_eth_host, 20108);

            Properties connConfig = new Properties();
            connConfig.setProperty("user", "minty");
            connConfig.setProperty("password", "");

            Scanner s = new Scanner(socket.getInputStream());
            System.err.println("Scanner running.");
            while (s.hasNextLine()) {
                String fftd = "";
                String tstamp = "";
                String hosts = "";
                String cmark = "";
                try {
                    String line = s.nextLine();
                    String[] token = line.split(",");

                    if (token[0].equals("  1")) {
                        tstamp = token[11];
                        cmark = token[12];
                        System.out.println(String.format("dtype = %3s  device = %s : %s", token[0], token[1], line, tstamp));
                        token[2] = "";
                    }
                    if (token[0].equals("  2")) {
                        System.out.println(String.format("dtype = %3s  device = %s cpu = %s host = %s : %s", token[0], token[1], token[2], token[6], line));
                        hosts = token[6];
                        cmark = token[7];
                        token[6] = "";
                        token[7] = "";
                    }
                    if (token[0].equals("  8")) {
                        System.out.println(String.format("dtype = %3s  device = %s hit  low = %s : %s", token[0], token[1], token[2], line));
                        fftd = token[2];
                        cmark = token[3];
                        token[2] = "";
                        token[3] = "";
                    }
                    if (token[0].equals("  9")) {
                        System.out.println(String.format("dtype = %3s  device = %s hit high = %s : %s", token[0], token[1], token[2], line));
                        fftd = token[2];
                        cmark = token[3];
                        token[2] = "";
                        token[3] = "";
                    }

                    try {
                        Connection conn = DriverManager.getConnection(mysql_host, connConfig);

                        if (cmark.equals("IMU")) {
                            // Prepare INSERT Statement to Add IMU data
                            try ( PreparedStatement prep = conn.prepareStatement(
                                    "INSERT INTO hits.imu (dtype, device, cpu, str, fft, tstamp, host) VALUES (?, ?, ?, ?, ?, ?, ?)",
                                    Statement.RETURN_GENERATED_KEYS)) {
                                // Add IMU packet data
                                prep.setString(1, token[0]);
                                prep.setString(2, token[1]);
                                prep.setString(3, token[2]);
                                prep.setString(4, line);
                                prep.setString(5, fftd);
                                prep.setString(6, tstamp);
                                prep.setString(7, hosts);
                                prep.addBatch();

                                int[] updateCounts = prep.executeBatch();
                                for (int count : updateCounts) {
                                    // Print Counts
//                            System.out.println(count);
                                }
                            }
                        }
                        conn.close();
                    } catch (SQLException ex) {
                        // handle any errors
                        System.out.println("SQLException: " + ex.getMessage());
                        System.out.println("SQLState: " + ex.getSQLState());
                        System.out.println("VendorError: " + ex.getErrorCode());
                    }
                } catch (Exception e) {
                }
            }
            // Close our streams
            socket.close();
            s.close();
            System.err.println("Lost communication with the IMU socket. Exiting.");
            System.exit(1);

        } catch (Exception e) {
            System.err.println("Unable to open the TCP socket. Exiting.");
            System.exit(1);
        }
    }

}
1669767555111.png
Yellow: CAN-FD data packets @2MHz
Blue: ethernet TTL serial data packets @230400bps

1669768010267.png
Mysql database
 
Last edited:

Thread Starter

nsaspook

Joined Aug 27, 2009
13,081
This is what this project is trying to prevent.

MAGLEV turbo vaccum pump destruction in an ion beam mass slit reducer. It likely won't stop all of the pump damage but it should detect a vibration signature in time to close and isolate the vacuum system valves to contain the shrapnel damage.
1672113363661.png
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,081
Have the host 4 layer PCB (Eagle non-free) in hand now so I can transfer the design from the pic32mk mjc DEV board. The front-end uC and board level I/O interfaces are the same as the sensor board with added 3.3VDC power supply, CAN driver, external clock and serial to Ethernet module. https://www.waveshare.com/uart-to-eth.htm
1672953601268.png
1672953673961.png
1672953738316.png
 
Last edited:

Thread Starter

nsaspook

Joined Aug 27, 2009
13,081
First prototype host built and working. A 3.3 volt onboard switching regulator takes the standard 24vdc as input power to feed all the remote vibration monitors via a 4 wire CAN cable to each
1673211912840.png
1673211946318.png
1673214092071.png
Using the existing external CANBUS driver modules for testing so the internal CANBUS driver pad is not populated. The host board also can be a sensor board if an optional sensor is installed.
1673225546008.png
 
Last edited:

Thread Starter

nsaspook

Joined Aug 27, 2009
13,081
1674674880273.png
Final board spin for this project from OSHPark. Added my standard SPI GLCD 10 pin header interface and a few other extras for onboard programming of the ETH module via the serial port.
https://github.com/nsaspook/wfi32

Sensor only boards and host board configured as a remote sensor CANBUS network to the host board. Host board has a TTL to Ethernet module for data transmission to a remote Linux system running a Java client to connect and download via the ETH module TCP server for formatting and sending updates to the MYSQL central sensor database.

Blob soldering the controller chip. Use lots of gel no-clean flux.
1674674231020.png
Tack two corners.
1674674268088.png
Flux and solder all pins.
1674674312649.png
Flux and solder-wick the excess off.
1674674429370.png
Clean all solder residue and flux.
1674674478459.png
1674674509534.png
 
Last edited:
Top