Cannot find bug, interminent hungup AVR128db64 XC8 pro

Hi, need some expert opinion. I have some bug causing hangup. With MPLab Microchip debugger I cannot find the reason. Microchip do not have a view on Tasks, Semaphores etc.
Do you see maybe something obvious here in the code?

#include "FreeRTOS.h"
#include "clk_config.h"
#include "mcc_generated_files/system/system.h"
#include "mcc_generated_files/timer/delay.h"
#include "mcc_generated_files/timer/tca1.h"
#include "RGBcontrol.h"
#include "grideye.h"


#include <avr/interrupt.h>
#include <string.h>
#include <task.h>
#include <json.h>
#include <semphr.h>
#include <queue.h>
#include <stdlib.h>
#include "serial.h"
#include <avr/wdt.h>


#define UART_BAUD_RATE 31250
#define UART_QUEUE_SIZE 254
extern COMport COM1_ToRadio; //radioMCU
extern COMport COM4;
extern COMport COM5_ToWD;


typedef struct {
    uint8_t relay1_Status;
    uint8_t relay2_Status;
    uint8_t relay3_Status;
    uint8_t relay4_Status;
    uint8_t microphoneAlarmStatus;
    float microphoneAmbientValue;
    float microphonePeakValue;
    float gridEyeTemp;
    float gridEyeAlarmHighTreshold;
    float gridEyeAlarmLowTreshold;
    bool gridEyeAlarmStatus;
    float gridEyeTemperatureHisteresis;
    uint8_t buzzerStatus;
} t_sensorBoard ;

LedControl Led1;
t_sensorBoard sensorBoardActualStatus;
t_sensorBoard sensorBoardPreviousStatus;
char COM1_RadioRxMessage[254];
char NL[]={'\n'};
char jsonBufer[254];

char tmpMSG[64];
uint16_t msgLength=0;

volatile float averGridEyeTemp;

char tmpa[64];

Json_Handle jsonHandler;
Json_Handle jsonTemplate;

volatile uint16_t uxHighWaterMark;

SemaphoreHandle_t mutexAlarmStatus;

void Heartbeat(void *pvParameters);
static void prvSetupHardware( void );
void ControlRgbLed (void *pvParameters);
void Buzzer(t_sensorBoard *device);
void BuzzerThread(void *pvParameters);
void ControlAlarms (void *pvParameters);
void initSensorBoard (t_sensorBoard *device);
void Collect(void *pvParameters);
void UpdatingBoardStruct (void);
void JSON_init(Json_Handle *hObject, Json_Handle *hTemplate);
void JSON_serialize(Json_Handle *hObject, char *jsonBuff);
void VerifyParametersChange (t_sensorBoard *actualState, t_sensorBoard *previousState);
void SendReportToCloud (t_sensorBoard *actualState);
void VerThread(void *pvParameters);



int main( void )
{
    mutexAlarmStatus = xSemaphoreCreateMutex();  
    xSemaphoreGive(mutexAlarmStatus);    
    prvSetupHardware();
    

    //xTaskCreate(Heartbeat, "SR",128,NULL,1,NULL);
    xTaskCreate(VerThread,"PU",512,NULL,1,NULL); //96 left
    xTaskCreate(ControlRgbLed,"R",128,NULL,1,NULL);  //30 left
    xTaskCreate(ControlAlarms,"G",128,NULL,1,NULL); //68
    xTaskCreate(BuzzerThread,"B",128,NULL,1,NULL); //73
    xTaskCreate(Collect,"PU",612,NULL,1,NULL); //
    
    
    vTaskStartScheduler();
    
    while(1)
    {
        ;        
    }
    
    return 0;
}

void Heartbeat(void *pvParameters)  
{
    while(1)
    {
        IO_PB7_Toggle();  //D16 MCU1 Heartbeat
        vTaskDelay( 502 / portTICK_PERIOD_MS ); 
        
    }
}

void ControlRgbLed (void *pvParameters)
{
    while (1)
    {
       
       //portENTER_CRITICAL();
        read_pix();
       //portEXIT_CRITICAL(); 
       
       averGridEyeTemp=((averGridEyeTemp+get_temp())/2);
       xSemaphoreTake(mutexAlarmStatus, portMAX_DELAY);
       sensorBoardActualStatus.gridEyeTemp=averGridEyeTemp;
       xSemaphoreGive(mutexAlarmStatus);
       TemperatureToColour (&Led1, averGridEyeTemp) ;
       vTaskDelay(50 / portTICK_PERIOD_MS);
       uxHighWaterMark = uxTaskGetStackHighWaterMark2( NULL );
       if (uxHighWaterMark<2) IO_PB7_SetHigh();
    }    
}

