Browse Source

v20220606.patch03

huangliang 2 years ago
parent
commit
67651f2553

+ 6 - 1
AMTLDR/Src/SpiBooter.c

@@ -65,7 +65,12 @@ static const flash_chip flash_chip_table[] =
     {"S25FL032P", SFUD_MF_ID_CYPRESS, 0x02, 0x15, 4L*1024L*1024L},    \
     {"A25L080", SFUD_MF_ID_AMIC, 0x30, 0x14, 1L*1024L*1024L},         \
     {"F25L004", SFUD_MF_ID_ESMT, 0x20, 0x13, 512L*1024L},             \
+    {"MX25L6433F", SFUD_MF_ID_MICRONIX, 0x20, 0x17, 8L*1024L*1024L},  \
+    {"MX25L12845G", SFUD_MF_ID_MICRONIX, 0x20, 0x18, 16L*1024L*1024L},  \
+    {"MX25L25645G", SFUD_MF_ID_MICRONIX, 0x20, 0x19, 32L*1024L*1024L},\
     {"PCT25VF016B", SFUD_MF_ID_SST, 0x25, 0x41, 2L*1024L*1024L},      \
+    {"GD25B256", SFUD_MF_ID_GIGADEVICE, 0x43, 0x19, 32L*1024L*1024L},\
+    {"GD25B512ME", SFUD_MF_ID_GIGADEVICE, 0x47, 0x1A, 64L*1024L*1024L},
 };
 
 static int addr_in_4_byte = 0;
@@ -92,7 +97,7 @@ static void SetSpiDataMode(unsigned int bitMode)
 static void SpiWaitIdle(void)
 {
 	while(rSPI_SR & SPIFLASH_BUSY);
-	udelay(1);
+	udelay(2);
 }
 
 static void SpiEmptyRxFIFO(void)

+ 31 - 5
STEPLDR/Src/SpiBooter.c

@@ -35,7 +35,7 @@
 #define SFUD_MF_ID_SST                                 0xBF
 #define SFUD_MF_ID_MICRONIX                            0xC2
 #define SFUD_MF_ID_GIGADEVICE                          0xC8
-#define SFUD_MF_ID_ISSI                                0xD5
+#define SFUD_MF_ID_ISSI                                0x9D
 #define SFUD_MF_ID_WINBOND                             0xEF
 
 static void SpiWriteEnable(void);
@@ -70,7 +70,13 @@ static const flash_chip flash_chip_table[] =
     {"S25FL032P", SFUD_MF_ID_CYPRESS, 0x02, 0x15, 4L*1024L*1024L},    \
     {"A25L080", SFUD_MF_ID_AMIC, 0x30, 0x14, 1L*1024L*1024L},         \
     {"F25L004", SFUD_MF_ID_ESMT, 0x20, 0x13, 512L*1024L},             \
+    {"MX25L6433F", SFUD_MF_ID_MICRONIX, 0x20, 0x17, 8L*1024L*1024L},  \
+    {"MX25L12845G", SFUD_MF_ID_MICRONIX, 0x20, 0x18, 16L*1024L*1024L},  \
+    {"MX25L25645G", SFUD_MF_ID_MICRONIX, 0x20, 0x19, 32L*1024L*1024L},\
     {"PCT25VF016B", SFUD_MF_ID_SST, 0x25, 0x41, 2L*1024L*1024L},      \
+    {"GD25B128c", SFUD_MF_ID_GIGADEVICE, 0x43, 0x19, 32L*1024L*1024L},\
+    {"GD25B256", SFUD_MF_ID_GIGADEVICE, 0x43, 0x19, 32L*1024L*1024L},\
+    {"GD25B512ME", SFUD_MF_ID_GIGADEVICE, 0x47, 0x1A, 64L*1024L*1024L},
 };
 
 static int addr_in_4_byte = 0;
@@ -97,7 +103,7 @@ static void SetSpiDataMode(unsigned int bitMode)
 static void SpiWaitIdle(void)
 {
 	while(rSPI_SR & SPIFLASH_BUSY);
-	udelay(1);
+	udelay(2);
 }
 
 static void SpiEmptyRxFIFO(void)
@@ -141,6 +147,18 @@ static UINT8 SpiReadSta2(void)
 	SetSpiDataMode(32);
 	return status;
 }
