Quality RTOS & Embedded Software

 Real time embedded FreeRTOS RSS feed 
Quick Start Supported MCUs PDF Books Trace Tools Ecosystem


Loading

FreeRTOS+TCP Simple network interfaces STM32F429

Posted by yanvasilij on September 19, 2016

Hello!

I am trying to create FreeRTOS+tcp simple network interfaces. I created my own NetworkInterface.c with standard peripheral library and run FreeRTOSIPInit(). Then I tryed ping my board and did'not get ping answer. ETHIRQHandler occures, all program doesn't crash.

MCU - STM32F429 compiler - arm-none-eaby-gcc


NetworkInterface.c:

~~~ /* Standard includes. */

include
include
include

/* FreeRTOS includes. */

include "FreeRTOS.h"
include "task.h"
include "queue.h"
include "semphr.h"

/* FreeRTOS+TCP includes. */

include "FreeRTOS_IP.h"
include "FreeRTOS_Sockets.h"
include "FreeRTOSIPPrivate.h"
include "NetworkBufferManagement.h"
include "stm32f4x7_eth.h"
include "NetworkInterfaceDefs.h"

/* ST includes. */

include "stm32f4xx.h"

/********************************************************************************** * prototypes *******************************************************************************/ static void prvEMACHandlerTask( void *pvParameters ); /******************************************************************************* * vars *******************************************************************************/ static TaskHandle_t xEMACTaskHandle = NULL; / Ethernet Rx & Tx DMA Descriptors / extern ETHDMADESCTypeDef DMARxDscrTab[ETHRXBUFNB], DMATxDscrTab[ETH_TXBUFNB]; / Ethernet Driver Receive buffers / extern uint8t RxBuff[ETHRXBUFNB][ETHRXBUFSIZE]; /* Ethernet Driver Transmit buffers */ extern uint8t TxBuff[ETHTXBUFNB][ETHTXBUFSIZE]; / Global pointer for last received frame infos */ extern ETHDMARxFrameinfos *DMARXFRAME_infos; /******************************************************************************** * static funs **********************************************************************************/ static void resetPhy (void) { GPIOInitTypeDef gpioInit; unsigned int some; gpioInit.GPIOMode = GPIOModeOUT; gpioInit.GPIOOType = GPIOOTypePP; gpioInit.GPIOPin = GPIOPin12; gpioInit.GPIOPuPd = GPIOPuPdNOPULL; gpioInit.GPIOSpeed = GPIOLowSpeed; GPIOInit(GPIOH, &gpioInit); GPIOWriteBit(GPIOH, GPIOPin12, BitRESET); some=1000000; while (some) some--; GPIOWriteBit(GPIOH, GPIOPin12, Bit_SET); }