void Led1_Green_Level (int16_t brightness)
{
      TCA1.SINGLE.CMP0=brightness;  
}

void Led1_Red_Level (int16_t brightness)
{
      TCA1.SINGLE.CMP1=brightness;  

}

void Led1_Blue_Level (int16_t brightness)
{
      TCA1.SINGLE.CMP2=brightness;  
}

void Buzzer(t_sensorBoard *device) {

    while(1)
    {
         vTaskDelay( 2 / portTICK_PERIOD_MS );
        
        if (device->buzzerStatus)
        {
            TCD0_Start();
            vTaskDelay( 128 / portTICK_PERIOD_MS ); 
            TCD0_Stop();
            vTaskDelay( 128 / portTICK_PERIOD_MS );
        }
        else
        {
            TCD0_Stop();
        }
        vTaskDelay( 2 / portTICK_PERIOD_MS );
        uxHighWaterMark = uxTaskGetStackHighWaterMark2( NULL );
        if (uxHighWaterMark<2) IO_PB7_SetHigh();
    }
}

void BuzzerThread(void *pvParameters)
{
    Buzzer( &sensorBoardActualStatus );
}


void ControlAlarms (void *pvParameters)
{
    while (1)
    {
       /*GridEye Alarm ---------------------------------------------------*/
       if ((sensorBoardActualStatus.gridEyeTemp>sensorBoardActualStatus.gridEyeAlarmHighTreshold) || (sensorBoardActualStatus.gridEyeTemp<sensorBoardActualStatus.gridEyeAlarmLowTreshold))
       {
           xSemaphoreTake(mutexAlarmStatus, portMAX_DELAY);
           sensorBoardActualStatus.gridEyeAlarmStatus=1;
           sensorBoardActualStatus.buzzerStatus=1;
           xSemaphoreGive(mutexAlarmStatus);
       }
       else
       {
            xSemaphoreTake(mutexAlarmStatus, portMAX_DELAY);
            sensorBoardActualStatus.gridEyeAlarmStatus=0;
            sensorBoardActualStatus.buzzerStatus=0;
            xSemaphoreGive(mutexAlarmStatus);
       }
       /*GridEye Alarm ---------------------------------------------------*/
       
       
       vTaskDelay( 210 / portTICK_PERIOD_MS );
       uxHighWaterMark = uxTaskGetStackHighWaterMark2( NULL );
       if (uxHighWaterMark<2) IO_PB7_SetHigh();
    }    
    
}

void initSensorBoard (t_sensorBoard *device)
{
    xSemaphoreTake(mutexAlarmStatus, portMAX_DELAY);
    device->gridEyeTemp=30;
    device->relay1_Status=0;
    device->relay2_Status=0;
    device->relay3_Status=0;
    device->relay4_Status=0;
    device->gridEyeAlarmHighTreshold=50;
    device->gridEyeAlarmLowTreshold=10;
    device->gridEyeAlarmStatus=0;
    device->gridEyeTemperatureHisteresis=1;
    device->microphoneAlarmStatus=0;
    device->buzzerStatus=0;
    xSemaphoreGive(mutexAlarmStatus);
}

void Collect(void *pvParameters)  
{

    while(1)
    {
        xSerialGetStringLine( &COM1_ToRadio, portMAX_DELAY,  COM1_RadioRxMessage, 254 );
        if (COM1_RadioRxMessage[0]!='{' || COM1_RadioRxMessage[strlen(COM1_RadioRxMessage)-1]!='}' ) 
        {
            memset(COM1_RadioRxMessage,0,254);
        }
        else
            if (COM1_RadioRxMessage[0]=='{' && COM1_RadioRxMessage[strlen(COM1_RadioRxMessage)-1]=='}' )
        {
             COM5_ToWD.PutString(COM1_RadioRxMessage, portMAX_DELAY/3000, &COM5_ToWD); //Forward message
             COM5_ToWD.PutString(NL, portMAX_DELAY/3000, &COM5_ToWD); //Add New Line

          
          if (JSON_update_object (&jsonHandler,  COM1_RadioRxMessage) ==0)
          UpdatingBoardStruct (); // update board structure
        }
        vTaskDelay( 80 / portTICK_PERIOD_MS );
        uxHighWaterMark = uxTaskGetStackHighWaterMark2( NULL );
        if (uxHighWaterMark<2) IO_PB7_SetHigh();
    }
}