+
+static void SpiWriteSta(uint8_t status)
+{
+	SpiWriteEnable();
+	SetSpiDataMode(8);
+	SetCSGpioEnable(1);
+	rSPI_DR = SPI_WRITE_STATUS;
+	rSPI_DR = status;
+	SpiWaitIdle();
+	SetCSGpioEnable(0);
+	SetSpiDataMode(32);
+}
 #endif
 
 static UINT8 SpiReadSta3(void)
@@ -506,9 +524,17 @@ void SpiInit()
 		SpiDisable4ByteMode();
 
 #ifdef SPI0_QSPI_MODE
-	uint8_t status = SpiReadSta2();
-	status |= SPI_QE;
-	SpiWriteSta2(status);
+	if (i < sizeof(flash_chip_table) / sizeof(flash_chip) &&
+		(SFUD_MF_ID_ISSI == flash_chip_table[i].mf_id ||
+		 SFUD_MF_ID_MICRONIX == flash_chip_table[i].mf_id)) {
+		uint8_t status = SpiReadSta();
+		status |= SPI_QE2;
+		SpiWriteSta(status);
+	} else {
+		uint8_t status = SpiReadSta2();
+		status |= SPI_QE;
+		SpiWriteSta2(status);
+	}
 #endif
 	
 	SpiReadSta3();

+ 1 - 0
STEPLDR/Src/spi.h

@@ -50,6 +50,7 @@
 #define SPIFLASH_WRITEENABLE		(1<<1)
 
 #define SPI_QE					(1 << 1)
+#define SPI_QE2					(1 << 6)
 
 #define SPI_WRITE_DMA  
 #define SPI_READ_DMA    

+ 1 - 1
amt630h-freertos/ArkmicroFiles/libboard-amt630h/include/board.h

@@ -221,7 +221,7 @@
 //#define I2C1_SLAVE_MODE
 //#define I2C_EEPROM_SLAVE_DEMO
 //#define I2C_EEPROM_MASTER_DEMO
-#define I2C_GPIO0_SDA_PIN		102
+#define I2C_GPIO0_SDA_PIN		100
 #define I2C_GPIO0_SCL_PIN		101
 /*******************************************/
 

+ 1 - 1
amt630h-freertos/ArkmicroFiles/libcpu-amt630h/source/clock.c

@@ -305,7 +305,7 @@ static void clk_sys_init(xClockProperty *clk)
 	if (clk->u.sys_property.inv_reg) {
 		reg = readl(clk->u.sys_property.inv_reg);
 		reg &= ~(clk->u.sys_property.inv_mask << clk->u.sys_property.inv_offset);
-		reg |= (clk->u.sys_property.inv_value << clk->u.sys_property.inv_mask)
+		reg |= (clk->u.sys_property.inv_value & clk->u.sys_property.inv_mask)
 				<< clk->u.sys_property.inv_offset;
 		writel(reg, clk->u.sys_property.inv_reg);
 	}

+ 67 - 92
amt630h-freertos/ArkmicroFiles/libcpu-amt630h/source/dma.c

@@ -27,6 +27,7 @@
 
 static struct dma_chan dma_ch[DMA_CH_NUM] = {0};
 static SemaphoreHandle_t dma_mutex;
+static QueueHandle_t dma_m2m_done = NULL;
 
 
 struct dma_chan *dma_request_channel(int favorite_ch)
@@ -148,7 +149,7 @@ int dma_config_channel(struct dma_chan *chan, struct dma_config *config)
 		int lli_num;
 		int i;
 