static void initEthGpios (void) { GPIO_InitTypeDef gpioInit; unsigned int some;

RCC->AHB1ENR |= 0x00000010; //GPIOE enable clock
RCC->AHB1ENR |= 0x00000001; //GPIOA enable clock
RCC->AHB1ENR |= 0x00000002; //GPIOB enable clock
RCC->AHB1ENR |= 0x00000004; //GPIOC enable clock
RCC->AHB1ENR |= 0x00000040; //GPIOG enable clock
RCC->AHB1ENR |= 0x00000080; //GPIOH enable clock

gpioInit.GPIO_Mode = GPIO_Mode_OUT;
gpioInit.GPIO_OType = GPIO_OType_PP;
gpioInit.GPIO_Pin = GPIO_Pin_12;
gpioInit.GPIO_PuPd = GPIO_PuPd_NOPULL;
gpioInit.GPIO_Speed = GPIO_Low_Speed;
GPIO_Init(GPIOH, &gpioInit);
GPIO_WriteBit(GPIOH, GPIO_Pin_12, Bit_RESET);

some=1000000;
while (some) some--;

GPIO_WriteBit(GPIOH, GPIO_Pin_12, Bit_SET);

/* Enable System configuration controller clock */
RCC->APB2ENR |= (1 << 14);
/* Reset Ethernet MAC */
RCC->AHB1RSTR |=  0x02000000;
SYSCFG->PMC |=  (1 << 23);
RCC->AHB1RSTR &= ~0x02000000;
RCC->AHB1ENR |= 0x1E000047;

/* Configure Port A ethernet pins (PA.1, PA.2, PA.7) */
GPIOA->MODER   &= ~0x0000C03C;
GPIOA->MODER   |=  0x00008028;              /* Pins to alternate function */
GPIOA->OTYPER  &= ~0x00000086;              /* Pins in push-pull mode     */
GPIOA->OSPEEDR |=  0x0000C03C;              /* Slew rate as 100MHz pin    */
GPIOA->PUPDR   &= ~0x0000C03C;              /* No pull up, no pull down   */

GPIOA->AFR[0]  &= ~0xF0000FF0;
GPIOA->AFR[0]  |=  0xB0000BB0;              /* Pins to AF11 (Ethernet)    */

/* Configure Port C ethernet pins (PC.1, PC.4, PC.5) */
GPIOC->MODER   &= ~0x00000F0C;
GPIOC->MODER   |=  0x00000A08;              /* Pins to alternate function */
GPIOC->OTYPER  &= ~0x00000032;              /* Pins in push-pull mode     */
GPIOC->OSPEEDR |=  0x00000F0C;              /* Slew rate as 100MHz pin    */
GPIOC->PUPDR   &= ~0x00000F0C;              /* No pull up, no pull down   */

GPIOC->AFR[0]  &= ~0x00FF00F0;
GPIOC->AFR[0]  |=  0x00BB00B0;              /* Pins to AF11 (Ethernet)    */

/* Configure Port G ethernet pins (PB.12, PB.13) */
GPIOB->MODER   &= ~0x0F000000;
GPIOB->MODER   |=  0x0A000000;              /* Pin to alternate function  */
GPIOB->OTYPER  &= ~0x00003000;              /* Pin in push-pull mode      */
GPIOB->OSPEEDR |=  0x0F000000;              /* Slew rate as 100MHz pin    */
GPIOB->PUPDR   &= ~0x0F000000;              /* No pull up, no pull down   */

GPIOB->AFR[1]  &= ~0x00FF0000;
GPIOB->AFR[1]  |=  0x00BB0000;              /* Pin to AF11 (Ethernet)     */

/* Configure Port B ethernet pins (PB.11) */
GPIOB->MODER   &= ~0x00C00000;
GPIOB->MODER   |=  0x00800000;              /* Pins to alternate function */
GPIOB->OTYPER  &= ~0x00000800;              /* Pins in push-pull mode     */
GPIOB->OSPEEDR |=  0x00C00000;              /* Slew rate as 100MHz pin    */
GPIOB->PUPDR   &= ~0x0FF00000;              /* No pull up, no pull down   */

GPIOB->AFR[1]  &= ~0x0000F000;
GPIOB->AFR[1]  |=  0x0000B000;              /* Pins to AF11 (Ethernet)    */

}

/********************************************************************************** * global **********************************************************************************/

