PIC32MK MCJ motor controller and sensor node for CANBUS

Thread Starter

nsaspook

Joined Aug 27, 2009
13,277
Have a mockup of a full machine sensor CAN-FD network in the home shop for testing. A bit of a mess but it all works.
Four boards, 3 3dof acceleration sensor data collectors and 1 network host.
1675230590562.png

The current job is to make these processes (data collection and data storage) as reliable as possible.
Zoom mode on the bottom half of the screen.
Blue for CAN packets (4 types) on the bus, Yellow for serial data packets (4 types) to the Ethernet. Serial bandwidth is a bottleneck but easily manageable with only a few sensors..
We all love CAN because it's easy to put the data in a buffer and then receive that buffer on the other-side without a lot of software a manage the physical bus.
The UART stream is trickier without hardware flow control but here we let the host CAN receiver be our flow-control with it's FIFO buffers that work with little cpu intervention. For the UART we only need a simple bounce-buffer and a DMA/wait trigger for the next serial packet to the TCP server.
Incoming data logging from the database Java client reading Ethernet data from the CAN host and sending that to another database server. If you run a Linux firewall (lots of spamming connections) and a database on the same server you need to make sure you don't DoS your own network with too many continuous connections that can happen of you create and drop a DB connection with every packet.
https://cs7networks.co.uk/2016/11/20/ipv6-conntrack-and-munin/
https://support.huaweicloud.com/intl/en-us/trouble-ecs/ecs_trouble_0324.html

32 message FIFOs
Each FIFO can have up to 32 messages for a total of 512 messages
FIFO can be a transmit message FIFO or a receive message FIFO
https://ww1.microchip.com/downloads...twork_with_Flexible_Data_rate_DS60001549A.pdf

That's plenty of headroom for 1/2 dozen sensors running asynchronously.
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,277
Time to write a command parser so we can display the IP address of the module on he LCD screen by local or remote command.
The ETH module uses the old AT command mode that needs a few special hand-shakes to activate out of transparent data mode.

First a simple command parser to read data from the socket via the UART receive pin.
https://raw.githubusercontent.com/nsaspook/wfi32/nhost/firmware/src/cmd_scanner.c

It just calls a function pointer when there is command character match.

For the AT function we use 'A'.
C:
static t_cmd g_cmds[] = {

    { "L", fh_show_link},
    { "D", fh_stop_trigger},
    { "E", fh_start_trigger},
    { "A", fh_start_AT},

    // null command terminator
    { 0x00, 0x00}
};
C:
/*
* capture and display ETH module network IP address
*/
void fh_start_AT(void *a_data)
{
    sprintf(cmd_buffer, "Start AT commands            ");

    // wait for send uart buffer to finish
    uint32_t contention = 0;
    LED_RED_Off();
    while (uart1_dma_busy || U1STAbits.UTXBF) { // uart flow-control RED led
        if (contention++ == uart_wait) {
            LED_RED_Toggle();
        }
    };

    // put the ETH module in config mode
    ETH_CFG_Clear();
    WaitMs(500);
    ETH_CFG_Set();
    WaitMs(5000); // wait until the module is back online

    // AT command mode
    UART1DmaWrite("+++", 3); // send data to the ETH module
    WaitMs(200);
    UART1DmaWrite("a", 1); // send data to the ETH module
    WaitMs(200);
    if (UART1_ReceiverIsReady()) { // check to see if we have a response
        // send a Ethernet connection query
        UART1DmaWrite("AT+WANN\r\r\n", 10); // send data to the ETH module
        // put the result in a buffer for the GLCD to display
        UART1_Read(response_buffer, 22);
    } else { // nothing
        sprintf(response_buffer, "AT command failed           ");
    }
    /*
     * AT mode will timeout after 30 seconds and go back to transparent data mode
     */
}
1675384736393.png

The Java testing client sends this when started.
Code:
            // Connect to the TTL to ETH server
            Socket socket = new Socket(ttl_eth_host, 20108);
            // send IP address query to remote module
            socket.getOutputStream().write("A\r".getBytes("US-ASCII")); // or UTF-8 or any other applicable encoding...
1675384026787.png
Sensor host before java command.