//Used after receiving data from Radio
void UpdatingBoardStruct (void) 
{
        
        xSemaphoreTake(mutexAlarmStatus, portMAX_DELAY);
        sensorBoardPreviousStatus=sensorBoardActualStatus;  
    
        JSON_get_value (jsonHandler, "\"r1\"",  tmpMSG, &msgLength);
        sensorBoardActualStatus.relay1_Status=atoi(tmpMSG);
        memset(tmpMSG,0,strlen(tmpMSG));

        JSON_get_value (jsonHandler, "\"r2\"",  tmpMSG, &msgLength);
        sensorBoardActualStatus.relay2_Status=atoi(tmpMSG);
        memset(tmpMSG,0,strlen(tmpMSG));

        JSON_get_value (jsonHandler, "\"r3\"",  tmpMSG, &msgLength);
        sensorBoardActualStatus.relay3_Status=atoi(tmpMSG);
        memset(tmpMSG,0,strlen(tmpMSG));

        JSON_get_value (jsonHandler, "\"r4\"",  tmpMSG, &msgLength);
        sensorBoardActualStatus.relay4_Status=atoi(tmpMSG);
        memset(tmpMSG,0,strlen(tmpMSG));

        JSON_get_value (jsonHandler, "\"mas\"",  tmpMSG, &msgLength);
        sensorBoardActualStatus.microphoneAlarmStatus=atoi(tmpMSG);

        JSON_get_value (jsonHandler, "\"gaht\"",  tmpMSG, &msgLength);
        sensorBoardActualStatus.gridEyeAlarmHighTreshold=atof(tmpMSG);
        memset(tmpMSG,0,strlen(tmpMSG));

        JSON_get_value (jsonHandler, "\"galt\"",  tmpMSG, &msgLength);
        sensorBoardActualStatus.gridEyeAlarmLowTreshold=atof(tmpMSG);;
        memset(tmpMSG,0,strlen(tmpMSG));


        JSON_get_value (jsonHandler, "\"gas\"",  tmpMSG, &msgLength);
        sensorBoardActualStatus.gridEyeAlarmStatus=atoi(tmpMSG);
        memset(tmpMSG,0,strlen(tmpMSG));


        JSON_get_value (jsonHandler, "\"gth\"",  tmpMSG, &msgLength);
        sensorBoardActualStatus.gridEyeTemperatureHisteresis=atof(tmpMSG);
        memset(tmpMSG,0,strlen(tmpMSG));

        JSON_get_value (jsonHandler, "\"bs\"",  tmpMSG, &msgLength);
        sensorBoardActualStatus.buzzerStatus=atoi(tmpMSG);
        memset(tmpMSG,0,strlen(tmpMSG));
        xSemaphoreGive(mutexAlarmStatus);
        
}
char *ConvertFloat(float number)
{
    
    sprintf(tmpa,"%.2f", number);
    return tmpa;
}
char *ConvertLong(int number)
{
    
    sprintf(tmpa,"%d", number);
    return tmpa;
}

void UpdatingAndSerialiseJson (t_sensorBoard *device)
{
  
    JSON_set(&jsonHandler, "\"r1\"", ConvertLong(device->relay1_Status));
    JSON_set(&jsonHandler, "\"r2\"", ConvertLong(device->relay2_Status));
    JSON_set(&jsonHandler, "\"r3\"", ConvertLong(device->relay3_Status));
    JSON_set(&jsonHandler, "\"r4\"", ConvertLong(device->relay4_Status));
    JSON_set(&jsonHandler, "\"mas\"", ConvertLong(device->microphoneAlarmStatus));
    JSON_set(&jsonHandler, "\"mav\"", ConvertFloat(device->microphoneAmbientValue));
    JSON_set(&jsonHandler, "\"mpv\"", ConvertFloat(device->microphonePeakValue));
    JSON_set(&jsonHandler, "\"gt\"", ConvertFloat(device->gridEyeTemp));
    JSON_set(&jsonHandler, "\"gaht\"", ConvertFloat(device->gridEyeAlarmHighTreshold));
    JSON_set(&jsonHandler, "\"galt\"", ConvertFloat(device->gridEyeAlarmLowTreshold));
    JSON_set(&jsonHandler, "\"gas\"", ConvertLong(device->gridEyeAlarmStatus));
    JSON_set(&jsonHandler, "\"gth\"", ConvertFloat(device->gridEyeTemperatureHisteresis));
    JSON_set(&jsonHandler, "\"bs\"", ConvertLong(device->buzzerStatus));
    
    memset(jsonBufer,0,254);
    JSON_serialize(&jsonHandler, jsonBufer);
}