/** * @brief init ehternet controller * * @return / BaseTypet xNetworkInterfaceInitialise( void ) { ETHInitTypeDef ETH_InitStructure; / init randov function */ if( xEMACTaskHandle == NULL ) { RCCAPB2PeriphClockCmd(RCCAPB2PeriphSYSCFG, ENABLE); RCC->AHB1RSTR |= 0x02000000; SYSCFGETHMediaInterfaceConfig(SYSCFGETHMediaInterfaceRMII);

	RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_ETH_MAC | RCC_AHB1Periph_ETH_MAC_Tx | RCC_AHB1Periph_ETH_MAC_Rx | RCC_AHB1Periph_ETH_MAC_PTP, ENABLE);

	initEthGpios();

	ETH_SoftwareReset();
	while (ETH_GetSoftwareResetStatus() == SET);

	ETH_StructInit(&ETH_InitStructure);

	ETH_InitStructure.ETH_LoopbackMode = ETH_LoopbackMode_Disable;
	ETH_InitStructure.ETH_RetryTransmission = ETH_RetryTransmission_Disable;
	ETH_InitStructure.ETH_AutomaticPadCRCStrip = ETH_AutomaticPadCRCStrip_Disable;
	ETH_InitStructure.ETH_ReceiveAll = ETH_ReceiveAll_Disable;
	ETH_InitStructure.ETH_BroadcastFramesReception = ETH_BroadcastFramesReception_Enable;
	ETH_InitStructure.ETH_PromiscuousMode = ETH_PromiscuousMode_Disable;
	ETH_InitStructure.ETH_MulticastFramesFilter = ETH_MulticastFramesFilter_Perfect;
	ETH_InitStructure.ETH_UnicastFramesFilter = ETH_UnicastFramesFilter_Perfect;
	ETH_InitStructure.ETH_ChecksumOffload = ETH_ChecksumOffload_Enable;

	ETH_InitStructure.ETH_DropTCPIPChecksumErrorFrame = ETH_DropTCPIPChecksumErrorFrame_Enable; 
	ETH_InitStructure.ETH_ReceiveStoreForward = ETH_ReceiveStoreForward_Enable;         
	ETH_InitStructure.ETH_TransmitStoreForward = ETH_TransmitStoreForward_Enable;     

	ETH_InitStructure.ETH_ForwardErrorFrames = ETH_ForwardErrorFrames_Disable;       
	ETH_InitStructure.ETH_ForwardUndersizedGoodFrames = ETH_ForwardUndersizedGoodFrames_Disable;   
	ETH_InitStructure.ETH_SecondFrameOperate = ETH_SecondFrameOperate_Enable;
	ETH_InitStructure.ETH_AddressAlignedBeats = ETH_AddressAlignedBeats_Enable;      
	ETH_InitStructure.ETH_FixedBurst = ETH_FixedBurst_Enable;                
	ETH_InitStructure.ETH_RxDMABurstLength = ETH_RxDMABurstLength_32Beat;          
	ETH_InitStructure.ETH_TxDMABurstLength = ETH_TxDMABurstLength_32Beat;
	ETH_InitStructure.ETH_DMAArbitration = ETH_DMAArbitration_RoundRobin_RxTx_2_1;

	/* Configure Ethernet */
	ETH_Init(&ETH_InitStructure, PHYAddress);
	//Eth_Link_PHYITConfig(0x01);

	uint8_t macAdr[] = {0x1E, 0x30, 0x6C, 0xA2, 0x45, 0x5C};
	ETH_MACAddressConfig(ETH_MAC_Address0, macAdr);

	ETH_DMATxDescChainInit(DMATxDscrTab, &Tx_Buff[0][0], ETH_TXBUFNB);
	ETH_DMARxDescChainInit(DMARxDscrTab, &Rx_Buff[0][0], ETH_RXBUFNB);
	for(uint32_t i=0; i<ETH_TXBUFNB; i++)
	{
		ETH_DMATxDescChecksumInsertionConfig(&DMATxDscrTab[i], ETH_DMATxDesc_ChecksumTCPUDPICMPFull);
	}
	ETH_FlushTransmitFIFO();
	ETH_DMATransmissionCmd(ENABLE);
	ETH_DMAReceptionCmd(ENABLE);
	ETH_MACTransmissionCmd(ENABLE);
	ETH_MACReceptionCmd(ENABLE);
	/* Reset all interrupts */
	ETH->DMASR  = 0xFFFFFFFF;

	//ETH_DMA_IT_AIS | ETH_DMA_IT_RBU |
	ETH_DMAITConfig(ETH_DMA_IT_NIS |  ETH_DMA_IT_R, ENABLE);

	NVIC_InitTypeDef NVIC_InitStructure;
	NVIC_InitStructure.NVIC_IRQChannel = ETH_IRQn;
	NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0x0C;
	NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0x0C;
	NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
	NVIC_Init(&NVIC_InitStructure);

	ETH_Start();

	xTaskCreate( prvEMACHandlerTask, "EMAC", configEMAC_TASK_STACK_SIZE, NULL,
		   	configMAX_PRIORITIES - 1, &xEMACTaskHandle );
}
return pdPASS;

}

/** * @brief output data processing * * @param pxDescriptor * @param bReleaseAfterSend * * @return */ BaseTypet xNetworkInterfaceOutput( xNetworkBufferDescriptort * const pxDescriptor, BaseType_t bReleaseAfterSend ) { u32 ulTransmitSize = pxDescriptor->xDataLength;

if( ulTransmitSize > ETH_MAX_PACKET_SIZE )
{
	ulTransmitSize = ETH_MAX_PACKET_SIZE;
}
/* Copy bytes to dma buffres */
memcpy( ( void * ) DMATxDscrTab->Buffer1Addr, pxDescriptor->pucEthernetBuffer,
	   	ulTransmitSize );
/* Prepare transmit descriptors to give to DMA. */
ETH_Prepare_Transmit_Descriptors(ulTransmitSize);
iptraceNETWORK_INTERFACE_TRANSMIT();
if( bReleaseAfterSend != pdFALSE )
{
	vReleaseNetworkBufferAndDescriptor( pxDescriptor );
}
return pdTRUE;

}