1675384067569.png
After the Java 'A' command. There is also a host board GPIO pin that can trigger the same query.
 
Last edited:

Thread Starter

nsaspook

Joined Aug 27, 2009
13,277
PCB level IP query code. Output pins can still be used as Input pins because the I/O functionality is split between LAT and PORT registers. Here I use one of the designated Test Points TP1 that's normally used to toggle DEBUG information and use it as the trigger for the ETH module query. If normal debug operations don't keep the pin low for at least 4 seconds then we can use a >=5 second pin low signal as a trigger.

C:
        /*
         * Short TP1 to ground for at least 5 seconds to trigger a IP query to the ETH module
         * release short after red LED stays on
         */
        if (TP1_check()) {
            LED_RED_On();
            fh_start_AT(&cli_ctx);
        }
...
bool TP1_check(void)
{
    static uint32_t debounce = 0;

    if (TP1_Get() == 0) {
        debounce++;
        if (debounce >= debounce_delay) {
            debounce = debounce_delay + 1;
            return true;
        } else {
            return false;
        }
    } else {
        debounce = 0;
        return false;
    }
}
 

Attachments

Thread Starter

nsaspook

Joined Aug 27, 2009
13,277
Finally have supply of the original sensor BMA4xx family devices for this project. The BMA400 is much cheaper $5 than the SCL3300-D01-10 @$50 but the SCL3300 has much better device specifications.

1676048853141.png1676047961021.png
murata.png

The BMA400 should be fine as a predictive failure vibration sensor running at 100Hz for the output data rate.

Both types of sensors use the SPI interface (recommended over i2c) with 8MHz data clock.

1676050361023.png
BMA400 XYZ and sensor timestamp data block transfer time (CS low time).

1676053541272.png
1676050624093.png
Solder bump the LGA package (12 pins) pads, gel flux and hot air gun solder the device to the PCB.
https://community.bosch-sensortec.com/t5/Knowledge-base/BMA400-accelerometer-design-guide/ta-p/7397
1676053311586.png
Backside view of the chip.

1676050706068.png

Front-side view of the bottom level only view of the Eagle Cad board layout. Need to check the 4-wire SPI signals.
The easy way to probe tiny devices like this is to probe the signal connecting via using 30 gauge wire-wrap wire extension to the probe. Just strip off a small end section of insulation and push into the hole.
https://www.jensentools.com/product/606WI0010-R30BLK-0100
1676050661466.png
Vias used as test-points for scope probes. IMU_CS and SDI2 in the above timing scope screen-shot.

Pretty simple code setup for the device for a single type of application. Sample timing is set by the device data ready interrupt every 10ms. This interrupt is connected to the PIC32MK external interrupt #2 that triggers the data capture and CAN-FD transfer functions.

C:
/*
 * toggle the chip CS to set BMA400 SPI mode and
 * configure operation modes for vibration sensor software
 */