void SendReportToCloud (t_sensorBoard *actualState)
{
    UpdatingAndSerialiseJson (actualState);
    volatile int tmpx= strlen(jsonBufer);
    
    for (int i=0; i< 254;i++)
    {
        if (jsonBufer[i]==10) jsonBufer[i]=32; 
    }
    jsonBufer[tmpx]=10;
    
    if (jsonBufer[0]=='{' && jsonBufer[tmpx-2]=='}' && tmpx>10)
    {
        
        COM1_ToRadio.PutString(jsonBufer, portMAX_DELAY/3000, &COM1_ToRadio); 
    
    }
}

//checking if parameters has been changed, also if not been changed for few second it triggering like a heartbeat 
void VerifyParametersChange (t_sensorBoard *actualState, t_sensorBoard *previousState)
{
    static uint32_t sendReport=0;
    static uint16_t _timer=0;
    
    while (1)
    {
        sendReport=0;
        
        if ((actualState->gridEyeTemp>(previousState->gridEyeTemp + previousState->gridEyeTemperatureHisteresis)) || (actualState->gridEyeTemp<(previousState->gridEyeTemp - previousState->gridEyeTemperatureHisteresis))) 
        {
            previousState->gridEyeTemp=actualState->gridEyeTemp;
            sendReport=1;
        }
        
        if (previousState->relay1_Status != actualState->relay1_Status) 
        {
            previousState->relay1_Status = actualState->relay1_Status;
            sendReport=1;
        }
        
        if (previousState->relay2_Status != actualState->relay2_Status) 
        {
            previousState->relay2_Status = actualState->relay2_Status;
            sendReport=1;
        }
        vTaskDelay( 10 / portTICK_PERIOD_MS );
        if (previousState->relay3_Status != actualState->relay3_Status)  
        {
            previousState->relay3_Status = actualState->relay3_Status;
            sendReport=1;
        }
        
        if (previousState->relay4_Status != actualState->relay4_Status) 
        {
            previousState->relay4_Status = actualState->relay4_Status;
            sendReport=1;
        }
        

        
        if (_timer>=15) 
        {
            sendReport=1;
            actualState->microphoneAlarmStatus=4;
            _timer=0;
        }
        else actualState->microphoneAlarmStatus=0;
        
        if (sendReport) 
        {
            SendReportToCloud(actualState);
        }
        
        
        _timer++;
         
        /* Inspect our own high water mark on entering the task. */
        
        IO_PD1_Toggle();
        wdt_reset();
        vTaskDelay( 270 / portTICK_PERIOD_MS );
        uxHighWaterMark = uxTaskGetStackHighWaterMark2( NULL );
        if (uxHighWaterMark<2) IO_PB7_SetHigh();
        
    }
}

void VerThread(void *pvParameters)
{
    VerifyParametersChange (&sensorBoardActualStatus, &sensorBoardPreviousStatus);
}

static void prvSetupHardware( void )
{
    /* Ensure no interrupts execute while the scheduler is in an inconsistent
    state.  Interrupts are automatically enabled when the scheduler is
    started. */
    portDISABLE_INTERRUPTS();
    CLK_init();
    DELAY_milliseconds(1000);
    SYSTEM_Initialize();
    
    TCA1.SINGLE.PER=0xFF;  //max PWM period  is used with .CMP to form pulse width
    TCD0_Stop();  //Buzzer stop
    
    xSerialPortInitMinimal(UART_BAUD_RATE, 254, &USART1, &COM1_ToRadio);
  ///  xSerialPortInitMinimal(UART_BAUD_RATE, 254, &USART4, &COM4);
    xSerialPortInitMinimal(UART_BAUD_RATE, 254, &USART5, &COM5_ToWD);
    
    IO_PB6_SetDigitalOutput();
    IO_PB7_SetDigitalOutput();
    IO_PB0_SetDigitalOutput();
    IO_PB6_SetLow(); //MCU heartbeat
    IO_PB7_SetLow(); //MCU heartbeat
    IO_PB0_SetLow(); //LED 1 Blue

    
    initSensorBoard (&sensorBoardActualStatus);
    initSensorBoard (&sensorBoardPreviousStatus);
    
    init_grideye();
    InitLed (&Led1, &Led1_Red_Level, &Led1_Green_Level, &Led1_Blue_Level);
    

    
    JSON_init(&jsonHandler, &jsonTemplate);
    JSON_serialize(&jsonHandler, jsonBufer);

    portENABLE_INTERRUPTS();
    
    
}