/** * @brief Ethernet Irq */ void ETHIRQHandler( void ) { BaseTypet xHigherPriorityTaskWoken = 0;

if (ETH_GetDMAITStatus(ETH_DMA_IT_R) != RESET)
{
	ETH_CheckFrameReceived();
	ETH_DMAClearITPendingBit(ETH_DMA_IT_R);
	vTaskNotifyGiveFromISR( xEMACTaskHandle, &xHigherPriorityTaskWoken );
	//portYIELD_FROM_ISR( xHigherPriorityTaskWoken );
}
if (ETH_GetDMAITStatus(ETH_DMA_IT_NIS) != RESET)
{
	ETH_DMAClearITPendingBit(ETH_DMA_IT_NIS);
}
if (ETH_GetDMAITStatus(ETH_DMA_IT_AIS) != RESET)
{
	ETH_DMAClearITPendingBit(ETH_DMA_IT_AIS);
}
if (ETH_GetDMAITStatus(ETH_DMA_IT_RBU) != RESET)
{
	ETH_DMAClearITPendingBit(ETH_DMA_IT_RBU);
}

}

define BUFFERSIZE ( ipTOTALETHERNETFRAMESIZE + ipBUFFER_PADDING )
define BUFFERSIZEROUNDEDUP ( ( BUFFERSIZE + 7 ) & ~0x07UL )

static uint8t ucBuffers[ ipconfigNUMNETWORKBUFFERDESCRIPTORS ][ BUFFERSIZEROUNDED_UP ];

/* Static allocation buffers for FreeRTOS+TCP */ void vNetworkInterfaceAllocateRAMToBuffers( NetworkBufferDescriptort pxNetworkBuffers[ ipconfigNUMNETWORKBUFFERDESCRIPTORS ] ) { BaseType_t x;

for( x = 0; x < ipconfigNUM_NETWORK_BUFFER_DESCRIPTORS; x++ )
{
    pxNetworkBuffers[ x ].pucEthernetBuffer = &( ucBuffers[ x ][ ipBUFFER_PADDING ] );
    *( ( uint32_t * ) &ucBuffers[ x ][ 0 ] ) = ( uint32_t ) &( pxNetworkBuffers[ x ] );
}

}