void bma490l_set_spimode(void * imup)
{
    imu_cmd_t * imu = imup;
    static bool first = true;

    LED_GREEN_Off();
    LED_RED_On();

    if (imu) {
        if (first) {
            delay_us(5000); // power-up device delay
            imu_get_reg(imu, BMA400_CMD_DUMMY, false); // start SPI mode with a dummy read
            // use SPI interface on reboots so send a dummy ID command to clear errors
            bma490l_getid(imu);
        }

        imu_set_reg(imu, BMA400_REG_ACCEL_CONFIG_0, BMA400_NORM_MODE, false); // normal mode
        delay_us(1500);
        imu_set_reg(imu, BMA400_REG_ACCEL_CONFIG_1, BMA400_RANGE_MODE, false); // range=2g, osr=3 (high perf), acc_odr=100Hz:
        imu_set_reg(imu, BMA400_REG_ACCEL_CONFIG_2, BMA400_FILTER_MODE, false); // Use acc_filt2 (100Hz fixed) as data source
        imu_set_reg(imu, BMA400_REG_INT_CONF_0, BMA400_INT_CONF, false); // Enable data ready interrupt
        imu_set_reg(imu, BMA400_REG_INT_MAP, BMA400_INT_MAP, false); // Map data ready interrupt to INT1 pin -> ext2 interrupt on controller
        /*
         * trigger ISR on IMU data update interrupts
         */
        init_imu_int(imu);
        first = false;
    }

//
/*
 * Read raw ACCEL data from the chip using SPI
 */
bool bma490l_getdata(void * imup)
{
    imu_cmd_t * imu = imup;

    if (imu) {
        if (!imu->run) {
            imu_cs(imu);
            SPI2_WriteRead(R_DATA_CMD, BMA400_DATA_LEN, imu->rbuf, BMA400_DATA_LEN);
            while (imu->run) {
            };
        }
        return imu->online;
    } else {
        return false;
    }
}
// convert binary raw sensor data into standard meters/seconds double units format 
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) {
#ifdef BMA400
                /*
                 * need to swap X-Y and reverse sign to match SCA3000
                 * Z is fine
                 */
                uint16_t lsb;
                uint8_t msb;

                move_bma490_transfer_data(data, imu);
                sensortime = (data[9] << 16) | (data[8] << 8) | data[7]; // 24-bit sensor time
                sdata.scan.ts = sensortime;

                lsb = data[3];
                msb = data[4];
                x = (int16_t) (((uint16_t) msb * 256) + lsb); // 12-bit xyz data
                if (x > 2047) {
                    /* Computing accel data negative value */
                    x = x - 4096;
                }
                x = -x; // invert sign, no bit-twiddling
                sdata.scan.channels[SCA3300_ACC_X] = x;

                lsb = data[1];
                msb = data[2];
                y = (int16_t) (((uint16_t) msb * 256) + lsb);
                if (y > 2047) {
                    /* Computing accel data negative value */
                    y = y - 4096;
                }
                y = -y; // invert sign
                sdata.scan.channels[SCA3300_ACC_Y] = y;

                lsb = data[5];
                msb = data[6];
                z = (int16_t) (((uint16_t) msb * 256) + lsb);
                if (z > 2047) {
                    /* Computing accel data negative value */
                    z = z - 4096;
                }
                sdata.scan.channels[SCA3300_ACC_Z] = z;
                accel->sensortime = sensortime; // time log each accel measurement from IMU        
#else
                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
#endif
            }
#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];
        }
    }
}
https://raw.githubusercontent.com/nsaspook/wfi32/nhost/firmware/src/imu.c

dtype = 1 device = 10300E7 : 1,10300E7,-0.7020,-0.6443,-9.7709, 0.0000, 0.0000, 0.0000, 0.0000, 0.0000, 0.0000,13365264.0,IMU
dtype = 1 device = E2D4EAE : 1,E2D4EAE, 0.1453,-1.5210,-9.7135, 0.8459,-8.8989,-81.0681,633.3838,-665.5957,-954.2725,1967259321.0,IMU
dtype = 1 device = E2D4EAF : 1,E2D4EAF, 5.8615, 0.1387,-7.8503,36.7438, 0.8130,-53.2452,776.9751,633.2520,-842.9810,1965289164.0,IMU
dtype = 1 device = 10300E7 : 1,10300E7,-0.7020,-0.6443,-9.7132, 0.0000, 0.0000, 0.0000, 0.0000, 0.0000, 0.0000,13366288.0,IMU
dtype = 1 device = E2D4EAE : 1,E2D4EAE, 0.1502,-1.5243,-9.7234, 0.8734,-8.9154,-81.0516,633.4937,-665.6616,-954.2065,1967269165.0,IMU
dtype = 1 device = E2D4EAF : 1,E2D4EAF, 5.8746, 0.1436,-7.8372,36.8481, 0.8405,-53.1354,777.3926,633.3618,-842.5415,1965299008.0,IMU
Database logging for three sensors with sensor timestamps for data processing synchronization. The BMA400 10300E7 device ID is actually part of the PIC32MK unique identifier as the BMA400 has no unique serial number per device like the SCL3300 has.