There are a few things that spring to my mind:

  1. You can not and should not release a mutex before you took it, and more importantly, you can not use a mutex outside of a task (in main is a no no) Still I do not think that that accounts for your problem.
  2. Always and without exception check the return value of every FreeRTOS API you call.
  3. Strings you obtain from a serial line can always become corrupted. Is your protocol fault tolerant enough to handle misformed strings? You may want to log every string you obtain before processing it.
  4. Are you double/triple/quadruple… checking that you do not get stack overflows?
1 Like

Thank you very much for your time and help. I was checking stack overflow, looks ok - I try to keep at least 30 symbols more for each task.
I noticed that my problem might be related to the fact that from time to time messages coming from COM1 (coap messages received by radio and forwarded to this MCU which decode JSON and control relays) are coming very fast (a few messages one after another).

Thats how I realised serial port communication

#include "FreeRTOS.h"
#include "queue.h"
#include "task.h"
#include "serial.h"
#include <avr/interrupt.h>

#define USART_BAUD_RATE(BAUD_RATE) ((float)(configCPU_CLOCK_HZ * 64 / (16 * (float)BAUD_RATE)) + 0.5)
 
COMport COM1_ToRadio;
COMport COM4;
COMport COM5_ToWD;


void vInterruptOn(COMport *COMno) 
{
    COMno->USARTno->CTRLA |= (1 << USART_DREIE_bp);
     
}

void vInterruptOff(COMport *COMno) 
{
    COMno->USARTno->CTRLA &= ~(1 << USART_DREIE_bp);
}

void xSerialPortInitMinimal( unsigned long ulWantedBaud, unsigned portBASE_TYPE uxQueueLength, USART_t *USARTno, COMport *COMno)
{
    portENTER_CRITICAL();
    {
        COMno->PutChar=xSerialPutChar;
        COMno->PutString=vSerialPutString;
        
        COMno->USARTno=USARTno;
        /* Create the queues used by the com test task. */
        COMno->xRxedCharsHandle = xQueueCreate( uxQueueLength, ( unsigned portBASE_TYPE ) sizeof( char ) );
        COMno->xCharsForTxHandle= xQueueCreate( uxQueueLength, ( unsigned portBASE_TYPE ) sizeof( char ) );

        COMno->USARTno->BAUD = (uint16_t)USART_BAUD_RATE(ulWantedBaud);

        // ABEIE disabled; DREIE disabled; LBME disabled; RS485 DISABLE; RXCIE enabled; RXSIE enabled; TXCIE enabled; 
        COMno->USARTno->CTRLA = 0xD0;

        // MPCM disabled; ODME disabled; RXEN enabled; RXMODE NORMAL; SFDEN disabled; TXEN enabled; 
        COMno->USARTno->CTRLB = 0xC0;

        // CMODE Asynchronous Mode; UCPHA enabled; UDORD disabled; CHSIZE Character size: 8 bit; PMODE No Parity; SBMODE 1 stop bit; 
        COMno->USARTno->CTRLC = 0x3;

        //DBGRUN disabled; 
        COMno->USARTno->DBGCTRL = 0x0;

        //IREI disabled; 
        COMno->USARTno->EVCTRL = 0x0;

        //RXPL 0x0; 
        COMno->USARTno->RXPLCTRL = 0x0;

        //TXPL 0x0; 
        COMno->USARTno->TXPLCTRL = 0x0;

        //interrupt enable
        COMno->USARTno->CTRLA |= USART_RXCIE_bm; 
        
    }
    
    portEXIT_CRITICAL();
    
    /* Unlike other ports, this serial code does not allow for more than one
    com port.  We therefore don't return a pointer to a port structure and can
    instead just return NULL. */
  
}
/*-----------------------------------------------------------*/