/** * @brief ethernet driver handling task * * @param pvParameters */ static void prvEMACHandlerTask( void *pvParameters ) { NetworkBufferDescriptort *pxBufferDescriptor; sizet xBytesReceived; IPStackEventt xRxEvent; FrameTypeDef frame; __IO ETHDMADESCTypeDef *DMARxNextDesc;

for( ;; )
{
	ulTaskNotifyTake( pdFALSE, portMAX_DELAY  );

	while (ETH_CheckFrameReceived())
	{
		frame = ETH_Get_Received_Frame();
		/* Release descriptors to DMA */
		/* Check if frame with multiple DMA buffer segments */
		if (DMA_RX_FRAME_infos->Seg_Count > 1)
		{
			DMARxNextDesc = DMA_RX_FRAME_infos->FS_Rx_Desc;
		}
		else
		{
			DMARxNextDesc = frame.descriptor;
		}

		/* Set Own bit in Rx descriptors: gives the buffers back to DMA */
		for (u32 i=0; i<DMA_RX_FRAME_infos->Seg_Count; i++)
		{  
			DMARxNextDesc->Status = ETH_DMARxDesc_OWN;
			DMARxNextDesc = (ETH_DMADESCTypeDef *)(DMARxNextDesc->Buffer2NextDescAddr);
		}

		/* Clear Segment_Count */
		DMA_RX_FRAME_infos->Seg_Count =0;

		/* When Rx Buffer unavailable flag is set: clear it and resume reception */
		if ((ETH->DMASR & ETH_DMASR_RBUS) != (u32)RESET)  
		{
			/* Clear RBUS ETHERNET DMA flag */
			ETH->DMASR = ETH_DMASR_RBUS;
			/* Resume DMA reception */
			ETH->DMARPDR = 0;
		}

		if ( frame.length > 0 )
		{
			 pxBufferDescriptor = pxGetNetworkBufferWithDescriptor( xBytesReceived, 0 );
			 if( pxBufferDescriptor != NULL )
			 {
				 memcpy( pxBufferDescriptor->pucEthernetBuffer,
						 ( uint8_t * ) frame.buffer, frame.length);
				 pxBufferDescriptor->xDataLength = frame.length;
				 if( eConsiderFrameForProcessing( pxBufferDescriptor->pucEthernetBuffer )
						 == eProcessBuffer )
				 {
					 /* The event about to be sent to the TCP/IP is an Rx event. */
					 xRxEvent.eEventType = eNetworkRxEvent;

					 /* pvData is used to point to the network buffer descriptor that
						now references the received data. */
					 xRxEvent.pvData = ( void * ) pxBufferDescriptor;

					 /* Send the data to the TCP/IP stack. */
					 if( xSendEventStructToIPTask( &xRxEvent, 0 ) == pdFALSE )
					 {
						 /* The buffer could not be sent to the IP task so the buffer
							must be released. */
						 vReleaseNetworkBufferAndDescriptor( pxBufferDescriptor );

						 /* Make a call to the standard trace macro to log the
							occurrence. */
						 iptraceETHERNET_RX_EVENT_LOST();
					 }
					 else
					 {
						 /* The message was successfully sent to the TCP/IP stack.
							Call the standard trace macro to log the occurrence. */
						 iptraceNETWORK_INTERFACE_RECEIVE();
					 }
				 }
				 else
				 {
					 /* The Ethernet frame can be dropped, but the Ethernet buffer
						must be released. */
					 vReleaseNetworkBufferAndDescriptor( pxBufferDescriptor );
				 }
			 }
			 else
			 {
				 /* The event was lost because a network buffer was not available.
					Call the standard trace macro to log the occurrence. */
				 iptraceETHERNET_RX_EVENT_LOST();
			 }
		}
	}
}

} /********************************************************************************** * eof **********************************************************************************/ ~~~


Creating freertos+tcp task

~~~ /** * @file tcpProcess.cpp * @brief tcp task and etc. * @author * @version * @date 2016-09-16 */

include

/* FreeRTOS includes. */

include
include "task.h"
include "timers.h"
include "queue.h"
include "semphr.h"

/* FreeRTOS+TCP includes. */

include "FreeRTOS_IP.h"
include "FreeRTOS_Sockets.h"
include "FreeRTOS_DHCP.h"
include "stm32f4xx.h"

const uint8t ucIPAddress[ ipIPADDRESSLENGTHBYTES ] = {192, 168, 10, 50}; const uint8t ucNetMask[ ipIPADDRESSLENGTHBYTES ] = { 255, 255, 255, 0 }; const uint8t ucGatewayAddress[ ipIPADDRESSLENGTHBYTES ] = {192, 168, 10, 1}; const uint8t ucDNSServerAddress[ ipIPADDRESSLENGTHBYTES ] = { 208, 67, 222, 222 }; const uint8t ucMACAddress[ ipMACADDRESSLENGTHBYTES ] = { 0x1E, 0x30, 0x6C, 0xA2, 0x45, 0x5C }; /********************************************************************************** * static *******************************************************************************/ static void initRandomFunction (void) { / Enable RNG clock source / RCCAHB2PeriphClockCmd(RCCAHB2Periph_RNG, ENABLE); / RNG Peripheral enable */ RNG_Cmd(ENABLE); } /******************************************************************************** * global ********************************************************************************/ / * @brief random function * * @return */ UBaseTypet uxRand( void ) { const uint32t ulMultiplier = 0x015a4e35UL, ulIncrement = 1UL; static BaseTypet xInitialised = pdFALSE; static UBaseTypet ulNextRand;

/* Don't initialise until the scheduler is running, as the timeout in the
random number generator uses the tick count. */
if( xInitialised == pdFALSE )
{
		uint32_t ulSeed;
		/* Generate a random number with which to seed the local pseudo random
		   number generating function. */
		while(RNG_GetFlagStatus(RNG_FLAG_DRDY)== RESET);
		ulSeed = RNG_GetRandomNumber();
		ulNextRand = ulSeed;
		xInitialised = pdTRUE;
}
/* Utility function to generate a pseudo random number. */
ulNextRand = ( ulMultiplier * ulNextRand ) + ulIncrement;
return( ( int ) ( ulNextRand >> 16UL ) & 0x7fffUL );

}