1676053232196.png
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,277
Some operational testing to tune some detection software routines.
1677032313845.png
Taped to surface of a vacuum chamber, CAN transceiver in a small plastic case. The pump to the right of the sensor is a high cost failure item that will be used to generate some non-destructive signal profiles.
1677032541746.png
Sensor cable 20ft with upgraded CAN transducer for CAN-FD bit speeds.
1677032639201.png1677032673420.png
1677032710225.png
Signal quality at the end of the cable.

From this small data run
1677032895780.png
1677033912166.png
the Java code driven database search selected a section where the FFT routine code generates realtime vibration hit values in the fft block of the sensor packet. The creates a smaller events database from the larger
sensor database.
The tool was being worked on for a minor water leak so the recorded signals were just minor bumps and lead door movements.

1677033236325.png
40ms per Z sensor data point. Yes, the sensor is upside down. the software don't care.
Yellow is the normal ambient background signal for zero fft signature 'hit' value. Blue is the 'hit' trigger signal for up to a '7000' fft 'signature hit'
 
Last edited:

Thread Starter

nsaspook

Joined Aug 27, 2009
13,277
Another board rev for a controller/game-boy. The SCL3300 3-axis (XYZ) inclinometer was used.
1681276607855.png
HID buttons, buzzer, optical rotary encoder input with CAN-FD, SPI, GPIO, UART serial I/O.
1681276647417.png
The gel "no clean' flux need cleaning.

1681276705559.png

Some simple motion demo interaction videos using line rotation, boxes and Attractor graphics.
 

Thread Starter

nsaspook

Joined Aug 27, 2009
13,277
Some simple HID interfaces for the board. Audio feedback to button presses and screen auto-blanking and wake-up..
C:
/*
 * TMR2 buzzer PWM update timer
 */

#ifndef BUZZER_H
#define    BUZZER_H

#ifdef    __cplusplus
extern "C" {
#endif
#include "imupic32mcj.h"

#define BUZZER_DRIVER "V1.002" 
#define BUZZER_ALIAS "BUZZER"

#define BZ0    0
#define BZ1    1
#define BZ2    11
#define BZ3    21

#define BZ_OFF    255

#define BZ_ON_LOUD    100
#define BZ_ON_LOW    101

    typedef enum {
        B_init,
        B_abort,
    } B_STATE;

    typedef struct B_type {
        volatile uint32_t arate, alimit;
        volatile uint32_t srate, slimit;
        volatile uint32_t drate, dlimit;
    } B_type;

    void buzzer_init(B_STATE);
    void buzzer_trigger(uint32_t);
    uint32_t get_buzzer_trigger(void);

    extern B_type tone1, tone2, tone3;

#ifdef    __cplusplus
}
#endif

#endif    /* BUZZER_H */
C:
/*
 * Internal driven magnetic buzzer sounds ISR and PWM handler FSM
 * loudness: Attack slope, sustain slop, decay slope and timing
 * to adjust the dynamic sound character of each buzzer trigger
 * 
 */


#include "buzzer.h"
#include "hid.h"

static const uint32_t vol_high = 10000, vol_mute = 0, vol_low = 2000;

B_type tone1 = {
    .arate = 15,
    .alimit = 7000,
    .srate = 10,
    .slimit = 8000,
    .drate = 30,
    .dlimit = 500,
};

B_type tone2 = {
    .arate = 500,
    .alimit = 7000,
    .srate = 10,
    .slimit = 10000,
    .drate = 30,
    .dlimit = 500,
};

B_type tone3 = {
    .arate = 500,
    .alimit = 7000,
    .srate = 1,
    .slimit = 9000,
    .drate = 5,
    .dlimit = 500,
};

volatile uint32_t buzzer_state = 0;

static void buzzer_tone(uint32_t, uintptr_t);

/*
 * setup and start the needed hardware and software
 */
void buzzer_init(B_STATE bs)
{
    switch (bs) {
    case B_abort:
        MCPWM_ChannelPrimaryDutySet(MCPWM_CH_1, vol_mute);
        TMR2_Stop();
        MCPWM_Stop();
        break;
    case B_init:
    default:
        TMR2_CallbackRegister(buzzer_tone, 0);
        TMR2_Start();

        MCPWM_Start();
        MCPWM_ChannelPrimaryDutySet(MCPWM_CH_1, vol_mute);
        break;
    }
}