signed portBASE_TYPE xSerialGetChar( char *pcRxedChar, TickType_t xBlockTime, COMport *COMno )
{
    /* Get the next character from the buffer.  Return false if no characters
    are available, or arrive before xBlockTime expires. */
    if( xQueueReceive( COMno->xRxedCharsHandle, pcRxedChar, xBlockTime ) )  //check if & is needed
      {
        return pdTRUE;
    }
    else
    {
        return pdFALSE;
    }
}
/*-----------------------------------------------------------*/
void xSerialGetStringLine( COMport *COMno, TickType_t xBlockTime,  char *outputMessage, uint16_t outputMessageSize )
{
    volatile unsigned int _index = 0;
    char pcRxedChar=0;

    do
    {
        if( xQueueReceive( COMno->xRxedCharsHandle, &pcRxedChar, xBlockTime ) )  //check if & is needed
        {
            
            if(pcRxedChar != '\n'  )
            {
                outputMessage[_index++] = pcRxedChar;
                if(_index >= outputMessageSize)
                {
                    _index = 0;
                }
            }

            if(pcRxedChar == '\n')
            {
                outputMessage[_index] = '\0';
                _index = 0;
            }
            
            
        }
        
    }
    while (pcRxedChar!='\n');
    IO_PD5_Toggle();
    
    }
/*-----------------------------------------------------------*/


signed portBASE_TYPE xSerialPutChar( char *cOutChar, TickType_t xBlockTime, COMport *COMno )
{
    /* Return false if after the block time there is no room on the Tx queue. */
    if( xQueueSend( COMno->xCharsForTxHandle, cOutChar, xBlockTime ) != pdPASS )
    {
        return pdFAIL;
    }
    
    vInterruptOn(COMno);
    
    return pdPASS;
}
/*-----------------------------------------------------------*/

void vSerialPutString( char *OutString, TickType_t xBlockTime, COMport *COMno )
{
    char *pxNext;
    
    pxNext =  OutString;
    
    while( *pxNext)
    {
        COMno->PutChar(pxNext, portMAX_DELAY/3000, COMno);
        pxNext++;
    }
	IO_PD3_Toggle(); //TX D3 Led
}

/*-----------------------------------------------------------*/
void vSerialClose( COMport *COMno )
{
    /* Turn off the interrupts.  We may also want to delete the queues and/or
    re-install the original ISR. */

    portENTER_CRITICAL();
    {
        vInterruptOff(COMno);
        COMno->USARTno->CTRLB &= (1 << USART_RXEN_bp);
    }
    portEXIT_CRITICAL();
}
/*-----------------------------------------------------------*/

void ReceiveISR (COMport *COMno)
{
    char ucChar; 
    signed char xHigherPriorityTaskWoken = pdFALSE;

    /* Get the character and post it on the queue of Rxed characters.
    If the post causes a task to wake force a context switch as the woken task
    may have a higher priority than the task we have interrupted. */
    ucChar = COMno->USARTno->RXDATAL;
    xQueueSendFromISR( COMno->xRxedCharsHandle, &ucChar, &xHigherPriorityTaskWoken );
    if( xHigherPriorityTaskWoken != pdFALSE )
    {
        portYIELD_FROM_ISR();
    }
}

void SendISR (COMport *COMno)
{
    char cChar;
    signed char cTaskWoken = pdFALSE;

    if( xQueueReceiveFromISR( COMno->xCharsForTxHandle, &cChar, &cTaskWoken ) == pdTRUE )
    {
        /* Send the next character queued for Tx. */
        COMno->USARTno->TXDATAL = cChar;
    }
    else
    {
        /* Queue empty, nothing to send. */
        vInterruptOff(COMno);
    }
}


ISR(USART1_RXC_vect)
{
    ReceiveISR (&COM1_ToRadio);
    
}

ISR(USART1_DRE_vect)
{
    SendISR (&COM1_ToRadio);
    //IO_PD2_Toggle();
}

ISR(USART1_TXC_vect)
{
    USART1.STATUS |= USART_TXCIF_bm;
}


///////////////////////////////////////////////
ISR(USART4_RXC_vect)
{
    ReceiveISR (&COM4);
    
}

ISR(USART4_DRE_vect)
{
    SendISR (&COM4);
    //IO_PD2_Toggle();
}

ISR(USART4_TXC_vect)
{
    USART4.STATUS |= USART_TXCIF_bm;
}
////////////////////////////////////////////////////

ISR(USART5_RXC_vect)
{
    ReceiveISR (&COM5_ToWD);
    
}

ISR(USART5_DRE_vect)
{
    SendISR (&COM5_ToWD);
    
}

ISR(USART5_TXC_vect)
{
    USART5.STATUS |= USART_TXCIF_bm;
}

Again, what if your string input routine misses the cr, lf or 0 or whatever properly terminates your string? That can always happen due to noise on the line or a bug in your peers software.

1 Like