-		lli_num = (blk_size + DMA_BLOCK_SIZE - 1) / DMA_BLOCK_SIZE;
+		lli_num = (blk_size + DMA_BLOCK_SIZE - 1) / DMA_BLOCK_SIZE - 1;
 		if (chan->lli) {
 			vPortFree(chan->lli);
 			chan->lli = NULL;
@@ -157,24 +158,24 @@ int dma_config_channel(struct dma_chan *chan, struct dma_config *config)
 		if (!chan->lli)
 			return -ENOMEM;
 		for (i = 0; i < lli_num - 1; i++) {
-			chan->lli[i].src_addr = config->src_addr + (si ? i : 0) * (DMA_BLOCK_SIZE << src_width);
-			chan->lli[i].dst_addr = config->dst_addr + (di ? i : 0) * (DMA_BLOCK_SIZE << src_width);
+			chan->lli[i].src_addr = config->src_addr + (si ? (i + 1) : 0) * (DMA_BLOCK_SIZE << src_width);
+			chan->lli[i].dst_addr = config->dst_addr + (di ? (i + 1) : 0) * (DMA_BLOCK_SIZE << src_width);
 			chan->lli[i].next_lli = (unsigned int)&chan->lli[i + 1];
 			chan->lli[i].control = ctl | DMA_BLOCK_SIZE;
 			if (!config->blkint_en)
 				chan->lli[i].control &= ~(1 << 31);
 		}
-		chan->lli[i].src_addr = config->src_addr + (si ? i : 0) * (DMA_BLOCK_SIZE << src_width);
-		chan->lli[i].dst_addr = config->dst_addr + (di ? i : 0) * (DMA_BLOCK_SIZE << src_width);
+		chan->lli[i].src_addr = config->src_addr + (si ? (i + 1) : 0) * (DMA_BLOCK_SIZE << src_width);
+		chan->lli[i].dst_addr = config->dst_addr + (di ? (i + 1) : 0) * (DMA_BLOCK_SIZE << src_width);
 		chan->lli[i].next_lli = 0;
-		chan->lli[i].control = ctl | (blk_size - DMA_BLOCK_SIZE * (lli_num - 1));
+		chan->lli[i].control = ctl | (blk_size - DMA_BLOCK_SIZE * lli_num);
 		CP15_clean_dcache_for_dma((unsigned int)chan->lli,
 			(unsigned int)chan->lli + sizeof(struct dma_lli) * lli_num);
 
-		rDMACCxSrcAddr(chan->chan_id) = 0;
-		rDMACCxDestAddr(chan->chan_id) = 0;
+		rDMACCxSrcAddr(chan->chan_id) = config->src_addr;
+		rDMACCxDestAddr(chan->chan_id) = config->dst_addr;
 		rDMACCxLLI(chan->chan_id) = (unsigned int)chan->lli | 1;
-		rDMACCxControl(chan->chan_id) = ctl & ~(1 << 31) | 1;
+		rDMACCxControl(chan->chan_id) = ctl & ~(1 << 31) | DMA_BLOCK_SIZE;
 		rDMACCxConfiguration(chan->chan_id)	= cfg;
 	} else {
 		rDMACCxSrcAddr(chan->chan_id) = config->src_addr;
@@ -187,88 +188,6 @@ int dma_config_channel(struct dma_chan *chan, struct dma_config *config)
 	return 0;
 }
 