/*
 * buzzer amplitude/tone profiles
 * this gets called every 10us in the timer TMR2 callback interrupt
 */
static void buzzer_tone(uint32_t status, uintptr_t context)
{
    static uint32_t volume = vol_mute;

    switch (buzzer_state) {
    case BZ0:
        volume = vol_mute;
        break;
    case BZ_ON_LOUD: // steady loud
        volume = vol_high;
        break;
    case BZ_ON_LOW: // steady low
        volume = vol_low;
        break;
    case BZ1: // short chirp
        volume += tone1.arate;
        if (volume >= tone1.alimit) {
            buzzer_state = BZ1 + 1;
        }
        break;
    case BZ1 + 1:
        volume += tone1.srate;
        if (volume >= tone1.slimit) {
            buzzer_state = BZ1 + 2;
        }
        break;
    case BZ1 + 2:
        volume -= tone1.drate;
        if (volume <= tone1.dlimit) {
            volume = vol_mute;
            buzzer_state = BZ0;
        }
        break;
    case BZ2: // short click
        volume += tone2.arate;
        if (volume >= tone2.alimit) {
            buzzer_state = BZ2 + 1;
        }
        break;
    case BZ2 + 1:
        volume += tone2.srate;
        if (volume >= tone2.dlimit) {
            buzzer_state = BZ2 + 2;
        }
        break;
    case BZ2 + 2:
        volume -= tone2.drate;
        if (volume <= tone2.dlimit) {
            volume = vol_mute;
            ;
            buzzer_state = BZ0;
        }
        break;
    case BZ3: // longer click
        volume += tone3.arate;
        if (volume >= tone3.dlimit) {
            buzzer_state = BZ3 + 1;
        }
        break;
    case BZ3 + 1:
        volume += tone3.srate;
        if (volume >= tone3.slimit) {
            buzzer_state = BZ3 + 2;
        }
        break;
    case BZ3 + 2:
        volume -= tone3.drate;
        if (volume <= tone3.dlimit) {
            volume = vol_mute;
            buzzer_state = BZ0;
        }
        break;
    case BZ_OFF:
        H.silent = true;
        break;
    default:
        buzzer_state = BZ0;
        volume = vol_mute;
        break;
    }

    if (H.silent) {
        MCPWM_ChannelPrimaryDutySet(MCPWM_CH_1, vol_mute);
    } else {
        MCPWM_ChannelPrimaryDutySet(MCPWM_CH_1, volume);
    }
    if (volume == vol_mute) { // stop callback interrupts
        TMR2_Stop();
    }
}

void buzzer_trigger(uint32_t trigger)
{
    TMR2_Start(); // start callback interrupts to process buzzer profiles
    buzzer_state = trigger;
}

uint32_t get_buzzer_trigger(void)
{
    return buzzer_state;
}
Customize the sound profile of the buzzer for clicks, thumps, etc ...
1681519649737.png1681519683679.png


Button interface.
C:
/* 
 * TMR3 debounce timer
 * TMR4 screen blank timer
 */

#ifndef HID_H
#define    HID_H

#ifdef    __cplusplus
extern "C" {
#endif

#include "buzzer.h"
#include "gfx.h"

#define HID_DRIVER "V1.002" 
#define HID_ALIAS "HID"

#define FFT_WAKE    1500
#define HID_LONG_BLANK    14062499U * 10U

#define DBOUNCE_COUNTS    70000

    typedef enum {
        H_init,
        H_home,
        H_run,
        H_blank,
        H_zero_blank,
        H_abort,
    } H_STATE;

    typedef struct H_type {
        H_STATE hid_state;
        volatile bool dis_alt, show_la, la_mod, dis_unblank, dis_reset, silent;
    } H_type;

    extern H_type H;

    extern void hid_init(H_STATE);

#ifdef    __cplusplus
}
#endif

#endif    /* HID_H */
C:
/*
 * Human input device handler, GLCD screen back-light blank and FSM
 */
#include "hid.h"

H_type H = {
    .dis_alt = false,
    .dis_unblank = false,
    .show_la = true,
    .la_mod = true,
    .dis_reset = false,
    .silent = false,
    .hid_state = H_init,
};