/** * @brief start FreeRTOS+TCP */ void initTcpProcess (void) { initRandomFunction(); FreeRTOS_IPInit( ucIPAddress, ucNetMask, ucGatewayAddress, ucDNSServerAddress, ucMACAddress ); }

void vApplicationIPNetworkEventHook( eIPCallbackEvent_t eNetworkEvent ) { }

void vApplicationPingReplyHook( ePingReplyStatust eStatus, uint16t usIdentifier ) { }

/********************************************************************************** * eof **********************************************************************************/

~~~


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by rtel on September 19, 2016

I'm afraid I cannot spend a lot of time reading through a lot of chip specific code as it would only make sense if I also spend a lot of time reading the hardware manual. We either need more information as to how far you get, or you can use the STM32 driver that is already in the FreeRTOS Labs download.

With regards to how far you get:

  • You say the ETH_IRQHandler() executes. How many times does it execute? What does it do when it executes?

  • Does the task with the handle xEMACTaskHandle execute after being unblocked by the IRQ handler. If so, what does it do?

  • Why do you have the yield that uses xHigherPriorityTaskWoken commented out?


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by yanvasilij on September 19, 2016

Thanks for your answer!

  • The ETH_IRQHandler() happens sometimes without any reason and always when I pinging the board with ping commnad
  • xEMACTaskHandle execute always after ETH_IRQHandler
  • I suppressed xHigherPriorityTaskWoken for save stack. I use cooperative multitasking and switch contex by using vTaskYEILD(). Anyway I can turn it back, but I don't think that problem in it.

FreeRTOS+TCP Simple network interfaces STM32F429

Posted by rtel on September 19, 2016

I've never used the TCP stack with co-operative multi-tasking. I'm not sure what the result would be.


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by yanvasilij on September 19, 2016

Ok. I turned off co-operative multi-tasking (set configUSEPREEMPTION to 1 and configIDLESHOULDYIELD to 0). The problem is still exist. Furthermore I figured out that programm crashed to DefaultHandler after some time. Does I understed correct to port FreeRTOS+TCP and build an application (to check ping only) I need:

  • Provide xNetworkInterfaceInitialise() where MAC, PHY and MACDMA are initialized
  • Provide xNetworkInterfaceOutput() for sending data to MAC
  • Send incoming frames to ip stack by xSendEventStructToIPTask()
  • Provide vNetworkInterfaceAllocateRAMToBuffers() to bind staticaly allocated RAM buffres
  • Provide uxRand() to generate random values
  • Provide callbacks like vApplicationIPNetworkEventHook if need
  • Call FreeRTOS_IPInit() with necessary params to run stack

?


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by rtel on September 19, 2016

/ Provide vNetworkInterfaceAllocateRAMToBuffers() to bind staticaly allocated RAM buffres

That is only necessary if you are using BufferAllocation1. BufferAllocation2 is simpler to use, although slower, and prevents you allocating buffers from an ISR.

You need to determine which interrupt is calling the default handler in order to start debugging why you end up there. See the "Determining Which Exception Handler is Executing" section on the following page: http://www.freertos.org/Debugging-Hard-Faults-On-Cortex-M-Microcontrollers.html


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by yanvasilij on September 19, 2016

Yes, I use BufferAllocation_1.

I figured out (I used instruction on your link) that HardFault_Handler is occures sometimes (not all time). There is no another tasks in my application except freertos+tcp.


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by rtel on September 19, 2016

Now you know it is a hard fault you need to find where it is occurring. There is information on that on the same link.

Do you have configASSERT() defined, and stack overflow checking set to 2?


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by yanvasilij on September 19, 2016

I set configASSERT() follows: ~~~

define configASSERT(x) if( ( x ) == 0 ) for(;;)

~~~ configCHECKFORSTACK_OVERFLOW follow: ~~~

define configCHECKFORSTACK_OVERFLOW 2

~~~ Declared vApplicationStackOverflowHook: ~~~ void vApplicationStackOverflowHook(void) { while(1); } ~~~