-int dma_config_cylic_channel(struct dma_chan *chan, struct dma_config *config, int num)
-{
-	unsigned int ctl;
-	unsigned int cfg;
-	unsigned int src_width, dst_width;
-	unsigned int src_id = 0, dst_id = 0;
-	unsigned int di = 0, si = 0;
-	unsigned int data_width = (1 << DMA_BUSWIDTH_4_BYTES);
-	int i;
-
-	if (chan->lli) {
-		vPortFree(chan->lli);
-		chan->lli = NULL;
-	}
-	chan->lli = pvPortMalloc(sizeof(struct dma_lli) * num);
-	if (!chan->lli)
-		return -ENOMEM;
-
-	for (i = 0; i < num; i++) {
-		convert_burst(&config->src_maxburst);
-		convert_burst(&config->dst_maxburst);
-
-		if (config->direction == DMA_MEM_TO_DEV) {
-			src_width = __ffs(data_width | config->src_addr | config->transfer_size);
-			dst_width = config->dst_addr_width;
-			dst_id = config->dst_id;
-			si = 1;
-		} else if (config->direction == DMA_DEV_TO_MEM) {
-			src_width = config->src_addr_width;
-			dst_width = __ffs(data_width | config->dst_addr | config->transfer_size);
-			src_id = config->src_id;
-			di = 1;
-		} else if (config->direction == DMA_MEM_TO_MEM) {
-			src_width = __ffs(data_width | config->src_addr | config->transfer_size);
-			dst_width = __ffs(data_width | config->dst_addr | config->transfer_size);
-			si = 1;
-			di = 1;
-		}
-
-		ctl = (1 << 31) |   /* [31] I Read/write Terminal count interrupt enable bit */
-			  (0 << 28) | /* [30:28] Prot Read/write Protection */
-			  (di << 27) |  /* [27] DI Read/write Destination increment */
-			  (si << 26) |  /* [26] SI Read/write Source increment */
-			  (0 << 25) |   /* [25] D Read/write Destination AHB master select */
-			  (1 << 24) |   /* [24] S Read/write Source AHB master select */
-			  (dst_width << 21) | /* [23:21] DWidth Read/write Destination transfer width */
-			  (src_width << 18) | /* [20:18] SWidth Read/write Source transfer width */
-			  (config->dst_maxburst << 15) | /* [17:15] DBSize Read/write Destination burst size */
-			  (config->src_maxburst << 12) | /* [14:12] SBSize Read/write Source burst size */
-			  0; /*	[11:0] TransferSize Read/write Transfer size */
-
-		cfg = (0 << 18) | /* [18] H Read/write Halt */
-			  (0 << 16) | /* [16] L Read/write Lock */
-			  (1 << 15) | /* [15] ITC Read/write Terminal count interrupt mask */
-			  (1 << 14) | /* [14] IE Read/write Interrupt error mask */
-			  (config->direction << 11) | /* [13:11] FlowCntrl Read/write Flow control and transfer type */
-			  (dst_id << 6) | /* [9:6] DestPeripheral Read/write Destination peripheral */
-			  (src_id << 1) | /* [4:1] SrcPeripheral Read/write Source peripheral */
-			  0; /* [0] Channel enable */
-
-		chan->lli[i].src_addr = config->src_addr;
-		chan->lli[i].dst_addr = config->dst_addr;
-		chan->lli[i].next_lli = (unsigned int)&chan->lli[i + 1];
-		chan->lli[i].control = ctl | (config->transfer_size >> src_width);
-		if (!config->blkint_en)
-			chan->lli[i].control &= ~(1 << 31);
-		config++;
-	}
-	chan->lli[i - 1].next_lli = (unsigned int)&chan->lli[0];
-	CP15_clean_dcache_for_dma((unsigned int)chan->lli,
-		(unsigned int)chan->lli + sizeof(struct dma_lli) * num);
-
-	rDMACCxSrcAddr(chan->chan_id) = 0;
-	rDMACCxDestAddr(chan->chan_id) = 0;
-	rDMACCxLLI(chan->chan_id) = (unsigned int)chan->lli | 1;
-	rDMACCxControl(chan->chan_id) = ctl & ~(1 << 31) | 1;
-	rDMACCxConfiguration(chan->chan_id) = cfg;
-
-	return 0;
-}
-
-
 int dma_register_complete_callback(struct dma_chan *chan,
 											void (*callback)(void *param, unsigned int mask),
 											void *callback_param)
@@ -302,7 +221,7 @@ int dma_stop_channel(struct dma_chan *chan)
 	}
 
 	// A channel can be disabled by clearing the Enable bit.
-	rDMACCxConfiguration(chan->chan_id) &= ~(1 << chan->chan_id);
+	rDMACCxConfiguration(chan->chan_id) &= ~1;
 
 	// waiting
 	while(rDMACEnbldChns & (1 << chan->chan_id)) {
@@ -323,6 +242,61 @@ int dma_stop_channel(struct dma_chan *chan)
 	return 0;
 }
 