static void hid_blank_cb(uint32_t, uintptr_t);
static    void sw2_cb(GPIO_PIN, uintptr_t);
static    void sw4_cb(GPIO_PIN, uintptr_t);
static    void sw5_cb(GPIO_PIN, uintptr_t);

/*
 * setup and start the needed hardware and software
 */
void hid_init(H_STATE hs)
{
    H.hid_state = hs;
    switch (hs) {
    case H_init:
        TMR3_Start(); // debounce counter
        TMR4_CallbackRegister(hid_blank_cb, 0);
        TMR4_Start(); // screen blank counter
        GPIO_PinInterruptCallbackRegister(SW2_PIN, sw2_cb, 0);
        GPIO_PinIntEnable(SW2_PIN, GPIO_INTERRUPT_ON_FALLING_EDGE);
        SW2_InterruptEnable();

        GPIO_PinInterruptCallbackRegister(SW4_PIN, sw4_cb, 0);
        GPIO_PinIntEnable(SW4_PIN, GPIO_INTERRUPT_ON_FALLING_EDGE);
        SW4_InterruptEnable();

        GPIO_PinInterruptCallbackRegister(SW5_PIN, sw5_cb, 0);
        GPIO_PinIntEnable(SW5_PIN, GPIO_INTERRUPT_ON_FALLING_EDGE);
        SW5_InterruptEnable();
        break;
    case H_zero_blank:
        BLANK_COUNTER = 0x0; /* Clear counter to restart blanking period */
        break;
    case H_blank:
        ReSet_SetLow();
        H.dis_reset = true;
        break;
    default:
        break;
    }
}

/*
 * Switch button pressed IOC pin call-back functions
 * SW3 is input level only with no IOC functions
 */
static void sw2_cb(GPIO_PIN pin, uintptr_t context)
{
    static uint32_t dbounce = 0;

    if (TMR3_CounterGet() > (dbounce + DBOUNCE_COUNTS)) {
        buzzer_trigger(BZ1);
        dbounce = TMR3_CounterGet();
        H.show_la = !H.show_la;

        if (H.dis_reset) {
            H.dis_unblank = true;
        }

        if (SW3_Get()) {
            POS2CNT--;
        } else {
            POS2CNT++;
        }
        if (!H.show_la) {
            LA_gfx(true, false, 0);
        }
        hid_init(H_zero_blank); // reset the screen blanking counter
    }

}

static void sw4_cb(GPIO_PIN pin, uintptr_t context)
{
    static uint32_t dbounce = 0;

    if (TMR3_CounterGet() > (dbounce + DBOUNCE_COUNTS)) {
        buzzer_trigger(BZ3);
        dbounce = TMR3_CounterGet();
        H.dis_alt = !H.dis_alt;
        if (H.dis_reset) {
            H.dis_unblank = true;
        }
        hid_init(H_zero_blank); // reset the screen blanking counter
        if (!SW3_Get()) {
            hid_init(H_blank);
            if (!SW2_Get() && !SW5_Get()) { // set screen blanking period to ~10min
                TMR4_PeriodSet(HID_LONG_BLANK);
                buzzer_trigger(BZ_ON_LOW);
            } else {
                if (!H.silent) { // toggle buzzer sound
                    buzzer_trigger(BZ_OFF);
                } else {
                    H.silent = false;
                }
            }

        }
    }

}

static void sw5_cb(GPIO_PIN pin, uintptr_t context)
{
    static uint32_t dbounce = 0;

    if (TMR3_CounterGet() > (dbounce + DBOUNCE_COUNTS)) {
        buzzer_trigger(BZ1);
        dbounce = TMR3_CounterGet();
        H.la_mod = !H.la_mod;
        if (H.dis_reset) {
            H.dis_unblank = true;
        }
        if (SW3_Get()) {
            POS2CNT++;
        } else {
            POS2CNT--;
        }
        hid_init(H_zero_blank); // reset the screen blanking counter
    }

}

static void hid_blank_cb(uint32_t status, uintptr_t context)
{
    hid_init(H_blank);
    buzzer_trigger(BZ2);
}
 
Top