So sheduler start succesfully (I've never stop in configASSERT() ) and I don't get vApplicationStackOverflowHook.

When I debug HardFaultHandler I see the follow sequence: 1) prvPortStartFirstTask() called 2) prvPortStartFirstTask() called 3) some strange () 0xfffffffd 4) HardFaultHandler ()

coidescreen


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by rtel on September 19, 2016
define configASSERT(x) if( ( x ) == 0 ) for(;;)

You also need to disable interrupts - otherwise you would only know if you hit the assert if it was the highest priority task that was spinning in the loopl

When I debug HardFaultHandler I see the follow sequence: 1) prvPortStartFirstTask() called 2) prvPortStartFirstTask() called 3) some strange () 0xfffffffd 4) HardFaultHandler ()

The call stack doesn't tell you where the fault occurred - to do that you need to pull the program counter off the stack, as described on the previously linked page.


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by yanvasilij on September 19, 2016

I did the follows: In main: ~~~ int main(void) { uint32t *ACTLR = (uint32t *)0xE000E008; *ACTLR |= 2; //setting the DISDEFWBUF bit (bit 1) ... } ~~~ About configASSERT: ~~~ extern void vAssertCalled (void);

define configASSERT(x) if( ( x ) == 0 ) vAssertCalled()

... //somewhere void vAssertCalled (void) { taskDISABLE_INTERRUPTS(); for(;;); } ~~~

There is no change. I still have the same debug sequence when HardFault_Handler occurs.


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by davedoors on September 19, 2016

but have your found the instruction that was executing when the hard fault happens?


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by yanvasilij on September 19, 2016

No, I havn't. As Real Time Engineers ltd. sad call stack doesn't tell me where the fault occurred. Setting the DISDEFWBUF bit (bit 1) didn't helped.


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by rtel on September 19, 2016

The page I linked to in my first (or second?) post that you used to find which handler had been called tells you how to do that though.


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by yanvasilij on September 19, 2016

I am sorry. I was looking in wrong place. So I declared HardFaultHandler as described [here](http://www.freertos.org/Debugging-Hard-Faults-On-Cortex-M-Microcontrollers.html#armcorteximprecisefaults). When HardFault_Handler occured I looked into pc varible and figured out that it value is 0x0801a9ea. I looked at 0x0801a9ea in disassembly and figured out that instraction that causes fault is:

~~~ /* Set Own bit in Rx descriptors: gives the buffers back to DMA */ for (u32 i=0; iSegCount; i++) {
DMARxNextDesc->Status = ETHDMARxDescOWN; //<< THIS INSTRACTION CAUSES ERROR DMARxNextDesc = (ETHDMADESCTypeDef *)(DMARxNextDesc->Buffer2NextDescAddr); } ~~~


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by rtel on September 19, 2016

As a guess I would think DMARxNextDesc had an invalid value when you tried accessing it, so the write to DMARxNextDesc->Status causes a fault.


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by billskeen68 on October 3, 2016

New to debugging FreeRTOS and trying to follow exactly what to change in code to be able to get a precise hard fault PC register address to debug my application. I've reviewed this thread, the link from Real Time Engineers and several others, like:

http://www.freertos.org/Debugging-Hard-Faults-On-Cortex-M-Microcontrollers.html

and

https://blog.frankvh.com/2011/12/07/cortex-m3-m4-hard-fault-handler/

Could someone help out a noob and point me to something specific please? Thanks in advance.


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by rtel on October 4, 2016

The link you posted contains source code to do this, so I'm not sure what other specific information can be provided. Perhaps if you could show/explain what you have tried and why it didn't work we could provide some suggestions.


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by billskeen68 on October 4, 2016

I am using the FreeRTOS/Particle/Redbear Duo version of the firmware from: https://github.com/redbear/firmware

The bug I am trying to find is with my code calling TCPClient.write that is failing randomly.

i = client.write((const uint8_t *)pmessage.c_str(), pmessage.length());

I do a serial print of the up to 900 byte message just before the write and I can see no problems with it. Sometimes it fails immediately after startup, sometimes days or weeks later. When it does fail, I get a HardFault code 1 ( SOS blinks, then 1 blink, repeat).

I have compiled a debug version using Particle/RedBear make files and I have a breakpoint on the prvGetRegistersFromStack function in the corehalstm32f2xx.c file. This is the file/function RedBear support told me to put the breakpoint.

When the breakpoint is hit, I examine the pc register and it is pointing to the HardFault_Handler:

Breakpoint 1, HardFaultHandler () at src/stm32f2xx/corehalstm32f2xx.c:112 112 __asm volatile (gdb) info registers r0 0x0 0 r1 0x0 0 r2 0x2 2 r3 0x20020000 537001984 r4 0x20000dfc 536874492 r5 0x20000dfc 536874492 r6 0x8077da0 134708640 r7 0x20 32 r8 0xa5a5a5a5 -1515870811 r9 0xa5a5a5a5 -1515870811 r10 0xa5a5a5a5 -1515870811 r11 0xa5a5a5a5 -1515870811 r12 0xccccccc 214748364 sp 0x2001ffe0 0x2001ffe0 lr 0xfffffffd -3 pc 0x80533be 0x80533be <HardFaultHandler> xPSR 0x61000003 1627389955

Not sure what to do from here. That was the reason for the precise hardfault question.


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by rtel on October 4, 2016

Have you followed the instructions in the "Handling Imprecise Faults" section of the page previously linked (setting bit 1 of the ACTLR register)?


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by billskeen68 on October 4, 2016

That is the part I am not sure of where/what to do. Does this code go in core_hal.c, somewhere near/before the vTaskStartScheduler();?

uint32_t *ACTLR = (uint32_t *)0xE000E008;
*ACTLR |= 2; //setting the DISDEFWBUF bit (bit 1)

int main(void) { initmallocmutex(); xTaskCreate( applicationtaskstart, "appthread", APPLICATIONSTACKSIZE/sizeof( portSTACKTYPE ), NULL, 2, &appthreadhandle);

 uint32t ACTLR = (uint32t )0xE000E008;
*ACTLR |= 2; //setting the DISDEFWBUF bit (bit 1)

vTaskStartScheduler();

/* we should never get here */
while (1);

return 0;

}

How do I determine if I need configAssert and where does it go?

Sorry to be so dumb here, but learning as I go.


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by davedoors on October 4, 2016

in main:

~~~ uint32t * ACTLR = ((uint32t*)0xE000E008) uint32_t temp;

temp = *ACTLR; temp |= 0x02; *ACTLR = temp; // bit now set ~~~


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by billskeen68 on October 4, 2016

Okay, I added the 2 lines of code to the core_hal.c main function, recompiled debug version and now waiting for breakpoint hit. Interesting to note that this slowed down BLE device detection considerably. What used to take less than 30 seconds at startup now takes 4-5 minutes.


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by edwards3 on October 5, 2016

from the FreeRTOS page "turning off write buffering by setting the DISDEFWBUF bit (bit 1) in the Auxiliary Control Register (or ACTLR) will result in the imprecise fault becoming a precise fault, which makes the fault easier to debug, albeit at the cost of slower program execution."


FreeRTOS+TCP Simple network interfaces STM32F429

Posted by billskeen68 on October 5, 2016

Thanks MEdwards. I did read that. I just was not expecting 10x slower. Now that I have made that change, I have not had a hardfault since. Not sure what to do now, so going back to board mfg for suggestions.

Thank all for the help.


[ Back to the top ]    [ About FreeRTOS ]    [ Privacy ]    [ Sitemap ]    [ ]


Copyright (C) Amazon Web Services, Inc. or its affiliates. All rights reserved.

Latest News

NXP tweet showing LPC5500 (ARMv8-M Cortex-M33) running FreeRTOS.

Meet Richard Barry and learn about running FreeRTOS on RISC-V at FOSDEM 2019

Version 10.1.1 of the FreeRTOS kernel is available for immediate download. MIT licensed.

View a recording of the "OTA Update Security and Reliability" webinar, presented by TI and AWS.


Careers

FreeRTOS and other embedded software careers at AWS.



FreeRTOS Partners

ARM Connected RTOS partner for all ARM microcontroller cores

Espressif ESP32

IAR Partner

Microchip Premier RTOS Partner

RTOS partner of NXP for all NXP ARM microcontrollers

Renesas

STMicro RTOS partner supporting ARM7, ARM Cortex-M3, ARM Cortex-M4 and ARM Cortex-M0

Texas Instruments MCU Developer Network RTOS partner for ARM and MSP430 microcontrollers

OpenRTOS and SafeRTOS

Xilinx Microblaze and Zynq partner