+static void dma_m2m_callback(void *param, unsigned int mask)
+{
+	if(dma_m2m_done)
+		xQueueSendFromISR(dma_m2m_done, NULL, 0);
+}
+
+int dma_m2mcpy(unsigned int dst_addr, unsigned int src_addr, int size)
+{
+	struct dma_config cfg = {0};
+	int ret = -1;
+
+	struct dma_chan *dma_ch = dma_request_channel(0);
+	if (!dma_ch) {
+		printf("%s() dma_request_channel fail.\n",  __func__);
+		return -1;
+	}
+
+	cfg.dst_addr_width = DMA_BUSWIDTH_4_BYTES;
+	cfg.dst_maxburst = 256;
+	cfg.src_addr_width = DMA_BUSWIDTH_4_BYTES;
+	cfg.src_maxburst = 256;
+	cfg.transfer_size = size;
+	cfg.src_addr = src_addr;
+	cfg.dst_addr = dst_addr;
+	cfg.direction = DMA_MEM_TO_MEM;
+
+	dma_clean_range(src_addr, src_addr + size);
+	dma_inv_range(dst_addr, dst_addr + size);
+
+	ret = dma_config_channel(dma_ch, &cfg);
+	if (ret) {
+		printf("%s, dma_config_channel failed.\n", __func__);
+		goto exit;
+	}
+
+	dma_register_complete_callback(dma_ch, dma_m2m_callback, NULL);
+
+	xQueueReset(dma_m2m_done);
+
+	dma_start_channel(dma_ch);
+	if (xQueueReceive(dma_m2m_done, NULL, pdMS_TO_TICKS(1000)) != pdTRUE) {
+		printf("dma_m2mcpy wait timeout.\n");
+		ret = -ETIMEDOUT;
+		goto exit;
+	}
+
+	dma_stop_channel(dma_ch);
+	ret = 0;
+exit:
+	if(dma_ch)
+		dma_release_channel(dma_ch);
+	return ret;
+}
+
+
 static void dma_int_handler(void *param)
 {
 	unsigned int err_status, tfr_status;
@@ -359,6 +333,7 @@ static void dma_int_handler(void *param)
 int dma_init(void)
 {
 	dma_mutex = xSemaphoreCreateMutex();
+	dma_m2m_done = xQueueCreate(1, 0);
 
 	sys_soft_reset(softreset_dma);
 

+ 4 - 0
amt630h-freertos/ArkmicroFiles/libcpu-amt630h/source/pxp.c

@@ -141,6 +141,8 @@ int pxp_scaler_rotate(uint32_t s0buf, uint32_t s0ubuf, uint32_t s0vbuf,
 
 	ctrl = (1 << 19) | (1 << 18) | ((s0format & 0xf) << 12) | (outangle << 8) |
 		((outformat & 0xf) << 4) | 3;
+	if (outformat == PXP_OUT_FMT_ARGB8888)
+		ctrl |= (1 << 22);
 
 	xQueueReset(pxp_done);
 	writel(ctrl, pxpbase + PXP_CTRL);
@@ -185,6 +187,8 @@ int pxp_rotate(uint32_t s0buf, uint32_t s0ubuf, uint32_t s0vbuf,
 	writel(0x79c | (0x730 <<16), pxpbase + PXP_CSCCOEFF2);
 
 	ctrl = ((s0format & 0xf) << 12) | (outangle << 8) | ((outformat & 0xf) << 4) | 3;
+	if (outformat == PXP_OUT_FMT_ARGB8888)
+		ctrl |= (1 << 22);
 
 	xQueueReset(pxp_done);
 	writel(ctrl, pxpbase + PXP_CTRL);

+ 2 - 2
amt630h-freertos/ArkmicroFiles/libcpu-amt630h/source/sdmmc.c

@@ -821,7 +821,7 @@ static int dw_mci_submit_data_dma(struct ark_mmc_obj *mmc_obj, struct mmcsd_data
 	return 0;
 }
 
-static void ark_mmc_perpare_data(struct mmc_driver *mmc_drv)
+static void ark_mmc_prepare_data(struct mmc_driver *mmc_drv)
 {
     struct mmcsd_cmd *cmd = mmc_drv->cmd;
     struct mmcsd_data *data = cmd->data;
@@ -1059,7 +1059,7 @@ static void ark_mmc_request(struct mmcsd_host *host, struct mmcsd_req *req)
     }
 
 	mmc_obj->result = 0;
-    ark_mmc_perpare_data(mmc_drv);
+    ark_mmc_prepare_data(mmc_drv);
     ark_mmc_send_command(mmc_drv, cmd);
     ret = ark_mmc_get_response(mmc_drv, cmd);
     if(ret)

+ 16 - 0
amt630h-freertos/ArkmicroFiles/libcpu-amt630h/source/uart.c

@@ -410,6 +410,7 @@ static void vUart485IntHandler(void *param)
 {
 	UartPort_t *uap = param;
 	uint32_t iir;
+	uint32_t status;
 		
 	iir = readl(uap->regbase + UART485_IIR);
 	switch (iir & UART485_IIR_IID_MASK) {
@@ -420,6 +421,11 @@ static void vUart485IntHandler(void *param)
 	case UART485_IIR_IID_REV_LINE_STATUS:
 	case UART485_IIR_IID_CHAR_TIMEOUT:
 		iUart485RxChars(uap);
+		break;
+	case UART485_IIR_IID_BUSY_DETECT:
+		status = readl(uap->regbase + UART485_USR);
+		printf("busy status 0x%x.\n", status);
+		break;
 	}
 }
 
@@ -566,6 +572,16 @@ void vUartInit(UartPort_t *uap, uint32_t baud, uint32_t flags)
 		//set modem
 		writel(0, uap->regbase + UART485_MCR);
 
+		//wait not busy
+		while (readl(uap->regbase + UART485_USR) & 1) {
+			if (count++ < 100) {
+				udelay(100);
+			} else {
+				printf("Error! Uart%d wait busy fail.\n", uap->id);
+				return;
+			}
+		}
+
 		// baud = clk/(16*U_DLL)
 		//set baud rate
 		writel(readl(uap->regbase + UART485_LCR) | (1 << 7), uap->regbase + UART485_LCR);

+ 3 - 1
amt630h-freertos/app/main_lvgl.c

@@ -207,7 +207,7 @@ struct FMT_BLOCK_DEF
 
 struct DATA_BLOCK_DEF
 {
-    char data_id[4];     // 'R','I','F','F'
+    char data_id[4];     // 'd','a','t','a'
     uint32_t data_size;
 };
 
@@ -305,6 +305,8 @@ static void wavplay_thread(void *param)
 
         if (length <= 0)
             break;
+		else if (length > data_size)
+			length = data_size;
 
         /* 向 Audio 设备写入音频数据 */
         audio_dev_write(audio, buffer, length);

+ 1 - 1
amt630h-freertos/lib/awtk/awtk/src/base/image_manager.c

@@ -179,7 +179,7 @@ ret_t image_manager_update_specific(image_manager_t* imm, bitmap_t* image) {
   bitmap_cache_t* iter = NULL;
   return_value_if_fail(image != NULL, RET_BAD_PARAMS);
 
-  if (imm == NULL) {
+  if (!imm && !(imm = image_manager())) {
     return RET_FAIL;
   }
 

+ 10 - 0
amt630h-freertos/lib/sfud/inc/sfud_flash_def.h

@@ -182,6 +182,16 @@ typedef struct {
     {SFUD_MF_ID_MICRONIX, 0x20, 0x16, NORMAL_SPI_READ|DUAL_OUTPUT},                                \
     /* GD25Q64B */                                                                                 \
     {SFUD_MF_ID_GIGADEVICE, 0x40, 0x17, NORMAL_SPI_READ|DUAL_OUTPUT},                              \
+    /* MX25L6433F */                                                               \
+    {SFUD_MF_ID_MICRONIX, 0x20, 0x17,  NORMAL_SPI_READ|DUAL_OUTPUT|DUAL_IO|QUAD_OUTPUT|QUAD_IO}, \
+    /* MX25L12845G */                                                               \
+    {SFUD_MF_ID_MICRONIX, 0x20, 0x18,  NORMAL_SPI_READ|DUAL_OUTPUT|DUAL_IO|QUAD_OUTPUT|QUAD_IO}, \
+    /* MX25L25645G */                                                               \
+    {SFUD_MF_ID_MICRONIX, 0x20, 0x19,  NORMAL_SPI_READ|DUAL_OUTPUT|DUAL_IO|QUAD_OUTPUT|QUAD_IO}, \
+    /* GD25B256ME */                                                               \
+    {SFUD_MF_ID_GIGADEVICE, 0x43, 0x19,  NORMAL_SPI_READ|DUAL_OUTPUT|DUAL_IO|QUAD_OUTPUT|QUAD_IO}, \
+    /* GD25B512ME */                                                               \
+    {SFUD_MF_ID_GIGADEVICE, 0x47, 0x1A,  NORMAL_SPI_READ|DUAL_OUTPUT|DUAL_IO|QUAD_OUTPUT|QUAD_IO}, \
 }
 #endif /* SFUD_USING_QSPI */
 

+ 1 - 2
amt630h-freertos/main.c

@@ -295,8 +295,7 @@ void vAssertCalled( const char * pcFile, unsigned long ulLine )
 {
 volatile unsigned long ul = 0;
 
-	( void ) pcFile;
-	( void ) ulLine;
+	printf("vAssertCalled %s %d.\n", pcFile, ulLine);
 
 	taskENTER_CRITICAL();
 	{