diff --git a/.cproject b/.cproject index e60a6b5..db00e3e 100644 --- a/.cproject +++ b/.cproject @@ -110,7 +110,7 @@ - + @@ -175,7 +175,7 @@ - + diff --git a/APP/inc/rtconfig.h b/APP/inc/rtconfig.h index f918f04..0a60d5a 100644 --- a/APP/inc/rtconfig.h +++ b/APP/inc/rtconfig.h @@ -59,7 +59,10 @@ /* SECTION: Device System */ /* Using Device System */ #define RT_USING_DEVICE -//#define RT_USING_UART1 +// +#define RT_USING_DEVICE_IPC +// +#define RT_USING_SERIAL /* SECTION: Console options */ /* the buffer size of console*/ diff --git a/BSP/inc/bsp.h b/BSP/inc/bsp.h index df7947e..74d1f07 100644 --- a/BSP/inc/bsp.h +++ b/BSP/inc/bsp.h @@ -46,6 +46,10 @@ #define STM32_SRAM_SIZE 20 #define STM32_SRAM_END (0x20000000 + STM32_SRAM_SIZE * 1024) +/* RT_USING_UART */ +#define RT_USING_UART3 +#define RT_USING_UART1 +#define RT_UART_RX_BUFFER_SIZE 64 #define LED_LED1_ON GPIO_SetBits (GPIOA,GPIO_Pin_11) //LED1 #define LED_LED1_OFF GPIO_ResetBits(GPIOA,GPIO_Pin_11) //LED1 @@ -94,13 +98,7 @@ void IWDG_Feed(void); void BSP_Init(void); void rt_hw_board_init(void); -static void RCC_Configuration(void); -static void NVIC_Configuration(void); -static void GPIO_Configuration(void); -static void USART1_Configuration(void); -static void IWDG_Configuration(void); void IWDG_Feed(void); -static void SysTick_Configuration(void); void rt_hw_timer_handler(void); uint8_t AvoidTimeout(uint32_t TimeOfTimeout,uint32_t Period,uint8_t (*DetectCondition)(),uint8_t ConditionValue); diff --git a/BSP/inc/usart.h b/BSP/inc/usart.h new file mode 100644 index 0000000..438578d --- /dev/null +++ b/BSP/inc/usart.h @@ -0,0 +1,26 @@ +/* + * File : usart.h + * This file is part of RT-Thread RTOS + * COPYRIGHT (C) 2009, RT-Thread Development Team + * + * The license and distribution terms for this file may be + * found in the file LICENSE in this distribution or at + * http://www.rt-thread.org/license/LICENSE + * + * Change Logs: + * Date Author Notes + * 2009-01-05 Bernard the first version + */ + +#ifndef __USART_H__ +#define __USART_H__ + +#include +#include + +#define UART_ENABLE_IRQ(n) NVIC_EnableIRQ((n)) +#define UART_DISABLE_IRQ(n) NVIC_DisableIRQ((n)) + +void rt_hw_usart_init(void); + +#endif diff --git a/BSP/src/bsp.c b/BSP/src/bsp.c index 9140df3..613a6e3 100644 --- a/BSP/src/bsp.c +++ b/BSP/src/bsp.c @@ -23,6 +23,7 @@ #include #include #include +#include "usart.h" /* ********************************************************************************************************* * LOCAL TABLES @@ -46,6 +47,7 @@ void rt_hw_board_init() { BSP_Init(); + rt_hw_usart_init(); } /******************************************************************************* diff --git a/BSP/src/usart.c b/BSP/src/usart.c new file mode 100644 index 0000000..909c185 --- /dev/null +++ b/BSP/src/usart.c @@ -0,0 +1,491 @@ +/* + * File : usart.c + * This file is part of RT-Thread RTOS + * COPYRIGHT (C) 2006-2013, RT-Thread Development Team + * + * The license and distribution terms for this file may be + * found in the file LICENSE in this distribution or at + * http://www.rt-thread.org/license/LICENSE + * + * Change Logs: + * Date Author Notes + * 2009-01-05 Bernard the first version + * 2010-03-29 Bernard remove interrupt Tx and DMA Rx mode + * 2013-05-13 aozima update for kehong-lingtai. + */ + +#include "stm32f10x.h" +#include "usart.h" + +#include "bsp.h" +#include + +/* USART1 */ +#define UART1_GPIO_TX GPIO_Pin_9 +#define UART1_GPIO_RX GPIO_Pin_10 +#define UART1_GPIO GPIOA +/* USART1_REMAP */ +#define UART1_GPIO_REMAP_TX GPIO_Pin_6 +#define UART1_GPIO_REMAP_RX GPIO_Pin_7 +#define UART1_GPIO_REMAP GPIOB + +/* USART2 */ +#define UART2_GPIO_TX GPIO_Pin_2 +#define UART2_GPIO_RX GPIO_Pin_3 +#define UART2_GPIO GPIOA + +/* USART3_REMAP[1:0] = 00 */ +#define UART3_GPIO_TX GPIO_Pin_10 +#define UART3_GPIO_RX GPIO_Pin_11 +#define UART3_GPIO GPIOB + +/* STM32 uart driver */ +struct stm32_uart +{ + USART_TypeDef* uart_device; + IRQn_Type irq; + /* transmit interrupt type */ + rt_uint32_t tx_irq_type; +}; + +static rt_err_t stm32_configure(struct rt_serial_device *serial, struct serial_configure *cfg) +{ + struct stm32_uart* uart; + USART_InitTypeDef USART_InitStructure; + + RT_ASSERT(serial != RT_NULL); + RT_ASSERT(cfg != RT_NULL); + + uart = (struct stm32_uart *)serial->parent.user_data; + + USART_InitStructure.USART_BaudRate = cfg->baud_rate; + + if (cfg->data_bits == DATA_BITS_8){ + USART_InitStructure.USART_WordLength = USART_WordLength_8b; + } else if (cfg->data_bits == DATA_BITS_9) { + USART_InitStructure.USART_WordLength = USART_WordLength_9b; + } + + if (cfg->stop_bits == STOP_BITS_1){ + USART_InitStructure.USART_StopBits = USART_StopBits_1; + } else if (cfg->stop_bits == STOP_BITS_2){ + USART_InitStructure.USART_StopBits = USART_StopBits_2; + } + + if (cfg->parity == PARITY_NONE){ + USART_InitStructure.USART_Parity = USART_Parity_No; + } else if (cfg->parity == PARITY_ODD) { + USART_InitStructure.USART_Parity = USART_Parity_Odd; + } else if (cfg->parity == PARITY_EVEN) { + USART_InitStructure.USART_Parity = USART_Parity_Even; + } + + USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None; + USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx; + USART_Init(uart->uart_device, &USART_InitStructure); + + /* Enable USART */ + USART_Cmd(uart->uart_device, ENABLE); + /* enable interrupt */ + USART_ITConfig(uart->uart_device, USART_IT_RXNE, ENABLE); + + return RT_EOK; +} + +static rt_err_t stm32_control(struct rt_serial_device *serial, int cmd, void *arg) +{ + struct stm32_uart* uart; + rt_uint32_t *irq_type = (rt_uint32_t *)(arg); + + RT_ASSERT(serial != RT_NULL); + uart = (struct stm32_uart *)serial->parent.user_data; + + switch (cmd) + { + /* disable interrupt */ + case RT_DEVICE_CTRL_CLR_INT: + + if ((*irq_type) == RT_DEVICE_FLAG_INT_RX) + { + /* disable rx irq */ + USART_ITConfig(uart->uart_device, USART_IT_RXNE, DISABLE); + } + else if ((*irq_type) == RT_DEVICE_FLAG_INT_TX) + { + /* disable tx irq */ + USART_ITConfig(uart->uart_device, uart->tx_irq_type, DISABLE); + } + else if (irq_type == RT_NULL) + { + /* disable irq */ + UART_DISABLE_IRQ(uart->irq); + } + break; + /* enable interrupt */ + case RT_DEVICE_CTRL_SET_INT: + if ((*irq_type) == RT_DEVICE_FLAG_INT_RX) + { + /* enable rx irq */ + USART_ITConfig(uart->uart_device, USART_IT_RXNE, ENABLE); + } + else if ((*irq_type) == RT_DEVICE_FLAG_INT_TX) + { + /* enable tx irq */ + USART_ITConfig(uart->uart_device, uart->tx_irq_type, ENABLE); + } + else if (irq_type == RT_NULL) + { + /* enable irq */ + UART_ENABLE_IRQ(uart->irq); + } + break; + /* get interrupt flag */ + case RT_DEVICE_CTRL_GET_INT: + if ((*irq_type) == RT_DEVICE_FLAG_INT_RX) + { + /* return rx irq flag */ + (*irq_type) = USART_GetITStatus(uart->uart_device, USART_IT_RXNE); + } + else if ((*irq_type) == RT_DEVICE_FLAG_INT_TX) + { + /* return tx irq flag */ + (*irq_type) = USART_GetITStatus(uart->uart_device, uart->tx_irq_type); + } + break; + /* get USART flag */ + case RT_DEVICE_CTRL_GET_FLAG: + if ((*irq_type) == RT_DEVICE_FLAG_INT_RX) + { + /* return rx irq flag */ + (*irq_type) = USART_GetFlagStatus(uart->uart_device, + USART_FLAG_RXNE); + } + else if ((*irq_type) == RT_DEVICE_FLAG_INT_TX) + { + /* return tx flag */ + if (uart->tx_irq_type == USART_IT_TC) + { + (*irq_type) = USART_GetFlagStatus(uart->uart_device, + USART_FLAG_TC); + } + else if (uart->tx_irq_type == USART_IT_TXE) + { + (*irq_type) = USART_GetFlagStatus(uart->uart_device, + USART_FLAG_TXE); + } + } + break; + } + return RT_EOK; +} + +static int stm32_putc(struct rt_serial_device *serial, char c) +{ + struct stm32_uart* uart; + + RT_ASSERT(serial != RT_NULL); + uart = (struct stm32_uart *)serial->parent.user_data; + + while (!(uart->uart_device->SR & USART_FLAG_TXE)); + uart->uart_device->DR = c; + + return 1; +} + +static int stm32_getc(struct rt_serial_device *serial) +{ + int ch; + struct stm32_uart* uart; + + RT_ASSERT(serial != RT_NULL); + uart = (struct stm32_uart *)serial->parent.user_data; + + ch = -1; + if (uart->uart_device->SR & USART_FLAG_RXNE) + { + ch = uart->uart_device->DR & 0xff; + } + + return ch; +} + +static const struct rt_uart_ops stm32_uart_ops = +{ + stm32_configure, + stm32_control, + stm32_putc, + stm32_getc, +}; + +#if defined(RT_USING_UART1) || defined(RT_USING_REMAP_UART1) +/* UART1 device driver structure */ +struct stm32_uart uart1 = +{ + USART1, + USART1_IRQn, + USART_IT_TC, +}; +struct rt_serial_device serial1; + +void USART1_IRQHandler(void) +{ + struct stm32_uart* uart; + + uart = &uart1; + + /* enter interrupt */ + rt_interrupt_enter(); + if(USART_GetITStatus(uart->uart_device, USART_IT_RXNE) != RESET) + { + rt_hw_serial_isr(&serial1, RT_SERIAL_EVENT_RX_IND); + /* clear interrupt */ + USART_ClearITPendingBit(uart->uart_device, USART_IT_RXNE); + } + + if (USART_GetITStatus(uart->uart_device, uart->tx_irq_type) != RESET) + { + /* clear interrupt */ + rt_hw_serial_isr(&serial1, RT_SERIAL_EVENT_TX_DONE); + if (uart->tx_irq_type == USART_IT_TC) + { + USART_ClearITPendingBit(uart->uart_device, uart->tx_irq_type); + } + } + if (USART_GetFlagStatus(uart->uart_device, USART_FLAG_ORE) == SET) + { + stm32_getc(&serial1); + } + /* leave interrupt */ + rt_interrupt_leave(); +} +#endif /* RT_USING_UART1 */ + +#if defined(RT_USING_UART2) +/* UART1 device driver structure */ +struct stm32_uart uart2 = +{ + USART2, + USART2_IRQn, + USART_IT_TC, +}; +struct rt_serial_device serial2; + +void USART2_IRQHandler(void) +{ + struct stm32_uart* uart; + + uart = &uart2; + + /* enter interrupt */ + rt_interrupt_enter(); + if(USART_GetITStatus(uart->uart_device, USART_IT_RXNE) != RESET) + { + rt_hw_serial_isr(&serial2, RT_SERIAL_EVENT_RX_IND); + /* clear interrupt */ + USART_ClearITPendingBit(uart->uart_device, USART_IT_RXNE); + } + if (USART_GetITStatus(uart->uart_device, uart->tx_irq_type) != RESET) + { + /* clear interrupt */ + if (uart->tx_irq_type == USART_IT_TC) + { + USART_ClearITPendingBit(uart->uart_device, uart->tx_irq_type); + } + } + if (USART_GetFlagStatus(uart->uart_device, USART_FLAG_ORE) == SET) + { + stm32_getc(&serial2); + } + + /* leave interrupt */ + rt_interrupt_leave(); +} +#endif /* RT_USING_UART2 */ + +#if defined(RT_USING_UART3) +/* UART3 device driver structure */ +struct stm32_uart uart3 = +{ + USART3, + USART3_IRQn, + USART_IT_TC, +}; +struct rt_serial_device serial3; + +void USART3_IRQHandler(void) +{ + struct stm32_uart* uart; + + uart = &uart3; + + /* enter interrupt */ + rt_interrupt_enter(); + if(USART_GetITStatus(uart->uart_device, USART_IT_RXNE) != RESET) + { + rt_hw_serial_isr(&serial3, RT_SERIAL_EVENT_RX_IND); + /* clear interrupt */ + USART_ClearITPendingBit(uart->uart_device, USART_IT_RXNE); + } + if (USART_GetITStatus(uart->uart_device, uart->tx_irq_type) != RESET) + { + /* clear interrupt */ + if (uart->tx_irq_type == USART_IT_TC) + { + USART_ClearITPendingBit(uart->uart_device, uart->tx_irq_type); + } + } + if (USART_GetFlagStatus(uart->uart_device, USART_FLAG_ORE) == SET) + { + stm32_getc(&serial3); + } + + /* leave interrupt */ + rt_interrupt_leave(); +} +#endif /* RT_USING_UART3 */ + +static void RCC_Configuration(void) +{ +#if defined(RT_USING_UART1) + /* Enable UART GPIO clocks */ + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); + /* Enable UART clock */ + RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE); +#elif defined(RT_USING_REMAP_UART1) + /* Enable UART GPIO clocks */ + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); + /* Enable UART clock */ + RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE); +#endif + +#ifdef RT_USING_UART2 + /* Enable UART GPIO clocks */ + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE); + /* Enable UART clock */ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE); +#endif /* RT_USING_UART2 */ + +#ifdef RT_USING_UART3 + /* Enable UART GPIO clocks */ + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); + /* Enable UART clock */ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE); +#endif /* RT_USING_UART3 */ +} + +static void GPIO_Configuration(void) +{ + GPIO_InitTypeDef GPIO_InitStructure; + + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; + +#if defined(RT_USING_UART1) + /* Configure USART Rx/tx PIN */ + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; + GPIO_InitStructure.GPIO_Pin = UART1_GPIO_RX; + GPIO_Init(UART1_GPIO, &GPIO_InitStructure); + + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; + GPIO_InitStructure.GPIO_Pin = UART1_GPIO_TX; + GPIO_Init(UART1_GPIO, &GPIO_InitStructure); +#elif defined(RT_USING_REMAP_UART1) + /* Configure USART Remap Rx/tx PIN */ + GPIO_PinRemapConfig(GPIO_Remap_USART1,ENABLE); + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; + GPIO_InitStructure.GPIO_Pin = UART1_GPIO_REMAP_RX; + GPIO_Init(UART1_GPIO_REMAP, &GPIO_InitStructure); + + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; + GPIO_InitStructure.GPIO_Pin = UART1_GPIO_REMAP_TX; + GPIO_Init(UART1_GPIO_REMAP, &GPIO_InitStructure); +#endif /* RT_USING_UART1 */ + +#ifdef RT_USING_UART2 + /* Configure USART Rx/tx PIN */ + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; + GPIO_InitStructure.GPIO_Pin = UART2_GPIO_RX; + GPIO_Init(UART2_GPIO, &GPIO_InitStructure); + + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; + GPIO_InitStructure.GPIO_Pin = UART2_GPIO_TX; + GPIO_Init(UART2_GPIO, &GPIO_InitStructure); +#endif /* RT_USING_UART2 */ + +#ifdef RT_USING_UART3 + /* Configure USART Rx/tx PIN */ + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; + GPIO_InitStructure.GPIO_Pin = UART3_GPIO_RX; + GPIO_Init(UART3_GPIO, &GPIO_InitStructure); + + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; + GPIO_InitStructure.GPIO_Pin = UART3_GPIO_TX; + GPIO_Init(UART3_GPIO, &GPIO_InitStructure); +#endif /* RT_USING_UART3 */ +} + +static void NVIC_Configuration(struct stm32_uart* uart) +{ + NVIC_InitTypeDef NVIC_InitStructure; + + /* Enable the USART1 Interrupt */ + NVIC_InitStructure.NVIC_IRQChannel = uart->irq; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0; + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); +} + +void rt_hw_usart_init(void) +{ + struct stm32_uart* uart; + struct serial_configure config = RT_SERIAL_CONFIG_DEFAULT; + + RCC_Configuration(); + GPIO_Configuration(); + +#if defined(RT_USING_UART1) || defined(RT_USING_REMAP_UART1) + uart = &uart1; + config.baud_rate = BAUD_RATE_9600; + + serial1.ops = &stm32_uart_ops; + serial1.config = config; + + NVIC_Configuration(&uart1); + + /* register UART1 device */ + rt_hw_serial_register(&serial1, "uart1", + RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX , + uart); +#endif /* RT_USING_UART1 */ + +#ifdef RT_USING_UART2 + uart = &uart2; + + config.baud_rate = BAUD_RATE_115200; + serial2.ops = &stm32_uart_ops; + serial2.config = config; + + NVIC_Configuration(&uart2); + + /* register UART1 device */ + rt_hw_serial_register(&serial2, "uart2", + RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX, + uart); +#endif /* RT_USING_UART2 */ + +#ifdef RT_USING_UART3 + uart = &uart3; + + config.baud_rate = BAUD_RATE_115200; + + serial3.ops = &stm32_uart_ops; + serial3.config = config; + + NVIC_Configuration(&uart3); + + /* register UART1 device */ + rt_hw_serial_register(&serial3, "uart3", + RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX, + uart); +#endif /* RT_USING_UART3 */ +} diff --git a/EWARM/FreeModbus_Slave&Master+RTT+STM32.dep b/EWARM/FreeModbus_Slave&Master+RTT+STM32.dep index 044c38a..b2f5125 100644 --- a/EWARM/FreeModbus_Slave&Master+RTT+STM32.dep +++ b/EWARM/FreeModbus_Slave&Master+RTT+STM32.dep @@ -2,862 +2,441 @@ 2 - 664838259 + 2735907941 Debug - $PROJ_DIR$\..\RT-Thread-1.1.1\src\mempool.c - $PROJ_DIR$\..\RT-Thread-1.1.1\src\module.h - $PROJ_DIR$\..\RT-Thread-1.1.1\src\timer.c - $PROJ_DIR$\..\Libaries\CMSIS_EWARM\CM3\DeviceSupport\ST\STM32F10x\startup\iar\startup_stm32f10x_md.s - $PROJ_DIR$\..\RT-Thread-1.1.1\src\module.c - $PROJ_DIR$\..\RT-Thread-1.1.1\src\scheduler.c - $PROJ_DIR$\..\RT-Thread-1.1.1\src\object.c - $PROJ_DIR$\..\RT-Thread-1.1.1\src\slab.c - $PROJ_DIR$\..\RT-Thread-1.1.1\src\memheap.c - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_can.c - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_iwdg.c - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_crc.c - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_dma.c - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_pwr.c - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_rcc.c - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_rtc.c - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_sdio.c - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_spi.c - $PROJ_DIR$\Debug\Obj\stm32f10x_cec.o - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_dbgmcu.c - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_tim.c - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_wwdg.c - $PROJ_DIR$\Debug\Obj\slab.pbi - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_i2c.c - $PROJ_DIR$\Debug\Obj\module.pbi - $PROJ_DIR$\Debug\Obj\object.pbi - $PROJ_DIR$\Debug\Obj\module.o - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_bkp.c - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_exti.c - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_flash.c - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_dac.c - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_fsmc.c - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_gpio.c - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_usart.c - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_cec.c - $PROJ_DIR$\Debug\Obj\mbrtu.pbi - $PROJ_DIR$\Debug\Obj\scheduler.o - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_adc.c - $PROJ_DIR$\Debug\Obj\kservice.pbi - $PROJ_DIR$\Debug\Obj\mem.pbi - $PROJ_DIR$\Debug\Obj\scheduler.pbi - $PROJ_DIR$\Debug\Obj\app.pbi - $PROJ_DIR$\Debug\Obj\thread.pbi - $PROJ_DIR$\Debug\Obj\mempool.pbi - $PROJ_DIR$\Debug\Obj\device.pbi - $PROJ_DIR$\Debug\Obj\stm32f10x_crc.o - $PROJ_DIR$\Debug\Obj\idle.pbi - $PROJ_DIR$\Debug\Obj\timer.o - $PROJ_DIR$\Debug\Obj\thread.o - $PROJ_DIR$\Debug\Obj\clock.pbi - $PROJ_DIR$\Debug\Obj\kservice.o - $PROJ_DIR$\Debug\Obj\device.o - $PROJ_DIR$\Debug\Obj\clock.o - $PROJ_DIR$\Debug\Obj\ipc.pbi - $PROJ_DIR$\Debug\Obj\idle.o - $PROJ_DIR$\Debug\Obj\stm32f10x_adc.o - $PROJ_DIR$\Debug\Obj\app.o - $PROJ_DIR$\Debug\Obj\slab.o - $PROJ_DIR$\Debug\Obj\context_iar.o - $PROJ_DIR$\Debug\Obj\timer.pbi - $PROJ_DIR$\Debug\Obj\irq.pbi - $PROJ_DIR$\Debug\Obj\mem.o - $PROJ_DIR$\Debug\Obj\bsp.pbi - $PROJ_DIR$\Debug\Obj\system_stm32f10x.o - $PROJ_DIR$\Debug\Obj\stm32f10x_it.o - $PROJ_DIR$\Debug\Obj\app_task.o - $PROJ_DIR$\Debug\Obj\misc.o - $PROJ_DIR$\Debug\Obj\object.o + $PROJ_DIR$\..\RT-Thread-1.2.2\src\irq.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\kservice.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\mem.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\mempool.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\module.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\ipc.c $TOOLKIT_DIR$\inc\c\stdio.h - $PROJ_DIR$\..\BSP\inc\bsp.h - $PROJ_DIR$\..\RT-Thread-1.1.1\include\rtservice.h - $PROJ_DIR$\..\APP\inc\stm32f10x_it.h $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_i2c.h - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_wwdg.h + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_rtc.h + $PROJ_DIR$\..\RT-Thread-1.1.1\include\rtservice.h + $PROJ_DIR$\Debug\Obj\slab.o + $PROJ_DIR$\Debug\Obj\mem.o + $PROJ_DIR$\Debug\Obj\stm32f10x_it.o + $PROJ_DIR$\Debug\Obj\ipc.pbi + $PROJ_DIR$\Debug\Obj\stm32f10x_adc.o + $PROJ_DIR$\Debug\Obj\bsp.pbi + $PROJ_DIR$\Debug\Obj\misc.o + $PROJ_DIR$\..\BSP\inc\bsp.h $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_spi.h + $PROJ_DIR$\..\APP\inc\stm32f10x_it.h + $PROJ_DIR$\Debug\Obj\timer.pbi + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_bkp.h + $PROJ_DIR$\Debug\Obj\system_stm32f10x.o + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_wwdg.h + $PROJ_DIR$\Debug\Obj\app_task.o $PROJ_DIR$\..\APP\inc\cpuusage.h $TOOLKIT_DIR$\inc\c\stdlib.h - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_bkp.h + $PROJ_DIR$\Debug\Obj\irq.pbi $TOOLKIT_DIR$\inc\c\ysizet.h + $PROJ_DIR$\Debug\Obj\object.o + $PROJ_DIR$\Debug\Obj\idle.o $TOOLKIT_DIR$\inc\c\stdint.h + $PROJ_DIR$\Debug\Obj\app.o $TOOLKIT_DIR$\inc\c\ystdio.h - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_rtc.h - $TOOLKIT_DIR$\lib\dl7M_tln.a - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_sdio.h - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_pwr.h - $TOOLKIT_DIR$\lib\m7M_tl.a - $TOOLKIT_DIR$\config\linker\ST\stm32f103xB.icf - $PROJ_DIR$\Debug\Obj\portserial.pbi - $PROJ_DIR$\Debug\Obj\portevent_m.o - $PROJ_DIR$\..\RT-Thread-1.1.1\include\rtthread.h - $TOOLKIT_DIR$\inc\c\assert.h - $PROJ_DIR$\Debug\Obj\portevent.pbi - $TOOLKIT_DIR$\inc\c\stdarg.h - $TOOLKIT_DIR$\inc\c\inttypes.h - $PROJ_DIR$\..\APP\inc\delay_conf.h - $PROJ_DIR$\..\FreeModbus\modbus\include\mbproto.h - $PROJ_DIR$\..\APP\inc\app_task.h - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncdiag.c - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncdisc_m.c - $PROJ_DIR$\..\FreeModbus\modbus\rtu\mbrtu_m.c - $PROJ_DIR$\..\FreeModbus\port\portevent_m.c - $PROJ_DIR$\..\FreeModbus\port\portserial_m.c - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfunccoils.c - $PROJ_DIR$\..\FreeModbus\modbus\rtu\mbrtu.c - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbutils.c - $PROJ_DIR$\..\FreeModbus\port\porttimer.c - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncinput.c - $PROJ_DIR$\..\RT-Thread-1.1.1\src\idle.c + $PROJ_DIR$\Debug\Obj\context_iar.o $PROJ_DIR$\..\FreeModbus\modbus\mb.c - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncinput_m.c - $PROJ_DIR$\..\RT-Thread-1.1.1\src\kservice.c - $PROJ_DIR$\..\RT-Thread-1.1.1\src\mem.c - $PROJ_DIR$\..\FreeModbus\port\portserial.c - $PROJ_DIR$\..\RT-Thread-1.1.1\src\thread.c - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncdisc.c - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncholding_m.c - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncholding.c - $PROJ_DIR$\..\FreeModbus\port\user_mb_app_m.c - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncother.c $PROJ_DIR$\..\FreeModbus\port\port.c - $PROJ_DIR$\..\FreeModbus\port\user_mb_app.c - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfunccoils_m.c - $PROJ_DIR$\..\RT-Thread-1.1.1\src\clock.c - $PROJ_DIR$\..\RT-Thread-1.1.1\src\device.c - $PROJ_DIR$\..\FreeModbus\modbus\rtu\mbcrc.c - $PROJ_DIR$\..\FreeModbus\port\portevent.c - $PROJ_DIR$\..\RT-Thread-1.1.1\src\irq.c - $PROJ_DIR$\..\RT-Thread-1.1.1\src\ipc.c + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfunccoils.c + $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\wrokqueue.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\clock.c + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbutils.c $PROJ_DIR$\..\FreeModbus\port\porttimer_m.c - $PROJ_DIR$\..\BSP\src\bsp.c - $PROJ_DIR$\..\APP\inc\stm32f10x_conf.h - $PROJ_DIR$\..\RT-Thread-1.1.1\libcpu\arm\cortex-m3\context_iar.S - $PROJ_DIR$\..\RT-Thread-1.1.1\libcpu\arm\cortex-m3\cpuport.c - $PROJ_DIR$\..\RT-Thread-1.1.1\libcpu\arm\common\backtrace.c - $PROJ_DIR$\..\RT-Thread-1.1.1\libcpu\arm\common\showmem.c - $PROJ_DIR$\..\Libaries\CMSIS_EWARM\CM3\DeviceSupport\ST\STM32F10x\system_stm32f10x.c - $PROJ_DIR$\..\FreeModbus\modbus\mb_m.c + $PROJ_DIR$\..\FreeModbus\port\user_mb_app_m.c + $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\completion.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\cpuusage.c + $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\portal.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\device.c + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncdiag.c + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncdisc.c + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncholding.c + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncother.c + $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\ringbuffer.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\idle.c + $PROJ_DIR$\..\FreeModbus\port\portevent.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\memheap.c + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncinput_m.c + $PROJ_DIR$\..\FreeModbus\port\portserial_m.c + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncinput.c + $PROJ_DIR$\..\FreeModbus\modbus\rtu\mbrtu_m.c + $PROJ_DIR$\..\FreeModbus\port\portserial.c + $PROJ_DIR$\..\FreeModbus\modbus\rtu\mbrtu.c + $PROJ_DIR$\..\FreeModbus\modbus\rtu\mbcrc.c + $PROJ_DIR$\..\FreeModbus\port\porttimer.c + $PROJ_DIR$\..\FreeModbus\port\user_mb_app.c + $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\pipe.c + $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\dataqueue.c + $PROJ_DIR$\..\FreeModbus\port\portevent_m.c $PROJ_DIR$\..\APP\src\app.c $PROJ_DIR$\..\APP\src\app_task.c - $PROJ_DIR$\..\APP\src\cpuusage.c - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\misc.c + $PROJ_DIR$\..\BSP\src\bsp.c + $PROJ_DIR$\..\Libaries\CMSIS_EWARM\CM3\DeviceSupport\ST\STM32F10x\system_stm32f10x.c + $PROJ_DIR$\..\APP\inc\stm32f10x_conf.h + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncdisc_m.c + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncholding_m.c + $PROJ_DIR$\..\RT-Thread-1.2.2\libcpu\arm\cortex-m3\context_iar.S + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfunccoils_m.c $PROJ_DIR$\..\APP\src\stm32f10x_it.c + $PROJ_DIR$\..\RT-Thread-1.2.2\libcpu\arm\cortex-m3\cpuport.c + $PROJ_DIR$\..\FreeModbus\modbus\mb_m.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\object.c + $PROJ_DIR$\..\Libaries\CMSIS_EWARM\CM3\DeviceSupport\ST\STM32F10x\startup\iar\startup_stm32f10x_md.s + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_crc.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\slab.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_wwdg.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_flash.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_bkp.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\scheduler.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_rcc.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\thread.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_dac.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_i2c.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_iwdg.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_rtc.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_tim.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_fsmc.c + $PROJ_DIR$\..\RT-Thread-1.1.1\src\mempool.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_dbgmcu.c + $PROJ_DIR$\..\RT-Thread-1.1.1\src\timer.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_sdio.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\timer.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_adc.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_can.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_pwr.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_spi.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_exti.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_gpio.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_cec.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\misc.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_dma.c + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_usart.c + $PROJ_DIR$\Debug\Obj\object.pbi + $PROJ_DIR$\..\RT-Thread-1.1.1\src\module.c + $PROJ_DIR$\..\RT-Thread-1.1.1\src\memheap.c + $PROJ_DIR$\Debug\Obj\module.pbi + $PROJ_DIR$\Debug\Obj\mbrtu.pbi + $PROJ_DIR$\Debug\Obj\kservice.pbi + $PROJ_DIR$\Debug\Obj\idle.pbi + $PROJ_DIR$\Debug\Obj\timer.o + $PROJ_DIR$\Debug\Obj\kservice.o + $PROJ_DIR$\Debug\Obj\device.o + $PROJ_DIR$\Debug\Obj\stm32f10x_cec.o + $PROJ_DIR$\..\RT-Thread-1.1.1\src\object.c + $PROJ_DIR$\Debug\Obj\module.o + $PROJ_DIR$\Debug\Obj\app.pbi + $PROJ_DIR$\Debug\Obj\device.pbi + $PROJ_DIR$\Debug\Obj\thread.o + $PROJ_DIR$\Debug\Obj\clock.pbi + $PROJ_DIR$\Debug\Obj\clock.o + $PROJ_DIR$\Debug\Obj\scheduler.pbi + $PROJ_DIR$\Debug\Obj\scheduler.o + $PROJ_DIR$\Debug\Obj\slab.pbi + $PROJ_DIR$\Debug\Obj\mem.pbi + $PROJ_DIR$\Debug\Obj\thread.pbi + $PROJ_DIR$\Debug\Obj\mempool.pbi + $PROJ_DIR$\..\RT-Thread-1.1.1\src\slab.c + $PROJ_DIR$\Debug\Obj\stm32f10x_crc.o + $PROJ_DIR$\..\RT-Thread-1.1.1\src\scheduler.c + $TOOLKIT_DIR$\lib\m7M_tl.a + $TOOLKIT_DIR$\inc\c\inttypes.h + $TOOLKIT_DIR$\inc\c\assert.h + $PROJ_DIR$\..\RT-Thread-1.1.1\src\irq.c + $PROJ_DIR$\..\RT-Thread-1.1.1\src\mem.c + $PROJ_DIR$\..\RT-Thread-1.1.1\libcpu\arm\cortex-m3\cpuport.c + $PROJ_DIR$\..\RT-Thread-1.1.1\libcpu\arm\common\backtrace.c + $TOOLKIT_DIR$\config\linker\ST\stm32f103xB.icf + $PROJ_DIR$\..\RT-Thread-1.1.1\libcpu\arm\common\showmem.c + $PROJ_DIR$\..\APP\src\cpuusage.c $PROJ_DIR$\Debug\Obj\stm32f10x_usart.o - $PROJ_DIR$\Debug\Obj\mb_m.o + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_pwr.h + $PROJ_DIR$\Debug\Obj\portserial.pbi + $PROJ_DIR$\Debug\Obj\portevent_m.o + $PROJ_DIR$\Debug\Obj\portevent.pbi + $PROJ_DIR$\..\RT-Thread-1.1.1\src\kservice.c + $PROJ_DIR$\..\FreeModbus\modbus\include\mbproto.h + $PROJ_DIR$\..\RT-Thread-1.1.1\src\clock.c + $PROJ_DIR$\..\RT-Thread-1.1.1\src\ipc.c + $TOOLKIT_DIR$\inc\c\stdarg.h + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_sdio.h + $PROJ_DIR$\..\APP\inc\delay_conf.h + $PROJ_DIR$\..\APP\inc\app_task.h + $PROJ_DIR$\..\RT-Thread-1.1.1\src\device.c + $PROJ_DIR$\..\RT-Thread-1.1.1\libcpu\arm\cortex-m3\context_iar.S + $TOOLKIT_DIR$\lib\dl7M_tln.a + $PROJ_DIR$\..\RT-Thread-1.1.1\src\idle.c + $PROJ_DIR$\..\RT-Thread-1.1.1\include\rtthread.h + $PROJ_DIR$\..\RT-Thread-1.1.1\src\thread.c + $PROJ_DIR$\Debug\Obj\showmem.o + $PROJ_DIR$\..\Libaries\CMSIS_EWARM\Include\core_cmFunc.h + $PROJ_DIR$\Debug\Obj\stm32f10x_it.pbi + $PROJ_DIR$\Debug\Obj\stm32f10x_i2c.o + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_tim.h + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_usart.h + $PROJ_DIR$\Debug\Obj\showmem.pbi + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_exti.h + $PROJ_DIR$\Debug\Obj\stm32f10x_dac.pbi + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_flash.h + $PROJ_DIR$\Debug\Obj\stm32f10x_sdio.pbi + $PROJ_DIR$\Debug\Obj\mbfuncother.pbi + $PROJ_DIR$\Debug\Obj\mb.pbi + $PROJ_DIR$\..\Libaries\CMSIS_EWARM\CM3\DeviceSupport\ST\STM32F10x\system_stm32f10x.h + $PROJ_DIR$\Debug\Obj\app_task.pbi + $PROJ_DIR$\Debug\Obj\stm32f10x_dbgmcu.pbi + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h + $PROJ_DIR$\Debug\Obj\irq.o + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_iwdg.h + $PROJ_DIR$\Debug\Obj\mbcrc.pbi + $PROJ_DIR$\Debug\Obj\mbfuncdisc.pbi + $PROJ_DIR$\Debug\Obj\ipc.o + $TOOLKIT_DIR$\inc\c\intrinsics.h + $TOOLKIT_DIR$\inc\c\cmsis_iar.h + $PROJ_DIR$\Debug\Obj\system_stm32f10x.pbi + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_dma.h + $TOOLKIT_DIR$\inc\c\DLib_Product.h + $PROJ_DIR$\..\Libaries\CMSIS_EWARM\Include\core_cm3.h + $PROJ_DIR$\Debug\Obj\mbfuncholding.o + $PROJ_DIR$\Debug\Obj\bsp.o + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_rcc.h + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_gpio.h $PROJ_DIR$\..\Libaries\CMSIS_EWARM\CM3\DeviceSupport\ST\STM32F10x\stm32f10x.h - $PROJ_DIR$\..\RT-Thread-1.1.1\include\rtdef.h - $PROJ_DIR$\..\APP\inc\rtconfig.h - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_adc.h - $PROJ_DIR$\Debug\Obj\stm32f10x_iwdg.o - $PROJ_DIR$\..\FreeModbus\modbus\include\mbconfig.h - $PROJ_DIR$\..\RT-Thread-1.1.1\include\rthw.h - $PROJ_DIR$\..\RT-Thread-1.1.1\include\rtdebug.h - $PROJ_DIR$\..\RT-Thread-1.1.1\include\rtm.h - $PROJ_DIR$\Debug\Obj\mb.o - $PROJ_DIR$\Debug\Obj\misc.pbi $PROJ_DIR$\Debug\Obj\stm32f10x_crc.pbi - $PROJ_DIR$\..\FreeModbus\modbus\include\mbport.h - $PROJ_DIR$\..\FreeModbus\modbus\include\mb.h - $PROJ_DIR$\Debug\Obj\stm32f10x_cec.pbi - $PROJ_DIR$\Debug\Obj\stm32f10x_bkp.pbi $PROJ_DIR$\Debug\Obj\cpuport.pbi + $PROJ_DIR$\..\RT-Thread-1.1.1\include\rthw.h + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_adc.h + $PROJ_DIR$\Debug\Obj\stm32f10x_cec.pbi $PROJ_DIR$\Debug\Obj\mbrtu.o $PROJ_DIR$\Debug\Obj\mbcrc.o $PROJ_DIR$\Debug\Exe\FreeModbus_Slaver&Master+RTT+STM32.out $PROJ_DIR$\Debug\Obj\stm32f10x_can.pbi $PROJ_DIR$\Debug\Obj\portserial_m.pbi $PROJ_DIR$\..\FreeModbus\port\port.h - $PROJ_DIR$\Debug\Obj\FreeModbus_Slave&Master+RTT+STM32.pbd $PROJ_DIR$\Debug\Obj\stm32f10x_spi.o + $PROJ_DIR$\Debug\Obj\stm32f10x_iwdg.o + $PROJ_DIR$\Debug\Obj\FreeModbus_Slave&Master+RTT+STM32.pbd $PROJ_DIR$\Debug\Obj\memheap.o - $PROJ_DIR$\Debug\Obj\showmem.o - $PROJ_DIR$\Debug\Obj\showmem.pbi - $PROJ_DIR$\..\Libaries\CMSIS_EWARM\Include\core_cm3.h - $PROJ_DIR$\Debug\Obj\mbcrc.pbi - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_exti.h - $PROJ_DIR$\..\Libaries\CMSIS_EWARM\CM3\DeviceSupport\ST\STM32F10x\system_stm32f10x.h - $PROJ_DIR$\Debug\Obj\stm32f10x_dac.pbi - $PROJ_DIR$\Debug\Obj\stm32f10x_sdio.pbi - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_usart.h - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_gpio.h - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_rcc.h - $TOOLKIT_DIR$\inc\c\cmsis_iar.h - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_iwdg.h - $PROJ_DIR$\..\Libaries\CMSIS_EWARM\Include\core_cmFunc.h - $PROJ_DIR$\Debug\Obj\mbfuncother.pbi - $PROJ_DIR$\Debug\Obj\mbfuncholding.o - $PROJ_DIR$\Debug\Obj\mb.pbi - $PROJ_DIR$\Debug\Obj\bsp.o - $PROJ_DIR$\Debug\Obj\mbfuncdisc.pbi - $PROJ_DIR$\Debug\Obj\irq.o - $PROJ_DIR$\Debug\Obj\app_task.pbi - $PROJ_DIR$\Debug\Obj\ipc.o - $PROJ_DIR$\Debug\Obj\stm32f10x_it.pbi - $PROJ_DIR$\Debug\Obj\stm32f10x_i2c.o - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_tim.h - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_flash.h - $TOOLKIT_DIR$\inc\c\intrinsics.h - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_dma.h - $PROJ_DIR$\Debug\Obj\system_stm32f10x.pbi - $PROJ_DIR$\Debug\Obj\stm32f10x_dbgmcu.pbi - $TOOLKIT_DIR$\inc\c\DLib_Product.h + $PROJ_DIR$\..\FreeModbus\modbus\include\mbconfig.h + $PROJ_DIR$\..\RT-Thread-1.1.1\include\rtdebug.h + $PROJ_DIR$\Debug\Obj\mb.o + $PROJ_DIR$\Debug\Obj\misc.pbi + $PROJ_DIR$\Debug\Obj\stm32f10x_bkp.pbi + $PROJ_DIR$\..\RT-Thread-1.1.1\include\rtdef.h + $PROJ_DIR$\Debug\Obj\mb_m.o + $PROJ_DIR$\..\APP\inc\rtconfig.h + $PROJ_DIR$\..\RT-Thread-1.1.1\include\rtm.h + $PROJ_DIR$\..\FreeModbus\modbus\include\mbport.h + $PROJ_DIR$\..\FreeModbus\modbus\include\mb.h $PROJ_DIR$\Debug\Obj\port.pbi - $TOOLKIT_DIR$\lib\rt7M_tl.a - $PROJ_DIR$\Debug\Obj\port.o - $PROJ_DIR$\..\FreeModbus\port\user_mb_app.h - $TOOLKIT_DIR$\inc\c\DLib_Threads.h - $PROJ_DIR$\Debug\Obj\mbfuncdisc_m.pbi - $TOOLKIT_DIR$\inc\c\xencoding_limits.h - $TOOLKIT_DIR$\inc\c\DLib_Config_Normal.h $PROJ_DIR$\Debug\Obj\porttimer_m.pbi - $TOOLKIT_DIR$\inc\c\yvals.h - $PROJ_DIR$\Debug\Obj\porttimer.o - $PROJ_DIR$\Debug\Obj\porttimer.pbi - $PROJ_DIR$\Debug\Obj\portserial_m.o - $PROJ_DIR$\Debug\Obj\mempool.o $PROJ_DIR$\Debug\Obj\mbfuncdisc_m.o $PROJ_DIR$\Debug\Obj\stm32f10x_dma.pbi - $PROJ_DIR$\Debug\Obj\stm32f10x_exti.pbi $PROJ_DIR$\Debug\Obj\stm32f10x_gpio.pbi - $PROJ_DIR$\Debug\Obj\portevent_m.pbi $TOOLKIT_DIR$\inc\c\DLib_Defaults.h + $TOOLKIT_DIR$\inc\c\ycheck.h + $PROJ_DIR$\Debug\Obj\stm32f10x_fsmc.pbi + $PROJ_DIR$\..\FreeModbus\port\user_mb_app.h + $PROJ_DIR$\Debug\Obj\portserial.o + $TOOLKIT_DIR$\inc\c\xencoding_limits.h $PROJ_DIR$\Debug\Obj\stm32f10x_bkp.o + $TOOLKIT_DIR$\lib\rt7M_tl.a + $PROJ_DIR$\Debug\Obj\stm32f10x_fsmc.o + $PROJ_DIR$\Debug\Obj\portserial_m.o + $TOOLKIT_DIR$\inc\c\yvals.h + $PROJ_DIR$\Debug\Obj\mempool.o + $PROJ_DIR$\Debug\Obj\port.o + $PROJ_DIR$\Debug\Obj\stm32f10x_exti.pbi + $PROJ_DIR$\Debug\Obj\portevent_m.pbi + $TOOLKIT_DIR$\inc\c\DLib_Threads.h $PROJ_DIR$\Debug\Obj\stm32f10x_i2c.pbi $PROJ_DIR$\..\Libaries\CMSIS_EWARM\Include\core_cmInstr.h - $PROJ_DIR$\Debug\Obj\stm32f10x_fsmc.o $PROJ_DIR$\Debug\Obj\portevent.o - $PROJ_DIR$\Debug\Obj\stm32f10x_fsmc.pbi + $PROJ_DIR$\Debug\Obj\porttimer.o $PROJ_DIR$\Debug\Obj\stm32f10x_rtc.pbi - $TOOLKIT_DIR$\inc\c\ycheck.h - $PROJ_DIR$\Debug\Obj\portserial.o - $TOOLKIT_DIR$\lib\shb_l.a - $PROJ_DIR$\Debug\Obj\porttimer_m.o - $PROJ_DIR$\Debug\Obj\cpuusage.pbi - $PROJ_DIR$\Debug\Obj\cpuusage.o + $PROJ_DIR$\Debug\Obj\mbfuncdisc_m.pbi + $PROJ_DIR$\Debug\Obj\porttimer.pbi + $TOOLKIT_DIR$\inc\c\DLib_Config_Normal.h $PROJ_DIR$\Debug\Obj\stm32f10x_iwdg.pbi - $PROJ_DIR$\Debug\Obj\stm32f10x_spi.pbi $PROJ_DIR$\Debug\Obj\mbrtu_m.pbi - $PROJ_DIR$\Debug\Obj\cpuport.o - $PROJ_DIR$\Debug\Obj\stm32f10x_pwr.o + $TOOLKIT_DIR$\lib\shb_l.a + $PROJ_DIR$\Debug\Obj\cpuusage.pbi + $PROJ_DIR$\Debug\Obj\stm32f10x_spi.pbi $PROJ_DIR$\Debug\Obj\mbrtu_m.o - $PROJ_DIR$\Debug\Obj\stm32f10x_exti.o $PROJ_DIR$\Debug\Obj\stm32f10x_tim.pbi $PROJ_DIR$\Debug\Obj\stm32f10x_dac.o - $PROJ_DIR$\Debug\Obj\stm32f10x_adc.pbi - $PROJ_DIR$\Debug\Obj\stm32f10x_rcc.pbi - $PROJ_DIR$\Debug\Obj\stm32f10x_pwr.pbi $PROJ_DIR$\Debug\Obj\stm32f10x_rcc.o - $PROJ_DIR$\Debug\Obj\stm32f10x_gpio.o - $PROJ_DIR$\Debug\Obj\stm32f10x_tim.o $PROJ_DIR$\Debug\Obj\stm32f10x_sdio.o - $PROJ_DIR$\Debug\Obj\stm32f10x_wwdg.o $PROJ_DIR$\Debug\Obj\stm32f10x_flash.o $PROJ_DIR$\Debug\Obj\stm32f10x_dma.o - $PROJ_DIR$\Debug\Obj\stm32f10x_rtc.o + $PROJ_DIR$\Debug\Obj\cpuport.o + $PROJ_DIR$\Debug\Obj\stm32f10x_tim.o + $PROJ_DIR$\Debug\Obj\stm32f10x_pwr.pbi $PROJ_DIR$\Debug\Obj\stm32f10x_can.o + $PROJ_DIR$\Debug\Obj\stm32f10x_rcc.pbi + $PROJ_DIR$\Debug\Obj\stm32f10x_gpio.o + $PROJ_DIR$\Debug\Obj\stm32f10x_exti.o + $PROJ_DIR$\Debug\Obj\cpuusage.o + $PROJ_DIR$\Debug\Obj\stm32f10x_pwr.o + $PROJ_DIR$\Debug\Obj\porttimer_m.o + $PROJ_DIR$\Debug\Obj\stm32f10x_adc.pbi + $PROJ_DIR$\Debug\Obj\stm32f10x_wwdg.o + $PROJ_DIR$\Debug\Obj\stm32f10x_rtc.o $PROJ_DIR$\Debug\Obj\stm32f10x_wwdg.pbi - $PROJ_DIR$\Debug\Obj\stm32f10x_usart.pbi $PROJ_DIR$\Debug\Obj\stm32f10x_dbgmcu.o $PROJ_DIR$\Debug\Obj\stm32f10x_flash.pbi - $PROJ_DIR$\Debug\Obj\mbutils.pbi - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_crc.h - $PROJ_DIR$\Debug\Obj\mbfuncdiag.pbi - $PROJ_DIR$\Debug\Obj\mbfuncinput.o - $PROJ_DIR$\Debug\Obj\mbfunccoils.pbi - $PROJ_DIR$\Debug\Obj\backtrace.o - $PROJ_DIR$\Debug\Obj\mbutils.o - $PROJ_DIR$\Debug\Obj\backtrace.pbi + $PROJ_DIR$\Debug\Obj\stm32f10x_usart.pbi + $PROJ_DIR$\..\RT-Thread-1.2.2\include\rtdef.h $PROJ_DIR$\Debug\Obj\mbfuncdiag.o - $PROJ_DIR$\Debug\Obj\mbfuncinput.pbi - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_cec.h - $PROJ_DIR$\Debug\Obj\mbfuncother.o - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_dbgmcu.h - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_dac.h - $PROJ_DIR$\Debug\Obj\user_mb_app.o - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_fsmc.h - $PROJ_DIR$\Debug\Obj\startup_stm32f10x_md.o - $PROJ_DIR$\..\FreeModbus\modbus\include\mb_m.h - $PROJ_DIR$\..\FreeModbus\modbus\include\mbutils.h $PROJ_DIR$\Debug\Obj\memheap.pbi $PROJ_DIR$\Debug\Obj\mbfunccoils.o - $PROJ_DIR$\Debug\Obj\mbfuncdisc.o - $PROJ_DIR$\Debug\Obj\mbfuncholding.pbi $PROJ_DIR$\..\FreeModbus\modbus\rtu\mbrtu.h - $PROJ_DIR$\..\FreeModbus\modbus\rtu\mbcrc.h + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_crc.h + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_fsmc.h + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_cec.h + $PROJ_DIR$\..\FreeModbus\modbus\include\mb_m.h $PROJ_DIR$\Debug\Obj\user_mb_app.pbi - $PROJ_DIR$\..\FreeModbus\modbus\include\mbframe.h + $PROJ_DIR$\Debug\Obj\mbfuncother.o + $PROJ_DIR$\Debug\Obj\mbfunccoils.pbi + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_dbgmcu.h + $PROJ_DIR$\Debug\Obj\mbfuncinput.pbi + $PROJ_DIR$\Debug\Obj\user_mb_app.o + $PROJ_DIR$\..\FreeModbus\modbus\include\mbutils.h + $PROJ_DIR$\Debug\Obj\mbfuncdisc.o + $PROJ_DIR$\Debug\Obj\mbfuncinput.o + $PROJ_DIR$\Debug\Obj\mbutils.o + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_dac.h + $PROJ_DIR$\Debug\Obj\startup_stm32f10x_md.o + $PROJ_DIR$\..\FreeModbus\modbus\rtu\mbcrc.h $PROJ_DIR$\Debug\Obj\mb_m.pbi + $PROJ_DIR$\Debug\Obj\mbfuncholding.pbi + $PROJ_DIR$\Debug\Obj\backtrace.pbi + $PROJ_DIR$\..\FreeModbus\modbus\include\mbframe.h $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_can.h - $TOOLKIT_DIR$\inc\c\DLib_Product_string.h - $TOOLKIT_DIR$\inc\c\string.h - $PROJ_DIR$\..\FreeModbus\modbus\include\mbfunc.h - $PROJ_DIR$\Debug\Obj\mbfuncinput_m.pbi - $PROJ_DIR$\Debug\Obj\user_mb_app_m.o - $PROJ_DIR$\Debug\Obj\mbfunccoils_m.o - $PROJ_DIR$\Debug\Obj\mbfuncholding_m.o - $PROJ_DIR$\Debug\Obj\mbfuncinput_m.o - $PROJ_DIR$\Debug\Obj\mbfunccoils_m.pbi - $PROJ_DIR$\Debug\Obj\mbfuncholding_m.pbi - $PROJ_DIR$\Debug\Obj\user_mb_app_m.pbi - $PROJ_DIR$\..\RT-Thread-1.2.2\src\clock.c - $PROJ_DIR$\..\RT-Thread-1.2.2\src\cpuusage.c - $PROJ_DIR$\..\RT-Thread-1.2.2\src\idle.c - $PROJ_DIR$\..\RT-Thread-1.2.2\src\ipc.c - $PROJ_DIR$\..\RT-Thread-1.2.2\src\irq.c - $PROJ_DIR$\..\RT-Thread-1.2.2\src\kservice.c - $PROJ_DIR$\..\RT-Thread-1.2.2\src\device.c - $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\include\rtdevice.h - $PROJ_DIR$\Debug\Obj\portal.o - $PROJ_DIR$\Debug\Obj\pipe.pbi - $PROJ_DIR$\Debug\Obj\portal.pbi - $PROJ_DIR$\Debug\Obj\completion.o - $PROJ_DIR$\Debug\Obj\pipe.o - $PROJ_DIR$\Debug\Obj\dataqueue.pbi - $PROJ_DIR$\Debug\Obj\ringbuffer.pbi - $PROJ_DIR$\Debug\Obj\wrokqueue.o + $PROJ_DIR$\Debug\Obj\mbutils.pbi + $PROJ_DIR$\Debug\Obj\mbfuncdiag.pbi $PROJ_DIR$\Debug\Obj\completion.pbi - $PROJ_DIR$\Debug\Obj\ringbuffer.o + $PROJ_DIR$\Debug\Obj\mbfuncinput_m.pbi $PROJ_DIR$\Debug\Obj\dataqueue.o + $PROJ_DIR$\Debug\Obj\mbfunccoils_m.o $PROJ_DIR$\Debug\Obj\wrokqueue.pbi - $PROJ_DIR$\..\RT-Thread-1.2.2\src\slab.c - $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\pipe.c - $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\portal.c - $PROJ_DIR$\..\RT-Thread-1.2.2\src\thread.c - $PROJ_DIR$\..\RT-Thread-1.2.2\src\mempool.c - $PROJ_DIR$\..\RT-Thread-1.2.2\src\timer.c - $PROJ_DIR$\..\RT-Thread-1.2.2\src\mem.c - $PROJ_DIR$\..\RT-Thread-1.2.2\src\memheap.c - $PROJ_DIR$\..\RT-Thread-1.2.2\src\module.c - $PROJ_DIR$\..\RT-Thread-1.2.2\src\object.c - $PROJ_DIR$\..\RT-Thread-1.2.2\src\scheduler.c - $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\completion.c - $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\dataqueue.c - $PROJ_DIR$\..\RT-Thread-1.2.2\src\module.h - $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\ringbuffer.c - $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\wrokqueue.c - $PROJ_DIR$\..\RT-Thread-1.2.2\libcpu\arm\cortex-m3\cpuport.c - $PROJ_DIR$\..\RT-Thread-1.2.2\libcpu\arm\cortex-m3\context_iar.S - $PROJ_DIR$\..\RT-Thread-1.2.2\include\rtservice.h + $PROJ_DIR$\Debug\Obj\completion.o $PROJ_DIR$\..\RT-Thread-1.2.2\include\rtthread.h - $PROJ_DIR$\..\RT-Thread-1.2.2\include\rthw.h - $PROJ_DIR$\..\RT-Thread-1.2.2\include\rtdebug.h + $PROJ_DIR$\..\RT-Thread-1.2.2\include\rtservice.h $PROJ_DIR$\..\RT-Thread-1.2.2\include\rtm.h - $PROJ_DIR$\..\RT-Thread-1.2.2\include\rtdef.h + $PROJ_DIR$\..\FreeModbus\modbus\include\mbfunc.h + $PROJ_DIR$\Debug\Obj\wrokqueue.o + $PROJ_DIR$\..\RT-Thread-1.2.2\include\rthw.h + $PROJ_DIR$\Debug\Obj\ringbuffer.o + $PROJ_DIR$\..\RT-Thread-1.2.2\include\rtdebug.h + $PROJ_DIR$\Debug\Obj\mbfuncinput_m.o + $PROJ_DIR$\Debug\Obj\pipe.o + $PROJ_DIR$\Debug\Obj\mbfuncholding_m.pbi + $PROJ_DIR$\Debug\Obj\mbfunccoils_m.pbi + $PROJ_DIR$\Debug\Obj\portal.pbi + $PROJ_DIR$\Debug\Obj\dataqueue.pbi + $PROJ_DIR$\Debug\Obj\mbfuncholding_m.o + $TOOLKIT_DIR$\inc\c\string.h + $TOOLKIT_DIR$\inc\c\DLib_Product_string.h + $PROJ_DIR$\Debug\Obj\user_mb_app_m.pbi + $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\include\rtdevice.h + $PROJ_DIR$\Debug\Obj\pipe.pbi + $PROJ_DIR$\Debug\Obj\portal.o + $PROJ_DIR$\Debug\Obj\ringbuffer.pbi + $PROJ_DIR$\Debug\Obj\user_mb_app_m.o + $PROJ_DIR$\..\BSP\inc\usart.h + $PROJ_DIR$\Debug\Obj\usart.o + $PROJ_DIR$\Debug\Obj\usart.pbi + $PROJ_DIR$\..\FreeModbus\port\rtt\portserial_m.c + $PROJ_DIR$\..\FreeModbus\port\rtt\portevent.c + $PROJ_DIR$\..\FreeModbus\port\rtt\portserial.c + $PROJ_DIR$\..\FreeModbus\port\rtt\portevent_m.c + $PROJ_DIR$\..\BSP\src\usart.c + $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\serial\serial.c + $PROJ_DIR$\..\FreeModbus\port\rtt\porttimer.c + $PROJ_DIR$\..\FreeModbus\port\rtt\porttimer_m.c + $PROJ_DIR$\Debug\Obj\serial.o + $PROJ_DIR$\Debug\Obj\serial.pbi + $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\include\drivers\serial.h - $PROJ_DIR$\..\RT-Thread-1.1.1\src\mempool.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\irq.c BICOMP - 43 + 27 ICCARM - 215 + 183 BICOMP - 150 89 145 146 92 229 211 221 209 201 208 206 151 70 152 + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 ICCARM - 150 89 145 146 92 229 211 221 209 201 208 206 151 70 152 + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 - $PROJ_DIR$\..\RT-Thread-1.1.1\src\timer.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\kservice.c BICOMP - 59 + 115 ICCARM - 47 + 118 BICOMP - 89 145 146 92 229 211 221 209 201 208 206 151 70 152 150 + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 323 ICCARM - 89 145 146 92 229 211 221 209 201 208 206 151 70 152 150 + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 323 - $PROJ_DIR$\..\Libaries\CMSIS_EWARM\CM3\DeviceSupport\ST\STM32F10x\startup\iar\startup_stm32f10x_md.s - - - AARM - 276 - - - - - $PROJ_DIR$\..\RT-Thread-1.1.1\src\module.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\mem.c BICOMP - 24 + 131 ICCARM - 26 + 11 BICOMP - 150 89 145 146 92 229 211 221 209 201 208 206 151 70 152 + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 ICCARM - 150 89 145 146 92 229 211 221 209 201 208 206 151 70 152 + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 - $PROJ_DIR$\..\RT-Thread-1.1.1\src\scheduler.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\mempool.c BICOMP - 40 - - - ICCARM - 36 - - - - - BICOMP - 89 145 146 92 229 211 221 209 201 208 206 151 70 152 150 - - - ICCARM - 89 145 146 92 229 211 221 209 201 208 206 151 70 152 150 - - - - - $PROJ_DIR$\..\RT-Thread-1.1.1\src\object.c - - - BICOMP - 25 - - - ICCARM - 67 - - - - - BICOMP - 89 145 146 92 229 211 221 209 201 208 206 151 70 152 150 - - - ICCARM - 89 145 146 92 229 211 221 209 201 208 206 151 70 152 150 - - - - - $PROJ_DIR$\..\RT-Thread-1.1.1\src\slab.c - - - BICOMP - 22 - - - ICCARM - 57 - - - - - BICOMP - 150 89 145 146 92 229 211 221 209 201 208 206 151 70 152 - - - ICCARM - 150 89 145 146 92 229 211 221 209 201 208 206 151 70 152 - - - - - $PROJ_DIR$\..\RT-Thread-1.1.1\src\memheap.c - - - BICOMP - 279 - - - ICCARM - 169 - - - - - BICOMP - 150 89 145 146 92 229 211 221 209 201 208 206 151 70 152 - - - ICCARM - 150 89 145 146 92 229 211 221 209 201 208 206 151 70 152 - - - - - [ROOT_NODE] - - - ILINK - 163 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_can.c - - - BICOMP - 164 - - - ICCARM - 255 - - - - - BICOMP - 288 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - ICCARM - 288 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_iwdg.c - - - BICOMP - 235 - - - ICCARM - 148 - - - - - BICOMP - 183 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 181 195 178 179 - - - ICCARM - 183 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 181 195 178 179 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_crc.c - - - BICOMP - 155 - - - ICCARM - 45 - - - - - BICOMP - 261 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - ICCARM - 261 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_dma.c - - - BICOMP - 217 - - - ICCARM - 253 - - - - - BICOMP - 198 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 174 196 180 183 181 195 178 179 - - - ICCARM - 198 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 174 196 180 183 181 195 178 179 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_pwr.c - - - BICOMP - 246 - - - ICCARM - 239 - - - - - BICOMP - 84 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - ICCARM - 84 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_rcc.c - - - BICOMP - 245 - - - ICCARM - 247 - - - - - BICOMP - 181 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 195 178 179 - - - ICCARM - 181 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 195 178 179 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_rtc.c - - - BICOMP - 228 - - - ICCARM - 254 - - - - - BICOMP - 81 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - ICCARM - 81 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_sdio.c - - - BICOMP - 177 - - - ICCARM - 250 - - - - - BICOMP - 83 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - ICCARM - 83 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_spi.c - - - BICOMP - 236 - - - ICCARM - 168 - - - - - BICOMP - 74 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - ICCARM - 74 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_dbgmcu.c - - - BICOMP - 200 - - - ICCARM - 258 - - - - - BICOMP - 272 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - ICCARM - 272 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_tim.c - - - BICOMP - 242 - - - ICCARM - 249 - - - - - BICOMP - 195 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 178 179 - - - ICCARM - 195 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 178 179 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_wwdg.c - - - BICOMP - 256 - - - ICCARM - 251 - - - - - BICOMP - 73 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - ICCARM - 73 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_i2c.c - - - BICOMP - 223 - - - ICCARM - 194 - - - - - BICOMP - 72 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - ICCARM - 72 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_bkp.c - - - BICOMP - 159 - - - ICCARM - 222 - - - - - BICOMP - 77 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - ICCARM - 77 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_exti.c - - - BICOMP - 218 + 133 ICCARM @@ -867,194 +446,75 @@ BICOMP - 174 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 196 180 183 181 195 178 179 + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 ICCARM - 174 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 196 180 183 181 195 178 179 + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_flash.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\module.c BICOMP - 259 + 113 ICCARM - 252 + 122 BICOMP - 196 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 180 183 181 195 178 179 + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 ICCARM - 196 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 180 183 181 195 178 179 + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_dac.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\ipc.c BICOMP - 176 + 13 ICCARM - 243 + 187 BICOMP - 273 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 323 ICCARM - 273 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 323 - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_fsmc.c + [ROOT_NODE] - BICOMP - 227 - - - ICCARM - 225 - - - - - BICOMP - 275 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - ICCARM - 275 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_gpio.c - - - BICOMP - 219 - - - ICCARM - 248 - - - - - BICOMP - 180 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 183 181 195 178 179 - - - ICCARM - 180 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 183 181 195 178 179 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_usart.c - - - BICOMP - 257 - - - ICCARM - 142 - - - - - BICOMP - 178 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 179 - - - ICCARM - 178 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 179 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_cec.c - - - BICOMP - 158 - - - ICCARM - 18 - - - - - BICOMP - 270 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - ICCARM - 270 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_adc.c - - - BICOMP - 244 - - - ICCARM - 55 - - - - - BICOMP - 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 198 174 196 180 183 181 195 178 179 - - - ICCARM - 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 198 174 196 180 183 181 195 178 179 - - - - - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncdiag.c - - - BICOMP - 262 - - - ICCARM - 268 + ILINK + 206 - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncdisc_m.c + $PROJ_DIR$\..\FreeModbus\modbus\mb.c BICOMP - 207 + 178 ICCARM @@ -1064,467 +524,11 @@ BICOMP - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 277 286 + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 308 321 287 ICCARM - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 277 286 - - - - - $PROJ_DIR$\..\FreeModbus\modbus\rtu\mbrtu_m.c - - - BICOMP - 237 - - - ICCARM - 240 - - - - - BICOMP - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 277 283 286 284 - - - ICCARM - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 277 283 286 284 - - - - - $PROJ_DIR$\..\FreeModbus\port\portevent_m.c - - - BICOMP - 220 - - - ICCARM - 88 - - - - - BICOMP - 157 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 156 95 277 - - - ICCARM - 157 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 156 95 277 - - - - - $PROJ_DIR$\..\FreeModbus\port\portserial_m.c - - - BICOMP - 165 - - - ICCARM - 214 - - - - - BICOMP - 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 - - - ICCARM - 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 - - - - - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfunccoils.c - - - BICOMP - 264 - - - ICCARM - 280 - - - - - BICOMP - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 286 - - - ICCARM - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 286 - - - - - $PROJ_DIR$\..\FreeModbus\modbus\rtu\mbrtu.c - - - BICOMP - 35 - - - ICCARM - 161 - - - - - BICOMP - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 283 286 284 - - - ICCARM - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 283 286 284 - - - - - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbutils.c - - - BICOMP - 260 - - - ICCARM - 266 - - - - - BICOMP - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 - - - ICCARM - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 - - - - - $PROJ_DIR$\..\FreeModbus\port\porttimer.c - - - BICOMP - 213 - - - ICCARM - 212 - - - - - BICOMP - 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 - - - ICCARM - 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 - - - - - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncinput.c - - - BICOMP - 269 - - - ICCARM - 263 - - - - - BICOMP - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 286 - - - ICCARM - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 286 - - - - - $PROJ_DIR$\..\RT-Thread-1.1.1\src\idle.c - - - BICOMP - 46 - - - ICCARM - 54 - - - - - ICCARM - 150 89 145 146 92 229 211 221 209 201 208 206 151 70 152 - - - - - $PROJ_DIR$\..\FreeModbus\modbus\mb.c - - - BICOMP - 187 - - - ICCARM - 153 - - - - - BICOMP - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 286 291 283 - - - ICCARM - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 286 291 283 - - - - - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncinput_m.c - - - BICOMP - 292 - - - ICCARM - 296 - - - - - BICOMP - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 277 286 - - - ICCARM - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 277 286 - - - - - $PROJ_DIR$\..\RT-Thread-1.1.1\src\kservice.c - - - BICOMP - 38 - - - ICCARM - 50 - - - - - BICOMP - 89 145 146 92 229 211 221 209 201 208 206 151 70 152 150 - - - ICCARM - 89 145 146 92 229 211 221 209 201 208 206 151 70 152 150 - - - - - $PROJ_DIR$\..\RT-Thread-1.1.1\src\mem.c - - - BICOMP - 39 - - - ICCARM - 61 - - - - - BICOMP - 150 89 145 146 92 229 211 221 209 201 208 206 151 70 152 - - - ICCARM - 150 89 145 146 92 229 211 221 209 201 208 206 151 70 152 - - - - - $PROJ_DIR$\..\FreeModbus\port\portserial.c - - - BICOMP - 87 - - - ICCARM - 230 - - - - - BICOMP - 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 - - - ICCARM - 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 - - - - - $PROJ_DIR$\..\RT-Thread-1.1.1\src\thread.c - - - BICOMP - 42 - - - ICCARM - 48 - - - - - BICOMP - 89 145 146 92 229 211 221 209 201 208 206 151 70 152 150 - - - ICCARM - 89 145 146 92 229 211 221 209 201 208 206 151 70 152 150 - - - - - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncdisc.c - - - BICOMP - 189 - - - ICCARM - 281 - - - - - BICOMP - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 286 - - - ICCARM - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 286 - - - - - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncholding_m.c - - - BICOMP - 298 - - - ICCARM - 295 - - - - - BICOMP - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 277 286 - - - ICCARM - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 277 286 - - - - - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncholding.c - - - BICOMP - 282 - - - ICCARM - 186 - - - - - BICOMP - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 286 - - - ICCARM - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 286 - - - - - $PROJ_DIR$\..\FreeModbus\port\user_mb_app_m.c - - - BICOMP - 299 - - - ICCARM - 293 - - - - - BICOMP - 205 157 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 156 95 277 286 278 - - - ICCARM - 205 157 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 156 95 277 286 278 - - - - - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncother.c - - - BICOMP - 185 - - - ICCARM - 271 - - - - - BICOMP - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 286 - - - ICCARM - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 286 + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 308 321 287 @@ -1533,449 +537,67 @@ BICOMP - 202 + 225 ICCARM - 204 + 242 BICOMP - 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 + 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 ICCARM - 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 + 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 - $PROJ_DIR$\..\FreeModbus\port\user_mb_app.c + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfunccoils.c BICOMP - 285 - - - ICCARM - 274 - - - - - BICOMP - 205 157 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 156 95 277 286 278 - - - ICCARM - 205 157 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 156 95 277 286 278 - - - - - $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfunccoils_m.c - - - BICOMP - 297 - - - ICCARM 294 + + ICCARM + 286 + BICOMP - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 277 286 + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 308 ICCARM - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 277 286 + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 308 - $PROJ_DIR$\..\RT-Thread-1.1.1\src\clock.c + $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\wrokqueue.c BICOMP - 49 + 316 ICCARM - 52 - - - - - ICCARM - 150 89 145 146 92 229 211 221 209 201 208 206 151 70 152 - - - - - $PROJ_DIR$\..\RT-Thread-1.1.1\src\device.c - - - BICOMP - 44 - - - ICCARM - 51 - - - - - ICCARM - 89 145 146 92 229 211 221 209 201 208 206 151 70 152 - - - - - $PROJ_DIR$\..\FreeModbus\modbus\rtu\mbcrc.c - - - BICOMP - 173 - - - ICCARM - 162 + 322 BICOMP - 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 336 354 ICCARM - 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 - - - - - $PROJ_DIR$\..\FreeModbus\port\portevent.c - - - BICOMP - 91 - - - ICCARM - 226 - - - - - BICOMP - 157 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 156 95 - - - ICCARM - 157 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 156 95 - - - - - $PROJ_DIR$\..\RT-Thread-1.1.1\src\irq.c - - - BICOMP - 60 - - - ICCARM - 190 - - - - - BICOMP - 150 89 145 146 92 229 211 221 209 201 208 206 151 70 152 - - - ICCARM - 150 89 145 146 92 229 211 221 209 201 208 206 151 70 152 - - - - - $PROJ_DIR$\..\RT-Thread-1.1.1\src\ipc.c - - - BICOMP - 53 - - - ICCARM - 192 - - - - - BICOMP - 89 145 146 92 229 211 221 209 201 208 206 151 70 152 150 - - - ICCARM - 89 145 146 92 229 211 221 209 201 208 206 151 70 152 150 - - - - - $PROJ_DIR$\..\FreeModbus\port\porttimer_m.c - - - BICOMP - 210 - - - ICCARM - 232 - - - - - BICOMP - 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 277 - - - ICCARM - 166 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 277 - - - - - $PROJ_DIR$\..\BSP\src\bsp.c - - - BICOMP - 62 - - - ICCARM - 188 - - - - - BICOMP - 69 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 340 339 146 341 343 92 338 342 - - - ICCARM - 69 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 340 339 146 341 343 92 338 342 - - - - - $PROJ_DIR$\..\RT-Thread-1.1.1\libcpu\arm\cortex-m3\context_iar.S - - - AARM - 58 - - - - - $PROJ_DIR$\..\RT-Thread-1.1.1\libcpu\arm\cortex-m3\cpuport.c - - - BICOMP - 160 - - - - - $PROJ_DIR$\..\RT-Thread-1.1.1\libcpu\arm\common\backtrace.c - - - BICOMP - 267 - - - - - $PROJ_DIR$\..\RT-Thread-1.1.1\libcpu\arm\common\showmem.c - - - BICOMP - 171 - - - ICCARM - 170 - - - - - $PROJ_DIR$\..\Libaries\CMSIS_EWARM\CM3\DeviceSupport\ST\STM32F10x\system_stm32f10x.c - - - BICOMP - 199 - - - ICCARM - 63 - - - - - BICOMP - 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - ICCARM - 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 179 - - - - - $PROJ_DIR$\..\FreeModbus\modbus\mb_m.c - - - BICOMP - 287 - - - ICCARM - 143 - - - - - BICOMP - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 277 286 291 283 - - - ICCARM - 76 229 211 221 209 201 208 206 78 290 289 166 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 149 340 339 146 341 343 92 338 342 90 93 157 156 95 277 286 291 283 - - - - - $PROJ_DIR$\..\APP\src\app.c - - - BICOMP - 41 - - - ICCARM - 56 - - - - - BICOMP - 96 76 229 211 221 209 201 208 206 78 68 80 340 339 146 341 343 92 338 342 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 69 94 75 205 157 166 149 90 93 156 95 277 286 278 - - - ICCARM - 96 76 229 211 221 209 201 208 206 78 68 80 340 339 146 341 343 92 338 342 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 69 94 75 205 157 166 149 90 93 156 95 277 286 278 - - - - - $PROJ_DIR$\..\APP\src\app_task.c - - - BICOMP - 191 - - - ICCARM - 65 - - - - - BICOMP - 96 76 229 211 221 209 201 208 206 78 68 80 340 339 146 341 343 92 338 342 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 69 94 75 205 157 166 149 90 93 156 95 277 286 278 - - - ICCARM - 96 76 229 211 221 209 201 208 206 78 68 80 340 339 146 341 343 92 338 342 130 147 144 172 79 224 182 197 184 175 198 174 196 180 183 181 195 178 179 69 94 75 205 157 166 149 90 93 156 95 277 286 278 - - - - - $PROJ_DIR$\..\APP\src\cpuusage.c - - - BICOMP - 233 - - - ICCARM - 234 - - - - - ICCARM - 89 145 146 92 229 211 221 209 201 208 206 151 70 152 150 75 - - - - - $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\misc.c - - - BICOMP - 154 - - - ICCARM - 66 - - - - - BICOMP - 179 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 - - - ICCARM - 179 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 130 147 198 174 196 180 183 181 195 178 - - - - - $PROJ_DIR$\..\APP\src\stm32f10x_it.c - - - BICOMP - 193 - - - ICCARM - 64 - - - - - BICOMP - 71 69 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 339 146 341 343 92 338 342 94 - - - ICCARM - 71 69 130 147 144 172 79 229 211 221 209 201 208 206 224 182 197 184 175 198 174 196 180 183 181 195 178 179 339 146 341 343 92 338 342 94 - - - - - $PROJ_DIR$\Debug\Exe\FreeModbus_Slaver&Master+RTT+STM32.out - - - ILINK - 86 56 65 188 52 311 58 238 234 318 51 54 192 190 50 153 143 162 280 294 268 281 216 186 295 263 296 271 161 240 266 61 169 215 66 26 67 312 204 308 226 88 230 214 212 232 317 36 57 276 55 222 255 18 45 243 258 253 241 252 225 248 194 64 148 239 247 254 250 168 249 142 251 63 48 47 274 293 315 231 203 85 82 + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 336 354 @@ -1984,210 +606,26 @@ BICOMP - 49 + 126 ICCARM - 52 + 127 BICOMP - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 ICCARM - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 - $PROJ_DIR$\..\RT-Thread-1.2.2\src\cpuusage.c - - - BICOMP - 233 - - - ICCARM - 234 - - - - - BICOMP - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 340 - - - ICCARM - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 340 - - - - - $PROJ_DIR$\..\RT-Thread-1.2.2\src\idle.c - - - BICOMP - 46 - - - ICCARM - 54 - - - - - BICOMP - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 - - - ICCARM - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 - - - - - $PROJ_DIR$\..\RT-Thread-1.2.2\src\ipc.c - - - BICOMP - 53 - - - ICCARM - 192 - - - - - BICOMP - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 340 - - - ICCARM - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 340 - - - - - $PROJ_DIR$\..\RT-Thread-1.2.2\src\irq.c - - - BICOMP - 60 - - - ICCARM - 190 - - - - - BICOMP - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 - - - ICCARM - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 - - - - - $PROJ_DIR$\..\RT-Thread-1.2.2\src\kservice.c - - - BICOMP - 38 - - - ICCARM - 50 - - - - - BICOMP - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 340 - - - ICCARM - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 340 - - - - - $PROJ_DIR$\..\RT-Thread-1.2.2\src\device.c - - - BICOMP - 44 - - - ICCARM - 51 - - - - - BICOMP - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 - - - ICCARM - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 - - - - - $PROJ_DIR$\..\RT-Thread-1.2.2\src\slab.c - - - BICOMP - 22 - - - ICCARM - 57 - - - - - BICOMP - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 - - - ICCARM - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 - - - - - $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\pipe.c - - - BICOMP - 309 - - - ICCARM - 312 - - - - - BICOMP - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 307 - - - ICCARM - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 307 - - - - - $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\portal.c + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbutils.c BICOMP @@ -2195,201 +633,59 @@ ICCARM - 308 + 301 BICOMP - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 307 + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 ICCARM - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 307 + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 - $PROJ_DIR$\..\RT-Thread-1.2.2\src\thread.c + $PROJ_DIR$\..\FreeModbus\port\porttimer_m.c BICOMP - 42 + 226 ICCARM - 48 + 275 - - BICOMP - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 340 - ICCARM - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 340 + 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 291 - $PROJ_DIR$\..\RT-Thread-1.2.2\src\mempool.c + $PROJ_DIR$\..\FreeModbus\port\user_mb_app_m.c BICOMP - 43 + 335 ICCARM - 215 + 340 BICOMP - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 + 233 224 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 223 153 291 308 298 ICCARM - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 - - - - - $PROJ_DIR$\..\RT-Thread-1.2.2\src\timer.c - - - BICOMP - 59 - - - ICCARM - 47 - - - - - BICOMP - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 340 - - - ICCARM - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 340 - - - - - $PROJ_DIR$\..\RT-Thread-1.2.2\src\mem.c - - - BICOMP - 39 - - - ICCARM - 61 - - - - - BICOMP - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 - - - ICCARM - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 - - - - - $PROJ_DIR$\..\RT-Thread-1.2.2\src\memheap.c - - - BICOMP - 279 - - - ICCARM - 169 - - - - - BICOMP - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 - - - ICCARM - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 - - - - - $PROJ_DIR$\..\RT-Thread-1.2.2\src\module.c - - - BICOMP - 24 - - - ICCARM - 26 - - - - - BICOMP - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 - - - ICCARM - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 - - - - - $PROJ_DIR$\..\RT-Thread-1.2.2\src\object.c - - - BICOMP - 25 - - - ICCARM - 67 - - - - - BICOMP - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 340 - - - ICCARM - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 340 - - - - - $PROJ_DIR$\..\RT-Thread-1.2.2\src\scheduler.c - - - BICOMP - 40 - - - ICCARM - 36 - - - - - BICOMP - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 340 - - - ICCARM - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 340 + 233 224 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 223 153 291 308 298 @@ -2398,53 +694,7 @@ BICOMP - 316 - - - ICCARM - 311 - - - - - BICOMP - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 307 - - - ICCARM - 340 339 146 341 343 92 229 211 221 209 201 208 206 338 342 307 - - - - - $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\dataqueue.c - - - BICOMP - 313 - - - ICCARM - 318 - - - - - BICOMP - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 307 340 - - - ICCARM - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 307 340 - - - - - $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\ringbuffer.c - - - BICOMP - 314 + 312 ICCARM @@ -2454,20 +704,666 @@ BICOMP - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 307 290 78 289 + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 336 354 ICCARM - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 307 290 78 289 + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 336 354 - $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\wrokqueue.c + $PROJ_DIR$\..\RT-Thread-1.2.2\src\cpuusage.c BICOMP - 319 + 257 + + + ICCARM + 273 + + + + + BICOMP + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 323 + + + ICCARM + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 323 + + + + + $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\portal.c + + + BICOMP + 330 + + + ICCARM + 338 + + + + + BICOMP + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 336 354 + + + ICCARM + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 336 354 + + + + + $PROJ_DIR$\..\RT-Thread-1.2.2\src\device.c + + + BICOMP + 124 + + + ICCARM + 119 + + + + + BICOMP + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 + + + ICCARM + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 + + + + + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncdiag.c + + + BICOMP + 311 + + + ICCARM + 284 + + + + + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncdisc.c + + + BICOMP + 186 + + + ICCARM + 299 + + + + + BICOMP + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 308 + + + ICCARM + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 308 + + + + + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncholding.c + + + BICOMP + 306 + + + ICCARM + 194 + + + + + BICOMP + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 308 + + + ICCARM + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 308 + + + + + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncother.c + + + BICOMP + 177 + + + ICCARM + 293 + + + + + BICOMP + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 308 + + + ICCARM + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 308 + + + + + $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\ringbuffer.c + + + BICOMP + 339 + + + ICCARM + 324 + + + + + BICOMP + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 336 354 333 28 334 + + + ICCARM + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 336 354 333 28 334 + + + + + $PROJ_DIR$\..\RT-Thread-1.2.2\src\idle.c + + + BICOMP + 116 + + + ICCARM + 30 + + + + + BICOMP + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 + + + ICCARM + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 + + + + + $PROJ_DIR$\..\FreeModbus\port\portevent.c + + + BICOMP + 151 + + + ICCARM + 248 + + + + + ICCARM + 224 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 223 153 + + + + + $PROJ_DIR$\..\RT-Thread-1.2.2\src\memheap.c + + + BICOMP + 285 + + + ICCARM + 213 + + + + + BICOMP + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 + + + ICCARM + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 + + + + + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncinput_m.c + + + BICOMP + 313 + + + ICCARM + 326 + + + + + BICOMP + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 291 308 + + + ICCARM + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 291 308 + + + + + $PROJ_DIR$\..\FreeModbus\port\portserial_m.c + + + BICOMP + 208 + + + ICCARM + 239 + + + + + ICCARM + 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 + + + + + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncinput.c + + + BICOMP + 296 + + + ICCARM + 300 + + + + + BICOMP + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 308 + + + ICCARM + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 308 + + + + + $PROJ_DIR$\..\FreeModbus\modbus\rtu\mbrtu_m.c + + + BICOMP + 255 + + + ICCARM + 259 + + + + + BICOMP + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 291 287 308 304 + + + ICCARM + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 291 287 308 304 + + + + + $PROJ_DIR$\..\FreeModbus\port\portserial.c + + + BICOMP + 149 + + + ICCARM + 234 + + + + + ICCARM + 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 + + + + + $PROJ_DIR$\..\FreeModbus\modbus\rtu\mbrtu.c + + + BICOMP + 114 + + + ICCARM + 204 + + + + + BICOMP + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 287 308 304 + + + ICCARM + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 287 308 304 + + + + + $PROJ_DIR$\..\FreeModbus\modbus\rtu\mbcrc.c + + + BICOMP + 185 + + + ICCARM + 205 + + + + + BICOMP + 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 + + + ICCARM + 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 + + + + + $PROJ_DIR$\..\FreeModbus\port\porttimer.c + + + BICOMP + 252 + + + ICCARM + 249 + + + + + ICCARM + 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 + + + + + $PROJ_DIR$\..\FreeModbus\port\user_mb_app.c + + + BICOMP + 292 + + + ICCARM + 297 + + + + + BICOMP + 233 224 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 223 153 291 308 298 + + + ICCARM + 233 224 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 223 153 291 308 298 + + + + + $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\pipe.c + + + BICOMP + 337 + + + ICCARM + 327 + + + + + BICOMP + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 336 354 + + + ICCARM + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 336 354 + + + + + $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\dataqueue.c + + + BICOMP + 331 + + + ICCARM + 314 + + + + + BICOMP + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 336 354 323 + + + ICCARM + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 336 354 323 + + + + + $PROJ_DIR$\..\FreeModbus\port\portevent_m.c + + + BICOMP + 244 + + + ICCARM + 150 + + + + + ICCARM + 224 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 223 153 291 + + + + + $PROJ_DIR$\..\APP\src\app.c + + + BICOMP + 123 + + + ICCARM + 32 + + + + + BICOMP + 159 26 231 240 230 253 192 235 245 28 6 33 323 318 221 325 283 156 319 320 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 17 158 25 233 224 209 214 139 138 223 153 291 308 298 + + + ICCARM + 159 26 231 240 230 253 192 235 245 28 6 33 323 318 221 325 283 156 319 320 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 17 158 25 233 224 209 214 139 138 223 153 291 308 298 + + + + + $PROJ_DIR$\..\APP\src\app_task.c + + + BICOMP + 180 + + + ICCARM + 24 + + + + + BICOMP + 159 26 231 240 230 253 192 235 245 28 6 33 323 318 221 325 283 156 319 320 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 17 158 25 233 224 209 214 139 138 223 153 291 308 298 + + + ICCARM + 159 26 231 240 230 253 192 235 245 28 6 33 323 318 221 325 283 156 319 320 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 17 158 25 233 224 209 214 139 138 223 153 291 308 298 + + + + + $PROJ_DIR$\..\BSP\src\bsp.c + + + BICOMP + 15 + + + ICCARM + 195 + + + + + BICOMP + 17 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 323 318 221 325 283 156 319 320 341 + + + ICCARM + 17 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 323 318 221 325 283 156 319 320 341 + + + + + $PROJ_DIR$\..\Libaries\CMSIS_EWARM\CM3\DeviceSupport\ST\STM32F10x\system_stm32f10x.c + + + BICOMP + 190 + + + ICCARM + 22 + + + + + BICOMP + 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + ICCARM + 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + + + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncdisc_m.c + + + BICOMP + 251 + + + ICCARM + 227 + + + + + BICOMP + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 291 308 + + + ICCARM + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 291 308 + + + + + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfuncholding_m.c + + + BICOMP + 328 + + + ICCARM + 332 + + + + + BICOMP + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 291 308 + + + ICCARM + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 291 308 + + + + + $PROJ_DIR$\..\RT-Thread-1.2.2\libcpu\arm\cortex-m3\context_iar.S + + + AARM + 34 + + + + + $PROJ_DIR$\..\FreeModbus\modbus\functions\mbfunccoils_m.c + + + BICOMP + 329 ICCARM @@ -2477,11 +1373,34 @@ BICOMP - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 307 + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 291 308 ICCARM - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 307 + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 291 308 + + + + + $PROJ_DIR$\..\APP\src\stm32f10x_it.c + + + BICOMP + 168 + + + ICCARM + 12 + + + + + BICOMP + 19 17 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 318 221 325 283 156 319 320 158 + + + ICCARM + 19 17 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 318 221 325 283 156 319 320 158 @@ -2490,7 +1409,384 @@ BICOMP - 160 + 200 + + + ICCARM + 266 + + + + + BICOMP + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 + + + ICCARM + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 + + + + + $PROJ_DIR$\..\FreeModbus\modbus\mb_m.c + + + BICOMP + 305 + + + ICCARM + 220 + + + + + BICOMP + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 291 308 321 287 + + + ICCARM + 26 231 240 230 253 192 235 245 28 333 334 209 71 202 198 193 31 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 291 308 321 287 + + + + + $PROJ_DIR$\..\RT-Thread-1.2.2\src\object.c + + + BICOMP + 110 + + + ICCARM + 29 + + + + + BICOMP + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 323 + + + ICCARM + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 323 + + + + + $PROJ_DIR$\..\Libaries\CMSIS_EWARM\CM3\DeviceSupport\ST\STM32F10x\startup\iar\startup_stm32f10x_md.s + + + AARM + 303 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_crc.c + + + BICOMP + 199 + + + ICCARM + 135 + + + + + BICOMP + 288 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + ICCARM + 288 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + + + $PROJ_DIR$\..\RT-Thread-1.2.2\src\slab.c + + + BICOMP + 130 + + + ICCARM + 10 + + + + + BICOMP + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 + + + ICCARM + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_wwdg.c + + + BICOMP + 279 + + + ICCARM + 277 + + + + + BICOMP + 23 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + ICCARM + 23 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_flash.c + + + BICOMP + 281 + + + ICCARM + 264 + + + + + BICOMP + 175 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 197 184 196 170 171 182 + + + ICCARM + 175 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 197 184 196 170 171 182 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_bkp.c + + + BICOMP + 218 + + + ICCARM + 236 + + + + + BICOMP + 21 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + ICCARM + 21 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + + + $PROJ_DIR$\..\RT-Thread-1.2.2\src\scheduler.c + + + BICOMP + 128 + + + ICCARM + 129 + + + + + BICOMP + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 323 + + + ICCARM + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 323 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_rcc.c + + + BICOMP + 270 + + + ICCARM + 262 + + + + + BICOMP + 196 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 170 171 182 + + + ICCARM + 196 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 170 171 182 + + + + + $PROJ_DIR$\..\RT-Thread-1.2.2\src\thread.c + + + BICOMP + 132 + + + ICCARM + 125 + + + + + BICOMP + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 323 + + + ICCARM + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 323 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_dac.c + + + BICOMP + 174 + + + ICCARM + 261 + + + + + BICOMP + 302 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + ICCARM + 302 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_i2c.c + + + BICOMP + 246 + + + ICCARM + 169 + + + + + BICOMP + 7 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + ICCARM + 7 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_iwdg.c + + + BICOMP + 254 + + + ICCARM + 211 + + + + + BICOMP + 184 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 196 170 171 182 + + + ICCARM + 184 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 196 170 171 182 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_rtc.c + + + BICOMP + 250 + + + ICCARM + 278 + + + + + BICOMP + 8 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + ICCARM + 8 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_tim.c + + + BICOMP + 260 + + + ICCARM + 267 + + + + + BICOMP + 170 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 171 182 + + + ICCARM + 170 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 171 182 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_fsmc.c + + + BICOMP + 232 ICCARM @@ -2500,23 +1796,886 @@ BICOMP - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 + 289 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 ICCARM - 339 146 341 343 92 229 211 221 209 201 208 206 338 342 + 289 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 - $PROJ_DIR$\..\RT-Thread-1.2.2\libcpu\arm\cortex-m3\context_iar.S + $PROJ_DIR$\..\RT-Thread-1.1.1\src\mempool.c + + + BICOMP + 133 + + + ICCARM + 241 + + + + + BICOMP + 201 164 219 221 156 231 240 230 253 192 235 245 215 9 222 + + + ICCARM + 201 164 219 221 156 231 240 230 253 192 235 245 215 9 222 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_dbgmcu.c + + + BICOMP + 181 + + + ICCARM + 280 + + + + + BICOMP + 295 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + ICCARM + 295 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + + + $PROJ_DIR$\..\RT-Thread-1.1.1\src\timer.c + + + BICOMP + 20 + + + ICCARM + 117 + + + + + BICOMP + 164 219 221 156 231 240 230 253 192 235 245 215 9 222 201 + + + ICCARM + 164 219 221 156 231 240 230 253 192 235 245 215 9 222 201 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_sdio.c + + + BICOMP + 176 + + + ICCARM + 263 + + + + + BICOMP + 157 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + ICCARM + 157 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + + + $PROJ_DIR$\..\RT-Thread-1.2.2\src\timer.c + + + BICOMP + 20 + + + ICCARM + 117 + + + + + BICOMP + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 323 + + + ICCARM + 318 221 325 283 156 231 240 230 253 192 235 245 319 320 323 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_adc.c + + + BICOMP + 276 + + + ICCARM + 14 + + + + + BICOMP + 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 191 173 175 197 184 196 170 171 182 + + + ICCARM + 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 191 173 175 197 184 196 170 171 182 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_can.c + + + BICOMP + 207 + + + ICCARM + 269 + + + + + BICOMP + 309 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + ICCARM + 309 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_pwr.c + + + BICOMP + 268 + + + ICCARM + 274 + + + + + BICOMP + 148 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + ICCARM + 148 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_spi.c + + + BICOMP + 258 + + + ICCARM + 210 + + + + + BICOMP + 18 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + ICCARM + 18 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_exti.c + + + BICOMP + 243 + + + ICCARM + 272 + + + + + BICOMP + 173 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 175 197 184 196 170 171 182 + + + ICCARM + 173 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 175 197 184 196 170 171 182 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_gpio.c + + + BICOMP + 229 + + + ICCARM + 271 + + + + + BICOMP + 197 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 184 196 170 171 182 + + + ICCARM + 197 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 184 196 170 171 182 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_cec.c + + + BICOMP + 203 + + + ICCARM + 120 + + + + + BICOMP + 290 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + ICCARM + 290 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\misc.c + + + BICOMP + 217 + + + ICCARM + 16 + + + + + BICOMP + 182 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 + + + ICCARM + 182 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_dma.c + + + BICOMP + 228 + + + ICCARM + 265 + + + + + BICOMP + 191 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 173 175 197 184 196 170 171 182 + + + ICCARM + 191 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 173 175 197 184 196 170 171 182 + + + + + $PROJ_DIR$\..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_usart.c + + + BICOMP + 282 + + + ICCARM + 147 + + + + + BICOMP + 171 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 182 + + + ICCARM + 171 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 182 + + + + + $PROJ_DIR$\..\RT-Thread-1.1.1\src\module.c + + + BICOMP + 113 + + + ICCARM + 122 + + + + + BICOMP + 201 164 219 221 156 231 240 230 253 192 235 245 215 9 222 + + + ICCARM + 201 164 219 221 156 231 240 230 253 192 235 245 215 9 222 + + + + + $PROJ_DIR$\..\RT-Thread-1.1.1\src\memheap.c + + + BICOMP + 285 + + + ICCARM + 213 + + + + + BICOMP + 201 164 219 221 156 231 240 230 253 192 235 245 215 9 222 + + + ICCARM + 201 164 219 221 156 231 240 230 253 192 235 245 215 9 222 + + + + + $PROJ_DIR$\..\RT-Thread-1.1.1\src\object.c + + + BICOMP + 110 + + + ICCARM + 29 + + + + + BICOMP + 164 219 221 156 231 240 230 253 192 235 245 215 9 222 201 + + + ICCARM + 164 219 221 156 231 240 230 253 192 235 245 215 9 222 201 + + + + + $PROJ_DIR$\..\RT-Thread-1.1.1\src\slab.c + + + BICOMP + 130 + + + ICCARM + 10 + + + + + BICOMP + 201 164 219 221 156 231 240 230 253 192 235 245 215 9 222 + + + ICCARM + 201 164 219 221 156 231 240 230 253 192 235 245 215 9 222 + + + + + $PROJ_DIR$\..\RT-Thread-1.1.1\src\scheduler.c + + + BICOMP + 128 + + + ICCARM + 129 + + + + + BICOMP + 164 219 221 156 231 240 230 253 192 235 245 215 9 222 201 + + + ICCARM + 164 219 221 156 231 240 230 253 192 235 245 215 9 222 201 + + + + + $PROJ_DIR$\..\RT-Thread-1.1.1\src\irq.c + + + BICOMP + 27 + + + ICCARM + 183 + + + + + BICOMP + 201 164 219 221 156 231 240 230 253 192 235 245 215 9 222 + + + ICCARM + 201 164 219 221 156 231 240 230 253 192 235 245 215 9 222 + + + + + $PROJ_DIR$\..\RT-Thread-1.1.1\src\mem.c + + + BICOMP + 131 + + + ICCARM + 11 + + + + + BICOMP + 201 164 219 221 156 231 240 230 253 192 235 245 215 9 222 + + + ICCARM + 201 164 219 221 156 231 240 230 253 192 235 245 215 9 222 + + + + + $PROJ_DIR$\..\RT-Thread-1.1.1\libcpu\arm\cortex-m3\cpuport.c + + + BICOMP + 200 + + + + + $PROJ_DIR$\..\RT-Thread-1.1.1\libcpu\arm\common\backtrace.c + + + BICOMP + 307 + + + + + $PROJ_DIR$\..\RT-Thread-1.1.1\libcpu\arm\common\showmem.c + + + BICOMP + 172 + + + ICCARM + 166 + + + + + $PROJ_DIR$\..\APP\src\cpuusage.c + + + BICOMP + 257 + + + ICCARM + 273 + + + + + ICCARM + 164 219 221 156 231 240 230 253 192 235 245 215 9 222 201 25 + + + + + $PROJ_DIR$\..\RT-Thread-1.1.1\src\kservice.c + + + BICOMP + 115 + + + ICCARM + 118 + + + + + BICOMP + 164 219 221 156 231 240 230 253 192 235 245 215 9 222 201 + + + ICCARM + 164 219 221 156 231 240 230 253 192 235 245 215 9 222 201 + + + + + $PROJ_DIR$\..\RT-Thread-1.1.1\src\clock.c + + + BICOMP + 126 + + + ICCARM + 127 + + + + + ICCARM + 201 164 219 221 156 231 240 230 253 192 235 245 215 9 222 + + + + + $PROJ_DIR$\..\RT-Thread-1.1.1\src\ipc.c + + + BICOMP + 13 + + + ICCARM + 187 + + + + + BICOMP + 164 219 221 156 231 240 230 253 192 235 245 215 9 222 201 + + + ICCARM + 164 219 221 156 231 240 230 253 192 235 245 215 9 222 201 + + + + + $PROJ_DIR$\..\RT-Thread-1.1.1\src\device.c + + + BICOMP + 124 + + + ICCARM + 119 + + + + + ICCARM + 164 219 221 156 231 240 230 253 192 235 245 215 9 222 + + + + + $PROJ_DIR$\..\RT-Thread-1.1.1\libcpu\arm\cortex-m3\context_iar.S AARM - 58 + 34 + + $PROJ_DIR$\..\RT-Thread-1.1.1\src\idle.c + + + BICOMP + 116 + + + ICCARM + 30 + + + + + ICCARM + 201 164 219 221 156 231 240 230 253 192 235 245 215 9 222 + + + + + $PROJ_DIR$\..\RT-Thread-1.1.1\src\thread.c + + + BICOMP + 132 + + + ICCARM + 125 + + + + + BICOMP + 164 219 221 156 231 240 230 253 192 235 245 215 9 222 201 + + + ICCARM + 164 219 221 156 231 240 230 253 192 235 245 215 9 222 201 + + + + + $PROJ_DIR$\Debug\Exe\FreeModbus_Slaver&Master+RTT+STM32.out + + + ILINK + 144 32 24 195 127 317 34 266 273 314 119 30 187 183 118 216 220 205 286 315 284 299 227 194 332 300 326 293 204 259 301 11 213 241 16 122 29 327 242 338 248 150 234 239 249 275 324 129 352 10 303 14 236 269 120 135 261 280 265 272 264 238 271 169 12 211 274 262 278 263 210 267 147 277 22 125 117 342 297 340 322 256 237 137 162 + + + + + $PROJ_DIR$\..\FreeModbus\port\rtt\portserial_m.c + + + BICOMP + 208 + + + ICCARM + 239 + + + + + BICOMP + 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 + + + + + $PROJ_DIR$\..\FreeModbus\port\rtt\portevent.c + + + BICOMP + 151 + + + ICCARM + 248 + + + + + BICOMP + 224 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 223 153 + + + + + $PROJ_DIR$\..\FreeModbus\port\rtt\portserial.c + + + BICOMP + 149 + + + ICCARM + 234 + + + + + BICOMP + 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 336 354 17 + + + ICCARM + 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 336 354 17 + + + + + $PROJ_DIR$\..\FreeModbus\port\rtt\portevent_m.c + + + BICOMP + 244 + + + ICCARM + 150 + + + + + BICOMP + 224 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 223 153 291 + + + + + $PROJ_DIR$\..\BSP\src\usart.c + + + BICOMP + 343 + + + ICCARM + 342 + + + + + BICOMP + 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 341 323 318 221 325 283 156 319 320 17 336 354 + + + ICCARM + 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 71 202 191 173 175 197 184 196 170 171 182 341 323 318 221 325 283 156 319 320 17 336 354 + + + + + $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\serial\serial.c + + + BICOMP + 353 + + + ICCARM + 352 + + + + + BICOMP + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 336 354 + + + ICCARM + 323 318 221 325 283 156 231 240 230 253 192 235 245 319 320 336 354 + + + + + $PROJ_DIR$\..\FreeModbus\port\rtt\porttimer.c + + + BICOMP + 252 + + + ICCARM + 249 + + + + + BICOMP + 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 + + + ICCARM + 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 + + + + + $PROJ_DIR$\..\FreeModbus\port\rtt\porttimer_m.c + + + BICOMP + 226 + + + ICCARM + 275 + + + + + BICOMP + 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 291 + + + ICCARM + 209 71 202 198 193 31 231 240 230 253 192 235 245 247 189 188 167 179 191 173 175 197 184 196 170 171 182 214 323 318 221 325 283 156 319 320 139 138 224 223 153 291 + + + $PROJ_DIR$\..\RT-Thread-1.1.1\libcpu\arm\cortex-m3\cpuport.c ICCARM diff --git a/EWARM/FreeModbus_Slave&Master+RTT+STM32.ewp b/EWARM/FreeModbus_Slave&Master+RTT+STM32.ewp index 68852f8..762fe6e 100644 --- a/EWARM/FreeModbus_Slave&Master+RTT+STM32.ewp +++ b/EWARM/FreeModbus_Slave&Master+RTT+STM32.ewp @@ -1871,6 +1871,9 @@ $PROJ_DIR$\..\RT-Thread-1.2.2\libcpu\arm\cortex-m3\cpuport.c + + $PROJ_DIR$\..\BSP\src\usart.c + CMSIS @@ -1904,13 +1907,13 @@ Port - $PROJ_DIR$\..\FreeModbus\port\portevent_m.c + $PROJ_DIR$\..\FreeModbus\port\rtt\portevent_m.c - $PROJ_DIR$\..\FreeModbus\port\portserial_m.c + $PROJ_DIR$\..\FreeModbus\port\rtt\portserial_m.c - $PROJ_DIR$\..\FreeModbus\port\porttimer_m.c + $PROJ_DIR$\..\FreeModbus\port\rtt\porttimer_m.c $PROJ_DIR$\..\FreeModbus\port\user_mb_app_m.c @@ -1958,13 +1961,13 @@ $PROJ_DIR$\..\FreeModbus\port\port.c - $PROJ_DIR$\..\FreeModbus\port\portevent.c + $PROJ_DIR$\..\FreeModbus\port\rtt\portevent.c - $PROJ_DIR$\..\FreeModbus\port\portserial.c + $PROJ_DIR$\..\FreeModbus\port\rtt\portserial.c - $PROJ_DIR$\..\FreeModbus\port\porttimer.c + $PROJ_DIR$\..\FreeModbus\port\rtt\porttimer.c $PROJ_DIR$\..\FreeModbus\port\user_mb_app.c @@ -1990,6 +1993,9 @@ $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\ringbuffer.c + + $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\serial\serial.c + $PROJ_DIR$\..\RT-Thread-1.2.2\components\drivers\src\wrokqueue.c diff --git a/EWARM/settings/FreeModbus_Slave&Master+RTT+STM32.dbgdt b/EWARM/settings/FreeModbus_Slave&Master+RTT+STM32.dbgdt index 0da9e80..23e0239 100644 --- a/EWARM/settings/FreeModbus_Slave&Master+RTT+STM32.dbgdt +++ b/EWARM/settings/FreeModbus_Slave&Master+RTT+STM32.dbgdt @@ -39,7 +39,7 @@ - + TabID-27820-6871 @@ -55,7 +55,7 @@ TabID-23458-14555Find All DeclarationsFind-All-Declarations - 0 + 0 TabID-5800-6874 @@ -67,20 +67,20 @@ - 0TabID-15165-9557Live WatchStaticWatch0 + 0TabID-15165-9557Live WatchStaticWatch0 - TextEditor$WS_DIR$\..\APP\src\app_task.c000003015571557TextEditor$WS_DIR$\..\APP\src\app.c0000002525TextEditor$WS_DIR$\..\RT-Thread-1.2.2\src\cpuusage.c00000086086020100000010000001 + TextEditor$WS_DIR$\..\APP\src\app_task.c00000014921492TextEditor$WS_DIR$\..\APP\src\app.c000000252510100000010000001 - iaridepm.enu1debuggergui.enu1-2-2703241-2-29919758929203723144643729059-2-2703477-2-2200200119048206825285119729059-2-21951682-2-21684197100238120372358929203723 + iaridepm.enu1debuggergui.enu1-2-2703241-2-29919758929203723144643729059-2-2703477-2-2200200119048206825285119729059-2-21951682-2-21684197100238120372358929203723 diff --git a/EWARM/settings/FreeModbus_Slave&Master+RTT+STM32.dni b/EWARM/settings/FreeModbus_Slave&Master+RTT+STM32.dni index 3a754c8..f4ff1db 100644 --- a/EWARM/settings/FreeModbus_Slave&Master+RTT+STM32.dni +++ b/EWARM/settings/FreeModbus_Slave&Master+RTT+STM32.dni @@ -9,7 +9,7 @@ TriggerName=main LimitSize=0 ByteLimit=50 [DebugChecksum] -Checksum=911493072 +Checksum=-1153624826 [Exceptions] StopOnUncaught=_ 0 StopOnThrow=_ 0 diff --git a/EWARM/settings/FreeModbus_Slave&Master+RTT+STM32.wsdt b/EWARM/settings/FreeModbus_Slave&Master+RTT+STM32.wsdt index 61595af..c180396 100644 --- a/EWARM/settings/FreeModbus_Slave&Master+RTT+STM32.wsdt +++ b/EWARM/settings/FreeModbus_Slave&Master+RTT+STM32.wsdt @@ -17,7 +17,7 @@ 2012153248119162258082994 - + TabID-30370-1297 @@ -29,7 +29,7 @@ - 0TabID-24390-6730BuildBuildTabID-3984-13619Find All DeclarationsFind-All-Declarations0 + 0TabID-24390-6730BuildBuildTabID-3984-13619Find All DeclarationsFind-All-Declarations0 @@ -42,7 +42,7 @@ - iaridepm.enu1-2-2738270-2-23387120119073423161905765253-2-21841682-2-21684186100238119234720119073423 + iaridepm.enu1-2-2738270-2-23387120119073423161905765253-2-21841682-2-21684186100238119234720119073423 diff --git a/FreeModbus/port/port.h b/FreeModbus/port/port.h index 87a776f..70813a8 100644 --- a/FreeModbus/port/port.h +++ b/FreeModbus/port/port.h @@ -35,9 +35,9 @@ #define PR_END_EXTERN_C } //TODO ÔÝʱÏÈдB13Òý½Å£¬µÈ×éÍø²âÊÔʱÔÙÈ·ÈÏ -#define SLAVE_RS485_SEND_MODE GPIO_SetBits(GPIOB,GPIO_Pin_13) +#define SLAVE_RS485_TRANS_MODE GPIO_SetBits(GPIOB,GPIO_Pin_13) #define SLAVE_RS485_RECEIVE_MODE GPIO_ResetBits(GPIOB,GPIO_Pin_13) -#define MASTER_RS485_SEND_MODE GPIO_SetBits(GPIOB,GPIO_Pin_13) +#define MASTER_RS485_TRANS_MODE GPIO_SetBits(GPIOB,GPIO_Pin_13) #define MASTER_RS485_RECEIVE_MODE GPIO_ResetBits(GPIOB,GPIO_Pin_13) #define ENTER_CRITICAL_SECTION() EnterCriticalSection() diff --git a/FreeModbus/port/portserial.c b/FreeModbus/port/portserial.c deleted file mode 100644 index f246284..0000000 --- a/FreeModbus/port/portserial.c +++ /dev/null @@ -1,196 +0,0 @@ -/* - * FreeModbus Libary: STM32 Port - * Copyright (C) 2013 Armink - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * This library is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - * Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with this library; if not, write to the Free Software - * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - * - * File: $Id: portserial.c,v 1.60 2013/08/13 15:07:05 Armink $ - */ - -#include "port.h" - -/* ----------------------- Modbus includes ----------------------------------*/ -#include "mb.h" -#include "mbport.h" -/* ----------------------- static functions ---------------------------------*/ -static void prvvUARTTxReadyISR(void); -static void prvvUARTRxISR(void); -/* ----------------------- Start implementation -----------------------------*/ - -void vMBPortSerialEnable(BOOL xRxEnable, BOOL xTxEnable) -{ - if (xRxEnable) - { - /* 485ͨÐÅʱ£¬µÈ´ý´®¿ÚÒÆλ¼Ä´æÆ÷ÖеÄÊý¾Ý·¢ËÍÍê³Éºó£¬ÔÙȥʹÄÜ485µÄ½ÓÊÕ¡¢Ê§ÄÜ485µÄ·¢ËÍ*/ - while (!USART_GetFlagStatus(USART1,USART_FLAG_TC)); - SLAVE_RS485_RECEIVE_MODE; - USART_ITConfig(USART1, USART_IT_RXNE, ENABLE); - } - else - { - SLAVE_RS485_SEND_MODE; - USART_ITConfig(USART1, USART_IT_RXNE, DISABLE); - } - if (xTxEnable) - { - USART_ITConfig(USART1, USART_IT_TXE, ENABLE); - } - else - { - USART_ITConfig(USART1, USART_IT_TXE, DISABLE); - } -} - -void vMBPortClose(void) -{ - USART_ITConfig(USART1, USART_IT_TXE | USART_IT_RXNE, DISABLE); - USART_Cmd(USART1, DISABLE); -} -//ĬÈÏÒ»¸ö´Ó»ú ´®¿Ú1 ²¨ÌØÂÊ¿ÉÉèÖà Ææż¼ìÑé¿ÉÉèÖà -BOOL xMBPortSerialInit(UCHAR ucPORT, ULONG ulBaudRate, UCHAR ucDataBits, - eMBParity eParity) -{ - GPIO_InitTypeDef GPIO_InitStructure; - USART_InitTypeDef USART_InitStructure; - NVIC_InitTypeDef NVIC_InitStructure; - //======================ʱÖÓ³õʼ»¯======================================= - RCC_APB2PeriphClockCmd( - RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB | RCC_APB2Periph_USART1, - ENABLE); - //======================IO³õʼ»¯======================================= - //USART1_TX - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9; - GPIO_Init(GPIOA, &GPIO_InitStructure); - //USART1_RX - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10; - GPIO_Init(GPIOA, &GPIO_InitStructure); - //ÅäÖÃ485·¢ËͺͽÓÊÕģʽ -// TODO ÔÝʱÏÈдB13 µÈÖ®ºó×éÍø²âÊÔʱÔÙÐÞ¸Ä - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13; - GPIO_Init(GPIOB, &GPIO_InitStructure); - //======================´®¿Ú³õʼ»¯======================================= - USART_InitStructure.USART_BaudRate = ulBaudRate; - //ÉèÖÃУÑéģʽ - switch (eParity) - { - case MB_PAR_NONE: //ÎÞУÑé - USART_InitStructure.USART_Parity = USART_Parity_No; - USART_InitStructure.USART_WordLength = USART_WordLength_8b; - break; - case MB_PAR_ODD: //ÆæУÑé - USART_InitStructure.USART_Parity = USART_Parity_Odd; - USART_InitStructure.USART_WordLength = USART_WordLength_9b; - break; - case MB_PAR_EVEN: //żУÑé - USART_InitStructure.USART_Parity = USART_Parity_Even; - USART_InitStructure.USART_WordLength = USART_WordLength_9b; - break; - default: - return FALSE; - } - - USART_InitStructure.USART_StopBits = USART_StopBits_1; - USART_InitStructure.USART_HardwareFlowControl = - USART_HardwareFlowControl_None; - USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx; - if (ucPORT != 1) - return FALSE; - - ENTER_CRITICAL_SECTION(); //¹ØÈ«¾ÖÖÐ¶Ï - - USART_Init(USART1, &USART_InitStructure); - USART_ITConfig(USART1, USART_IT_RXNE, ENABLE); - USART_Cmd(USART1, ENABLE); - - //=====================Öжϳõʼ»¯====================================== - //ÉèÖÃNVICÓÅÏȼ¶·Ö×éΪGroup2£º0-3ÇÀռʽÓÅÏȼ¶£¬0-3µÄÏìӦʽÓÅÏȼ¶ - NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2); - NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1; - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); - - EXIT_CRITICAL_SECTION(); //¿ªÈ«¾ÖÖÐ¶Ï - - return TRUE; -} - -BOOL xMBPortSerialPutByte(CHAR ucByte) -{ - USART_SendData(USART1, ucByte); - return TRUE; -} - -BOOL xMBPortSerialGetByte(CHAR * pucByte) -{ - *pucByte = USART_ReceiveData(USART1); - return TRUE; -} - -/* - * Create an interrupt handler for the transmit buffer empty interrupt - * (or an equivalent) for your target processor. This function should then - * call pxMBFrameCBTransmitterEmpty( ) which tells the protocol stack that - * a new character can be sent. The protocol stack will then call - * xMBPortSerialPutByte( ) to send the character. - */ -void prvvUARTTxReadyISR(void) -{ - pxMBFrameCBTransmitterEmpty(); -} - -/* - * Create an interrupt handler for the receive interrupt for your target - * processor. This function should then call pxMBFrameCBByteReceived( ). The - * protocol stack will then call xMBPortSerialGetByte( ) to retrieve the - * character. - */ -void prvvUARTRxISR(void) -{ - pxMBFrameCBByteReceived(); -} -/******************************************************************************* - * Function Name : USART1_IRQHandler - * Description : This function handles USART1 global interrupt request. - * Input : None - * Output : None - * Return : None - *******************************************************************************/ -void USART1_IRQHandler(void) -{ - rt_interrupt_enter(); - //Òç³ö´íÎó - if (USART_GetFlagStatus(USART1, USART_FLAG_ORE) == SET) - { - prvvUARTRxISR(); - } - //½ÓÊÕÖÐ¶Ï - if (USART_GetITStatus(USART1, USART_IT_RXNE) == SET) - { - USART_ClearITPendingBit(USART1, USART_IT_RXNE); - prvvUARTRxISR(); - } - //·¢ËÍÖÐ¶Ï - if (USART_GetITStatus(USART1, USART_IT_TXE) == SET) - { - prvvUARTTxReadyISR(); - } - rt_interrupt_leave(); -} diff --git a/FreeModbus/port/portserial_m.c b/FreeModbus/port/portserial_m.c deleted file mode 100644 index 57f8aee..0000000 --- a/FreeModbus/port/portserial_m.c +++ /dev/null @@ -1,199 +0,0 @@ -/* - * FreeModbus Libary: STM32 Port - * Copyright (C) 2013 Armink - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * This library is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - * Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with this library; if not, write to the Free Software - * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - * - * File: $Id: portserial_m.c,v 1.60 2013/08/13 15:07:05 Armink add Master Functions $ - */ - -#include "port.h" - -/* ----------------------- Modbus includes ----------------------------------*/ -#include "mb.h" -#include "mbport.h" - -#if MB_MASTER_RTU_ENABLED > 0 || MB_MASTER_ASCII_ENABLED > 0 -/* ----------------------- static functions ---------------------------------*/ -static void prvvUARTTxReadyISR(void); -static void prvvUARTRxISR(void); -/* ----------------------- Start implementation -----------------------------*/ - -void vMBMasterPortSerialEnable(BOOL xRxEnable, BOOL xTxEnable) -{ - if (xRxEnable) - { - /* 485ͨÐÅʱ£¬µÈ´ý´®¿ÚÒÆλ¼Ä´æÆ÷ÖеÄÊý¾Ý·¢ËÍÍê³Éºó£¬ÔÙȥʹÄÜ485µÄ½ÓÊÕ¡¢Ê§ÄÜ485µÄ·¢ËÍ*/ - while (!USART_GetFlagStatus(USART2,USART_FLAG_TC)); - MASTER_RS485_RECEIVE_MODE; - USART_ITConfig(USART2, USART_IT_RXNE, ENABLE); - } - else - { - MASTER_RS485_SEND_MODE; - USART_ITConfig(USART2, USART_IT_RXNE, DISABLE); - } - if (xTxEnable) - { - USART_ITConfig(USART2, USART_IT_TXE, ENABLE); - } - else - { - USART_ITConfig(USART2, USART_IT_TXE, DISABLE); - } -} - -void vMBMasterPortClose(void) -{ - USART_ITConfig(USART2, USART_IT_TXE | USART_IT_RXNE, DISABLE); - USART_Cmd(USART2, DISABLE); -} -//ĬÈÏÒ»¸öÖ÷»ú ´®¿Ú2 ²¨ÌØÂÊ¿ÉÉèÖà Ææż¼ìÑé¿ÉÉèÖà -BOOL xMBMasterPortSerialInit(UCHAR ucPORT, ULONG ulBaudRate, UCHAR ucDataBits, - eMBParity eParity) -{ - GPIO_InitTypeDef GPIO_InitStructure; - USART_InitTypeDef USART_InitStructure; - NVIC_InitTypeDef NVIC_InitStructure; - //======================ʱÖÓ³õʼ»¯======================================= - RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB, ENABLE); - RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE); - //======================IO³õʼ»¯======================================= - //USART2_TX - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2; - GPIO_Init(GPIOA, &GPIO_InitStructure); - //USART2_RX - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3; - GPIO_Init(GPIOA, &GPIO_InitStructure); - //ÅäÖÃ485·¢ËͺͽÓÊÕģʽ -// TODO ÔÝʱÏÈдB13 µÈÖ®ºó×éÍø²âÊÔʱÔÙÐÞ¸Ä - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; - GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13; - GPIO_Init(GPIOB, &GPIO_InitStructure); - //======================´®¿Ú³õʼ»¯======================================= - USART_InitStructure.USART_BaudRate = ulBaudRate; - //ÉèÖÃУÑéģʽ - switch (eParity) - { - case MB_PAR_NONE: //ÎÞУÑé - USART_InitStructure.USART_Parity = USART_Parity_No; - USART_InitStructure.USART_WordLength = USART_WordLength_8b; - break; - case MB_PAR_ODD: //ÆæУÑé - USART_InitStructure.USART_Parity = USART_Parity_Odd; - USART_InitStructure.USART_WordLength = USART_WordLength_9b; - break; - case MB_PAR_EVEN: //żУÑé - USART_InitStructure.USART_Parity = USART_Parity_Even; - USART_InitStructure.USART_WordLength = USART_WordLength_9b; - break; - default: - return FALSE; - } - - USART_InitStructure.USART_StopBits = USART_StopBits_1; - USART_InitStructure.USART_HardwareFlowControl = - USART_HardwareFlowControl_None; - USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx; - if (ucPORT != 2) - return FALSE; - - ENTER_CRITICAL_SECTION(); //¹ØÈ«¾ÖÖÐ¶Ï - - USART_Init(USART2, &USART_InitStructure); - USART_ITConfig(USART2, USART_IT_RXNE, ENABLE); - USART_Cmd(USART2, ENABLE); - - //=====================Öжϳõʼ»¯====================================== - //ÉèÖÃNVICÓÅÏȼ¶·Ö×éΪGroup2£º0-3ÇÀռʽÓÅÏȼ¶£¬0-3µÄÏìӦʽÓÅÏȼ¶ - NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2); - NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); - - EXIT_CRITICAL_SECTION(); //¿ªÈ«¾ÖÖÐ¶Ï - - return TRUE; -} - -BOOL xMBMasterPortSerialPutByte(CHAR ucByte) -{ - USART_SendData(USART2, ucByte); - return TRUE; -} - -BOOL xMBMasterPortSerialGetByte(CHAR * pucByte) -{ - *pucByte = USART_ReceiveData(USART2); - return TRUE; -} - -/* - * Create an interrupt handler for the transmit buffer empty interrupt - * (or an equivalent) for your target processor. This function should then - * call pxMBFrameCBTransmitterEmpty( ) which tells the protocol stack that - * a new character can be sent. The protocol stack will then call - * xMBPortSerialPutByte( ) to send the character. - */ -void prvvUARTTxReadyISR(void) -{ - pxMBMasterFrameCBTransmitterEmpty(); -} - -/* - * Create an interrupt handler for the receive interrupt for your target - * processor. This function should then call pxMBFrameCBByteReceived( ). The - * protocol stack will then call xMBPortSerialGetByte( ) to retrieve the - * character. - */ -void prvvUARTRxISR(void) -{ - pxMBMasterFrameCBByteReceived(); -} -/******************************************************************************* - * Function Name : USART2_IRQHandler - * Description : This function handles USART2 global interrupt request. - * Input : None - * Output : None - * Return : None - *******************************************************************************/ -void USART2_IRQHandler(void) -{ - rt_interrupt_enter(); - //Òç³ö´íÎó - if (USART_GetFlagStatus(USART2, USART_FLAG_ORE) == SET) - { - prvvUARTRxISR(); - } - //½ÓÊÕÖÐ¶Ï - if (USART_GetITStatus(USART2, USART_IT_RXNE) == SET) - { - USART_ClearITPendingBit(USART2, USART_IT_RXNE); - prvvUARTRxISR(); - } - //·¢ËÍÖÐ¶Ï - if (USART_GetITStatus(USART2, USART_IT_TXE) == SET) - { - prvvUARTTxReadyISR(); - } - rt_interrupt_leave(); -} - -#endif diff --git a/FreeModbus/port/porttimer.c b/FreeModbus/port/porttimer.c deleted file mode 100644 index b7b74ce..0000000 --- a/FreeModbus/port/porttimer.c +++ /dev/null @@ -1,107 +0,0 @@ -/* - * FreeModbus Libary: STM32 Port - * Copyright (C) 2013 Armink - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * This library is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - * Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with this library; if not, write to the Free Software - * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - * - * File: $Id: porttimer.c,v 1.60 2013/08/13 15:07:05 Armink $ - */ - -/* ----------------------- Platform includes --------------------------------*/ -#include "port.h" - -/* ----------------------- Modbus includes ----------------------------------*/ -#include "mb.h" -#include "mbport.h" - -/* ----------------------- static functions ---------------------------------*/ -static void prvvTIMERExpiredISR(void); - -/* ----------------------- Start implementation -----------------------------*/ -BOOL xMBPortTimersInit(USHORT usTim1Timerout50us) -{ - - uint16_t PrescalerValue = 0; - TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; - NVIC_InitTypeDef NVIC_InitStructure; - //====================================ʱÖÓ³õʼ»¯=========================== - //ʹÄܶ¨Ê±Æ÷3ʱÖÓ - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM3, ENABLE); - //====================================¶¨Ê±Æ÷³õʼ»¯=========================== - //¶¨Ê±Æ÷ʱ¼ä»ùÅäÖÃ˵Ã÷ - //HCLKΪ72MHz£¬APB1¾­¹ý2·ÖƵΪ36MHz - //TIM3µÄʱÖÓ±¶ÆµºóΪ72MHz£¨Ó²¼þ×Ô¶¯±¶Æµ,´ïµ½×î´ó£© - //TIM3µÄ·ÖƵϵÊýΪ3599£¬Ê±¼ä»ùƵÂÊΪ72 / (1 + Prescaler) = 20KHz,»ù׼Ϊ50us - //TIM×î´ó¼ÆÊýֵΪusTim1Timerout50u - - PrescalerValue = (uint16_t) (SystemCoreClock / 20000) - 1; - //¶¨Ê±Æ÷1³õʼ»¯ - TIM_TimeBaseStructure.TIM_Period = (uint16_t) usTim1Timerout50us; - TIM_TimeBaseStructure.TIM_Prescaler = PrescalerValue; - TIM_TimeBaseStructure.TIM_ClockDivision = 0; - TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; - TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure); - //ԤװÔØʹÄÜ - TIM_ARRPreloadConfig(TIM3, ENABLE); - //====================================Öжϳõʼ»¯=========================== - //ÉèÖÃNVICÓÅÏȼ¶·Ö×éΪGroup2£º0-3ÇÀռʽÓÅÏȼ¶£¬0-3µÄÏìӦʽÓÅÏȼ¶ - NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2); - NVIC_InitStructure.NVIC_IRQChannel = TIM3_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1; - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); - //Çå³ýÒç³öÖжϱê־λ - TIM_ClearITPendingBit(TIM3, TIM_IT_Update); - //¶¨Ê±Æ÷3Òç³öÖÐ¶Ï¹Ø±Õ - TIM_ITConfig(TIM3, TIM_IT_Update, DISABLE); - //¶¨Ê±Æ÷3½ûÄÜ - TIM_Cmd(TIM3, DISABLE); - return TRUE; -} - -void vMBPortTimersEnable() -{ - TIM_ClearITPendingBit(TIM3, TIM_IT_Update); - TIM_ITConfig(TIM3, TIM_IT_Update, ENABLE); - TIM_SetCounter(TIM3, 0); - TIM_Cmd(TIM3, ENABLE); -} - -void vMBPortTimersDisable() -{ - TIM_ClearITPendingBit(TIM3, TIM_IT_Update); - TIM_ITConfig(TIM3, TIM_IT_Update, DISABLE); - TIM_SetCounter(TIM3, 0); - TIM_Cmd(TIM3, DISABLE); -} - -void prvvTIMERExpiredISR(void) -{ - (void) pxMBPortCBTimerExpired(); -} - -void TIM3_IRQHandler(void) -{ - rt_interrupt_enter(); - if (TIM_GetITStatus(TIM3, TIM_IT_Update) != RESET) - { - - TIM_ClearFlag(TIM3, TIM_FLAG_Update); //ÇåÖжϱê¼Ç - TIM_ClearITPendingBit(TIM3, TIM_IT_Update); //Çå³ý¶¨Ê±Æ÷T3Òç³öÖжϱê־λ - prvvTIMERExpiredISR(); - } - rt_interrupt_leave(); -} diff --git a/FreeModbus/port/porttimer_m.c b/FreeModbus/port/porttimer_m.c deleted file mode 100644 index 1630e09..0000000 --- a/FreeModbus/port/porttimer_m.c +++ /dev/null @@ -1,157 +0,0 @@ -/* - * FreeModbus Libary: STM32 Port - * Copyright (C) 2013 Armink - * - * This library is free software; you can redistribute it and/or - * modify it under the terms of the GNU Lesser General Public - * License as published by the Free Software Foundation; either - * version 2.1 of the License, or (at your option) any later version. - * - * This library is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU - * Lesser General Public License for more details. - * - * You should have received a copy of the GNU Lesser General Public - * License along with this library; if not, write to the Free Software - * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA - * - * File: $Id: porttimer_m.c,v 1.60 2013/08/13 15:07:05 Armink add Master Functions$ - */ - -/* ----------------------- Platform includes --------------------------------*/ -#include "port.h" - -/* ----------------------- Modbus includes ----------------------------------*/ -#include "mb.h" -#include "mb_m.h" -#include "mbport.h" - -#if MB_MASTER_RTU_ENABLED > 0 || MB_MASTER_ASCII_ENABLED > 0 -/* ----------------------- Variables ----------------------------------------*/ -static USHORT usT35TimeOut50us; -static USHORT usPrescalerValue = 0; - -/* ----------------------- static functions ---------------------------------*/ -static void prvvTIMERExpiredISR(void); - -/* ----------------------- Start implementation -----------------------------*/ -BOOL xMBMasterPortTimersInit(USHORT usTimeOut50us) -{ - NVIC_InitTypeDef NVIC_InitStructure; - //====================================ʱÖÓ³õʼ»¯=========================== - //ʹÄܶ¨Ê±Æ÷2ʱÖÓ - RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); - //====================================¶¨Ê±Æ÷³õʼ»¯=========================== - //¶¨Ê±Æ÷ʱ¼ä»ùÅäÖÃ˵Ã÷ - //HCLKΪ72MHz£¬APB1¾­¹ý2·ÖƵΪ36MHz - //TIM2µÄʱÖÓ±¶ÆµºóΪ72MHz£¨Ó²¼þ×Ô¶¯±¶Æµ,´ïµ½×î´ó£© - //TIM2µÄ·ÖƵϵÊýΪ3599£¬Ê±¼ä»ùƵÂÊΪ72 / (1 + Prescaler) = 20KHz,»ù׼Ϊ50us - //TIM×î´ó¼ÆÊýֵΪusTim1Timerout50u - usPrescalerValue = (uint16_t) (SystemCoreClock / 20000) - 1; - //±£´æT35¶¨Ê±Æ÷¼ÆÊýÖµ - usT35TimeOut50us = usTimeOut50us; - - //ԤװÔØʹÄÜ - TIM_ARRPreloadConfig(TIM2, ENABLE); - //====================================Öжϳõʼ»¯=========================== - //ÉèÖÃNVICÓÅÏȼ¶·Ö×éΪGroup2£º0-3ÇÀռʽÓÅÏȼ¶£¬0-3µÄÏìӦʽÓÅÏȼ¶ - NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2); - NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQn; - NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1; - NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; - NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; - NVIC_Init(&NVIC_InitStructure); - //Çå³ýÒç³öÖжϱê־λ - TIM_ClearITPendingBit(TIM2, TIM_IT_Update); - //¶¨Ê±Æ÷3Òç³öÖÐ¶Ï¹Ø±Õ - TIM_ITConfig(TIM2, TIM_IT_Update, DISABLE); - //¶¨Ê±Æ÷3½ûÄÜ - TIM_Cmd(TIM2, DISABLE); - return TRUE; -} - -void vMBMasterPortTimersT35Enable() -{ - TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; - - /* Set current timer mode,don't change it.*/ - vMBMasterSetCurTimerMode(MB_TMODE_T35); - - TIM_TimeBaseStructure.TIM_Prescaler = usPrescalerValue; - TIM_TimeBaseStructure.TIM_ClockDivision = 0; - TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; - TIM_TimeBaseStructure.TIM_Period = (uint16_t) usT35TimeOut50us; - TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure); - - TIM_ClearITPendingBit(TIM2, TIM_IT_Update); - TIM_ITConfig(TIM2, TIM_IT_Update, ENABLE); - TIM_SetCounter(TIM2, 0); - TIM_Cmd(TIM2, ENABLE); -} - -void vMBMasterPortTimersConvertDelayEnable() -{ - TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; - - /* Set current timer mode,don't change it.*/ - vMBMasterSetCurTimerMode(MB_TMODE_CONVERT_DELAY); - - TIM_TimeBaseStructure.TIM_Prescaler = usPrescalerValue; - TIM_TimeBaseStructure.TIM_ClockDivision = 0; - TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; - TIM_TimeBaseStructure.TIM_Period = (uint16_t)(MB_MASTER_DELAY_MS_CONVERT * 1000 / 50); - TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure); - - TIM_ClearITPendingBit(TIM2, TIM_IT_Update); - TIM_ITConfig(TIM2, TIM_IT_Update, ENABLE); - TIM_SetCounter(TIM2, 0); - TIM_Cmd(TIM2, ENABLE); -} - -void vMBMasterPortTimersRespondTimeoutEnable() -{ - TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; - - /* Set current timer mode,don't change it.*/ - vMBMasterSetCurTimerMode(MB_TMODE_RESPOND_TIMEOUT); - - TIM_TimeBaseStructure.TIM_Prescaler = usPrescalerValue; - TIM_TimeBaseStructure.TIM_ClockDivision = 0; - TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; - TIM_TimeBaseStructure.TIM_Period = (uint16_t)(MB_MASTER_TIMEOUT_MS_RESPOND * 1000 / 50); - TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure); - - TIM_ClearITPendingBit(TIM2, TIM_IT_Update); - TIM_ITConfig(TIM2, TIM_IT_Update, ENABLE); - TIM_SetCounter(TIM2, 0); - TIM_Cmd(TIM2, ENABLE); -} - -void vMBMasterPortTimersDisable() -{ - TIM_ClearITPendingBit(TIM2, TIM_IT_Update); - TIM_ITConfig(TIM2, TIM_IT_Update, DISABLE); - TIM_SetCounter(TIM2, 0); - TIM_Cmd(TIM2, DISABLE); -} - -void prvvTIMERExpiredISR(void) -{ - (void) pxMBMasterPortCBTimerExpired(); -} - -void TIM2_IRQHandler(void) -{ - rt_interrupt_enter(); - if (TIM_GetITStatus(TIM2, TIM_IT_Update) != RESET) - { - - TIM_ClearFlag(TIM2, TIM_FLAG_Update); //ÇåÖжϱê¼Ç - TIM_ClearITPendingBit(TIM2, TIM_IT_Update); //Çå³ý¶¨Ê±Æ÷TIM2Òç³öÖжϱê־λ - prvvTIMERExpiredISR(); - } - rt_interrupt_leave(); -} - -#endif diff --git a/FreeModbus/port/portevent.c b/FreeModbus/port/rtt/portevent.c similarity index 69% rename from FreeModbus/port/portevent.c rename to FreeModbus/port/rtt/portevent.c index 4a3c2f1..f1c51a2 100644 --- a/FreeModbus/port/portevent.c +++ b/FreeModbus/port/rtt/portevent.c @@ -29,14 +29,14 @@ static struct rt_event xSlaveOsEvent; BOOL xMBPortEventInit( void ) { - rt_event_init(&xSlaveOsEvent,"slave event",RT_IPC_FLAG_PRIO); + rt_event_init(&xSlaveOsEvent,"slave event",RT_IPC_FLAG_PRIO); return TRUE; } BOOL xMBPortEventPost( eMBEventType eEvent ) { - rt_event_send(&xSlaveOsEvent, eEvent); + rt_event_send(&xSlaveOsEvent, eEvent); return TRUE; } @@ -45,24 +45,24 @@ xMBPortEventGet( eMBEventType * eEvent ) { rt_uint32_t recvedEvent; /* waiting forever OS event */ - rt_event_recv(&xSlaveOsEvent, - EV_READY | EV_FRAME_RECEIVED | EV_EXECUTE | EV_FRAME_SENT, - RT_EVENT_FLAG_OR | RT_EVENT_FLAG_CLEAR, RT_WAITING_FOREVER, - &recvedEvent); - switch (recvedEvent) - { - case EV_READY: - *eEvent = EV_READY; - break; - case EV_FRAME_RECEIVED: - *eEvent = EV_FRAME_RECEIVED; - break; - case EV_EXECUTE: - *eEvent = EV_EXECUTE; - break; - case EV_FRAME_SENT: - *eEvent = EV_FRAME_SENT; - break; - } + rt_event_recv(&xSlaveOsEvent, + EV_READY | EV_FRAME_RECEIVED | EV_EXECUTE | EV_FRAME_SENT, + RT_EVENT_FLAG_OR | RT_EVENT_FLAG_CLEAR, RT_WAITING_FOREVER, + &recvedEvent); + switch (recvedEvent) + { + case EV_READY: + *eEvent = EV_READY; + break; + case EV_FRAME_RECEIVED: + *eEvent = EV_FRAME_RECEIVED; + break; + case EV_EXECUTE: + *eEvent = EV_EXECUTE; + break; + case EV_FRAME_SENT: + *eEvent = EV_FRAME_SENT; + break; + } return TRUE; } diff --git a/FreeModbus/port/portevent_m.c b/FreeModbus/port/rtt/portevent_m.c similarity index 61% rename from FreeModbus/port/portevent_m.c rename to FreeModbus/port/rtt/portevent_m.c index 77fe79c..76ac86d 100644 --- a/FreeModbus/port/portevent_m.c +++ b/FreeModbus/port/rtt/portevent_m.c @@ -34,14 +34,14 @@ static struct rt_event xMasterOsEvent; BOOL xMBMasterPortEventInit( void ) { - rt_event_init(&xMasterOsEvent,"master event",RT_IPC_FLAG_PRIO); + rt_event_init(&xMasterOsEvent,"master event",RT_IPC_FLAG_PRIO); return TRUE; } BOOL xMBMasterPortEventPost( eMBMasterEventType eEvent ) { - rt_event_send(&xMasterOsEvent, eEvent); + rt_event_send(&xMasterOsEvent, eEvent); return TRUE; } @@ -50,30 +50,30 @@ xMBMasterPortEventGet( eMBMasterEventType * eEvent ) { rt_uint32_t recvedEvent; /* waiting forever OS event */ - rt_event_recv(&xMasterOsEvent, - EV_MASTER_READY | EV_MASTER_FRAME_RECEIVED | EV_MASTER_EXECUTE | - EV_MASTER_FRAME_SENT | EV_MASTER_ERROR_PROCESS, - RT_EVENT_FLAG_OR | RT_EVENT_FLAG_CLEAR, RT_WAITING_FOREVER, - &recvedEvent); - /* the enum type couldn't convert to int type */ - switch (recvedEvent) - { - case EV_MASTER_READY: - *eEvent = EV_MASTER_READY; - break; - case EV_MASTER_FRAME_RECEIVED: - *eEvent = EV_MASTER_FRAME_RECEIVED; - break; - case EV_MASTER_EXECUTE: - *eEvent = EV_MASTER_EXECUTE; - break; - case EV_MASTER_FRAME_SENT: - *eEvent = EV_MASTER_FRAME_SENT; - break; - case EV_MASTER_ERROR_PROCESS: - *eEvent = EV_MASTER_ERROR_PROCESS; - break; - } + rt_event_recv(&xMasterOsEvent, + EV_MASTER_READY | EV_MASTER_FRAME_RECEIVED | EV_MASTER_EXECUTE | + EV_MASTER_FRAME_SENT | EV_MASTER_ERROR_PROCESS, + RT_EVENT_FLAG_OR | RT_EVENT_FLAG_CLEAR, RT_WAITING_FOREVER, + &recvedEvent); + /* the enum type couldn't convert to int type */ + switch (recvedEvent) + { + case EV_MASTER_READY: + *eEvent = EV_MASTER_READY; + break; + case EV_MASTER_FRAME_RECEIVED: + *eEvent = EV_MASTER_FRAME_RECEIVED; + break; + case EV_MASTER_EXECUTE: + *eEvent = EV_MASTER_EXECUTE; + break; + case EV_MASTER_FRAME_SENT: + *eEvent = EV_MASTER_FRAME_SENT; + break; + case EV_MASTER_ERROR_PROCESS: + *eEvent = EV_MASTER_ERROR_PROCESS; + break; + } return TRUE; } /** @@ -83,7 +83,7 @@ xMBMasterPortEventGet( eMBMasterEventType * eEvent ) */ void vMBMasterOsResInit( void ) { - rt_sem_init(&xMasterRunRes, "master res", 0x01 , RT_IPC_FLAG_PRIO); + rt_sem_init(&xMasterRunRes, "master res", 0x01 , RT_IPC_FLAG_PRIO); } /** @@ -96,8 +96,8 @@ void vMBMasterOsResInit( void ) */ BOOL xMBMasterRunResTake( LONG lTimeOut ) { - /*If waiting time is -1 .It will wait forever */ - return rt_sem_take(&xMasterRunRes, lTimeOut) ? FALSE : TRUE ; + /*If waiting time is -1 .It will wait forever */ + return rt_sem_take(&xMasterRunRes, lTimeOut) ? FALSE : TRUE ; } /** @@ -107,8 +107,8 @@ BOOL xMBMasterRunResTake( LONG lTimeOut ) */ void vMBMasterRunResRelease( void ) { - /* release resource */ - rt_sem_release(&xMasterRunRes); + /* release resource */ + rt_sem_release(&xMasterRunRes); } /** @@ -122,14 +122,14 @@ void vMBMasterRunResRelease( void ) * */ void vMBMasterErrorCBRespondTimeout(UCHAR ucDestAddress, const UCHAR* pucPDUData, - USHORT ucPDULength) { - /** - * @note This code is use OS's event mechanism for modbus master protocol stack. - * If you don't use OS, you can change it. - */ - rt_event_send(&xMasterOsEvent, EV_MASTER_ERROR_RESPOND_TIMEOUT); + USHORT ucPDULength) { + /** + * @note This code is use OS's event mechanism for modbus master protocol stack. + * If you don't use OS, you can change it. + */ + rt_event_send(&xMasterOsEvent, EV_MASTER_ERROR_RESPOND_TIMEOUT); - /* You can add your code under here. */ + /* You can add your code under here. */ } @@ -144,14 +144,14 @@ void vMBMasterErrorCBRespondTimeout(UCHAR ucDestAddress, const UCHAR* pucPDUData * */ void vMBMasterErrorCBReceiveData(UCHAR ucDestAddress, const UCHAR* pucPDUData, - USHORT ucPDULength) { - /** - * @note This code is use OS's event mechanism for modbus master protocol stack. - * If you don't use OS, you can change it. - */ - rt_event_send(&xMasterOsEvent, EV_MASTER_ERROR_RECEIVE_DATA); + USHORT ucPDULength) { + /** + * @note This code is use OS's event mechanism for modbus master protocol stack. + * If you don't use OS, you can change it. + */ + rt_event_send(&xMasterOsEvent, EV_MASTER_ERROR_RECEIVE_DATA); - /* You can add your code under here. */ + /* You can add your code under here. */ } @@ -166,14 +166,14 @@ void vMBMasterErrorCBReceiveData(UCHAR ucDestAddress, const UCHAR* pucPDUData, * */ void vMBMasterErrorCBExecuteFunction(UCHAR ucDestAddress, const UCHAR* pucPDUData, - USHORT ucPDULength) { - /** - * @note This code is use OS's event mechanism for modbus master protocol stack. - * If you don't use OS, you can change it. - */ - rt_event_send(&xMasterOsEvent, EV_MASTER_ERROR_EXECUTE_FUNCTION); + USHORT ucPDULength) { + /** + * @note This code is use OS's event mechanism for modbus master protocol stack. + * If you don't use OS, you can change it. + */ + rt_event_send(&xMasterOsEvent, EV_MASTER_ERROR_EXECUTE_FUNCTION); - /* You can add your code under here. */ + /* You can add your code under here. */ } @@ -184,13 +184,13 @@ void vMBMasterErrorCBExecuteFunction(UCHAR ucDestAddress, const UCHAR* pucPDUDat * */ void vMBMasterCBRequestScuuess( void ) { - /** - * @note This code is use OS's event mechanism for modbus master protocol stack. - * If you don't use OS, you can change it. - */ - rt_event_send(&xMasterOsEvent, EV_MASTER_PROCESS_SUCESS); + /** + * @note This code is use OS's event mechanism for modbus master protocol stack. + * If you don't use OS, you can change it. + */ + rt_event_send(&xMasterOsEvent, EV_MASTER_PROCESS_SUCESS); - /* You can add your code under here. */ + /* You can add your code under here. */ } @@ -207,32 +207,32 @@ eMBMasterReqErrCode eMBMasterWaitRequestFinish( void ) { eMBMasterReqErrCode eErrStatus = MB_MRE_NO_ERR; rt_uint32_t recvedEvent; /* waiting for OS event */ - rt_event_recv(&xMasterOsEvent, - EV_MASTER_PROCESS_SUCESS | EV_MASTER_ERROR_RESPOND_TIMEOUT - | EV_MASTER_ERROR_RECEIVE_DATA - | EV_MASTER_ERROR_EXECUTE_FUNCTION, - RT_EVENT_FLAG_OR | RT_EVENT_FLAG_CLEAR, RT_WAITING_FOREVER, - &recvedEvent); - switch (recvedEvent) - { - case EV_MASTER_PROCESS_SUCESS: - break; - case EV_MASTER_ERROR_RESPOND_TIMEOUT: - { - eErrStatus = MB_MRE_TIMEDOUT; - break; - } - case EV_MASTER_ERROR_RECEIVE_DATA: - { - eErrStatus = MB_MRE_REV_DATA; - break; - } - case EV_MASTER_ERROR_EXECUTE_FUNCTION: - { - eErrStatus = MB_MRE_EXE_FUN; - break; - } - } + rt_event_recv(&xMasterOsEvent, + EV_MASTER_PROCESS_SUCESS | EV_MASTER_ERROR_RESPOND_TIMEOUT + | EV_MASTER_ERROR_RECEIVE_DATA + | EV_MASTER_ERROR_EXECUTE_FUNCTION, + RT_EVENT_FLAG_OR | RT_EVENT_FLAG_CLEAR, RT_WAITING_FOREVER, + &recvedEvent); + switch (recvedEvent) + { + case EV_MASTER_PROCESS_SUCESS: + break; + case EV_MASTER_ERROR_RESPOND_TIMEOUT: + { + eErrStatus = MB_MRE_TIMEDOUT; + break; + } + case EV_MASTER_ERROR_RECEIVE_DATA: + { + eErrStatus = MB_MRE_REV_DATA; + break; + } + case EV_MASTER_ERROR_EXECUTE_FUNCTION: + { + eErrStatus = MB_MRE_EXE_FUN; + break; + } + } return eErrStatus; } diff --git a/FreeModbus/port/rtt/portserial.c b/FreeModbus/port/rtt/portserial.c new file mode 100644 index 0000000..cc23c0a --- /dev/null +++ b/FreeModbus/port/rtt/portserial.c @@ -0,0 +1,245 @@ +/* + * FreeModbus Libary: STM32 Port + * Copyright (C) 2013 Armink + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + * + * File: $Id: portserial.c,v 1.60 2013/08/13 15:07:05 Armink $ + */ + +#include "port.h" + +/* ----------------------- Modbus includes ----------------------------------*/ +#include "mb.h" +#include "mbport.h" +#include "rtdevice.h" +#include "bsp.h" + +/* ----------------------- Static variables ---------------------------------*/ +ALIGN(RT_ALIGN_SIZE) +/* software simulation serial transmit IRQ handler thread stack */ +static rt_uint8_t serial_soft_trans_irq_stack[512]; +/* software simulation serial transmit IRQ handler thread */ +static struct rt_thread thread_serial_soft_trans_irq; +/* serial event */ +static struct rt_event event_serial; +/* modbus slave serial device */ +static rt_serial_t *serial; + +/* ----------------------- Defines ------------------------------------------*/ +/* serial transmit event */ +#define EVENT_SERIAL_TRANS_START (1<<0) + +/* ----------------------- static functions ---------------------------------*/ +static void prvvUARTTxReadyISR(void); +static void prvvUARTRxISR(void); +static rt_err_t serial_rx_ind(rt_device_t dev, rt_size_t size); +static void serial_soft_trans_irq(void* parameter); + +/* ----------------------- Start implementation -----------------------------*/ +BOOL xMBPortSerialInit(UCHAR ucPORT, ULONG ulBaudRate, UCHAR ucDataBits, + eMBParity eParity) +{ + GPIO_InitTypeDef GPIO_InitStructure; + + /* set 485 model receive and transmit control IO */ + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13; + GPIO_Init(GPIOB, &GPIO_InitStructure); + + /* set serial name */ + if (ucPORT == 1) { +#if defined(RT_USING_UART1) || defined(RT_USING_REMAP_UART1) + extern struct rt_serial_device serial1; + serial = &serial1; +#endif + } else if (ucPORT == 2) { +#if defined(RT_USING_UART2) + extern struct rt_serial_device serial2; + serial = &serial2; +#endif + } else if (ucPORT == 3) { +#if defined(RT_USING_UART3) + extern struct rt_serial_device serial3; + serial = &serial3; +#endif + } + /* set serial configure parameter */ + serial->config.baud_rate = ulBaudRate; + serial->config.stop_bits = STOP_BITS_1; + switch(eParity){ + case MB_PAR_NONE: { + serial->config.data_bits = DATA_BITS_8; + serial->config.parity = PARITY_NONE; + break; + } + case MB_PAR_ODD: { + serial->config.data_bits = DATA_BITS_9; + serial->config.parity = PARITY_ODD; + break; + } + case MB_PAR_EVEN: { + serial->config.data_bits = DATA_BITS_9; + serial->config.parity = PARITY_EVEN; + break; + } + } + /* disable all interrupt */ + ENTER_CRITICAL_SECTION(); + /* set serial configure */ + serial->ops->configure(serial, &(serial->config)); + + /* resume all interrupt */ + EXIT_CRITICAL_SECTION(); + /* open serial device */ + if (!serial->parent.open(&serial->parent, + RT_DEVICE_OFLAG_RDWR | RT_DEVICE_FLAG_INT_RX )) { + serial->parent.rx_indicate = serial_rx_ind; + } else { + return FALSE; + } + + /* software initialize */ + rt_thread_init(&thread_serial_soft_trans_irq, + "slave trans", + serial_soft_trans_irq, + RT_NULL, + serial_soft_trans_irq_stack, + sizeof(serial_soft_trans_irq_stack), + 10, 5); + rt_thread_startup(&thread_serial_soft_trans_irq); + rt_event_init(&event_serial, "slave event", RT_IPC_FLAG_PRIO); + + + + return TRUE; +} + +void vMBPortSerialEnable(BOOL xRxEnable, BOOL xTxEnable) +{ + rt_uint32_t recved_event; + uint32_t irq_type; + if (xRxEnable) + { + /* waiting for last transmit complete */ + while (1) + { + irq_type = RT_DEVICE_FLAG_INT_TX; + serial->ops->control(serial, RT_DEVICE_CTRL_GET_FLAG, &irq_type); + if (irq_type) + { + break; + } + } + /* enable RX interrupt */ + irq_type = RT_DEVICE_FLAG_INT_RX; + serial->ops->control(serial, RT_DEVICE_CTRL_SET_INT, &irq_type); + /* switch 485 to receive mode */ + SLAVE_RS485_RECEIVE_MODE; + } + else + { + /* switch 485 to transmit mode */ + SLAVE_RS485_TRANS_MODE; + /* disable RX interrupt */ + irq_type = RT_DEVICE_FLAG_INT_RX; + serial->ops->control(serial, RT_DEVICE_CTRL_CLR_INT, &irq_type); + } + if (xTxEnable) + { + /* start serial transmit */ + rt_event_send(&event_serial, EVENT_SERIAL_TRANS_START); + irq_type = RT_DEVICE_FLAG_INT_TX; + } + else + { + /* stop serial transmit */ + rt_event_recv(&event_serial, EVENT_SERIAL_TRANS_START, + RT_EVENT_FLAG_OR | RT_EVENT_FLAG_CLEAR, 0, + &recved_event); + irq_type = RT_DEVICE_FLAG_INT_TX; + } +} + +void vMBPortClose(void) +{ + serial->parent.close(&(serial->parent)); +} + +BOOL xMBPortSerialPutByte(CHAR ucByte) +{ + serial->parent.write(&(serial->parent), 0, &ucByte, 1); + return TRUE; +} + +BOOL xMBPortSerialGetByte(CHAR * pucByte) +{ + serial->parent.read(&(serial->parent), 0, pucByte, 1); + return TRUE; +} + +/* + * Create an interrupt handler for the transmit buffer empty interrupt + * (or an equivalent) for your target processor. This function should then + * call pxMBFrameCBTransmitterEmpty( ) which tells the protocol stack that + * a new character can be sent. The protocol stack will then call + * xMBPortSerialPutByte( ) to send the character. + */ +void prvvUARTTxReadyISR(void) +{ + pxMBFrameCBTransmitterEmpty(); +} + +/* + * Create an interrupt handler for the receive interrupt for your target + * processor. This function should then call pxMBFrameCBByteReceived( ). The + * protocol stack will then call xMBPortSerialGetByte( ) to retrieve the + * character. + */ +void prvvUARTRxISR(void) +{ + pxMBFrameCBByteReceived(); +} + +/** + * Software simulation serial transmit IRQ handler. + * + * @param parameter parameter + */ +static void serial_soft_trans_irq(void* parameter) { + rt_uint32_t recved_event; + while (1) + { + /* waiting for serial transmit start */ + rt_event_recv(&event_serial, EVENT_SERIAL_TRANS_START, RT_EVENT_FLAG_OR, + RT_WAITING_FOREVER, &recved_event); + /* execute modbus callback */ + prvvUARTTxReadyISR(); + } +} + +/** + * This function is serial receive callback function + * + * @param dev the device of serial + * @param size the data size that receive + * + * @return return RT_EOK + */ +static rt_err_t serial_rx_ind(rt_device_t dev, rt_size_t size) { + prvvUARTRxISR(); + return RT_EOK; +} diff --git a/FreeModbus/port/rtt/portserial_m.c b/FreeModbus/port/rtt/portserial_m.c new file mode 100644 index 0000000..37660ec --- /dev/null +++ b/FreeModbus/port/rtt/portserial_m.c @@ -0,0 +1,199 @@ +/* + * FreeModbus Libary: STM32 Port + * Copyright (C) 2013 Armink + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + * + * File: $Id: portserial_m.c,v 1.60 2013/08/13 15:07:05 Armink add Master Functions $ + */ + +#include "port.h" + +/* ----------------------- Modbus includes ----------------------------------*/ +#include "mb.h" +#include "mbport.h" + +#if MB_MASTER_RTU_ENABLED > 0 || MB_MASTER_ASCII_ENABLED > 0 +/* ----------------------- static functions ---------------------------------*/ +static void prvvUARTTxReadyISR(void); +static void prvvUARTRxISR(void); +/* ----------------------- Start implementation -----------------------------*/ + +void vMBMasterPortSerialEnable(BOOL xRxEnable, BOOL xTxEnable) +{ + if (xRxEnable) + { + /* 485ͨÐÅʱ£¬µÈ´ý´®¿ÚÒÆλ¼Ä´æÆ÷ÖеÄÊý¾Ý·¢ËÍÍê³Éºó£¬ÔÙȥʹÄÜ485µÄ½ÓÊÕ¡¢Ê§ÄÜ485µÄ·¢ËÍ*/ + while (!USART_GetFlagStatus(USART2,USART_FLAG_TC)); + MASTER_RS485_RECEIVE_MODE; + USART_ITConfig(USART2, USART_IT_RXNE, ENABLE); + } + else + { + MASTER_RS485_TRANS_MODE; + USART_ITConfig(USART2, USART_IT_RXNE, DISABLE); + } + if (xTxEnable) + { + USART_ITConfig(USART2, USART_IT_TXE, ENABLE); + } + else + { + USART_ITConfig(USART2, USART_IT_TXE, DISABLE); + } +} + +void vMBMasterPortClose(void) +{ + USART_ITConfig(USART2, USART_IT_TXE | USART_IT_RXNE, DISABLE); + USART_Cmd(USART2, DISABLE); +} +//ĬÈÏÒ»¸öÖ÷»ú ´®¿Ú2 ²¨ÌØÂÊ¿ÉÉèÖà Ææż¼ìÑé¿ÉÉèÖà +BOOL xMBMasterPortSerialInit(UCHAR ucPORT, ULONG ulBaudRate, UCHAR ucDataBits, + eMBParity eParity) +{ + GPIO_InitTypeDef GPIO_InitStructure; + USART_InitTypeDef USART_InitStructure; + NVIC_InitTypeDef NVIC_InitStructure; + //======================ʱÖÓ³õʼ»¯======================================= + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB, ENABLE); + RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE); + //======================IO³õʼ»¯======================================= + //USART2_TX + GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP; + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2; + GPIO_Init(GPIOA, &GPIO_InitStructure); + //USART2_RX + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING; + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3; + GPIO_Init(GPIOA, &GPIO_InitStructure); + //ÅäÖÃ485·¢ËͺͽÓÊÕģʽ +// TODO ÔÝʱÏÈдB13 µÈÖ®ºó×éÍø²âÊÔʱÔÙÐÞ¸Ä + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP; + GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13; + GPIO_Init(GPIOB, &GPIO_InitStructure); + //======================´®¿Ú³õʼ»¯======================================= + USART_InitStructure.USART_BaudRate = ulBaudRate; + //ÉèÖÃУÑéģʽ + switch (eParity) + { + case MB_PAR_NONE: //ÎÞУÑé + USART_InitStructure.USART_Parity = USART_Parity_No; + USART_InitStructure.USART_WordLength = USART_WordLength_8b; + break; + case MB_PAR_ODD: //ÆæУÑé + USART_InitStructure.USART_Parity = USART_Parity_Odd; + USART_InitStructure.USART_WordLength = USART_WordLength_9b; + break; + case MB_PAR_EVEN: //żУÑé + USART_InitStructure.USART_Parity = USART_Parity_Even; + USART_InitStructure.USART_WordLength = USART_WordLength_9b; + break; + default: + return FALSE; + } + + USART_InitStructure.USART_StopBits = USART_StopBits_1; + USART_InitStructure.USART_HardwareFlowControl = + USART_HardwareFlowControl_None; + USART_InitStructure.USART_Mode = USART_Mode_Rx | USART_Mode_Tx; + if (ucPORT != 2) + return FALSE; + + ENTER_CRITICAL_SECTION(); //¹ØÈ«¾ÖÖÐ¶Ï + + USART_Init(USART2, &USART_InitStructure); + USART_ITConfig(USART2, USART_IT_RXNE, ENABLE); + USART_Cmd(USART2, ENABLE); + + //=====================Öжϳõʼ»¯====================================== + //ÉèÖÃNVICÓÅÏȼ¶·Ö×éΪGroup2£º0-3ÇÀռʽÓÅÏȼ¶£¬0-3µÄÏìӦʽÓÅÏȼ¶ + NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2); + NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0; + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); + + EXIT_CRITICAL_SECTION(); //¿ªÈ«¾ÖÖÐ¶Ï + + return TRUE; +} + +BOOL xMBMasterPortSerialPutByte(CHAR ucByte) +{ + USART_SendData(USART2, ucByte); + return TRUE; +} + +BOOL xMBMasterPortSerialGetByte(CHAR * pucByte) +{ + *pucByte = USART_ReceiveData(USART2); + return TRUE; +} + +/* + * Create an interrupt handler for the transmit buffer empty interrupt + * (or an equivalent) for your target processor. This function should then + * call pxMBFrameCBTransmitterEmpty( ) which tells the protocol stack that + * a new character can be sent. The protocol stack will then call + * xMBPortSerialPutByte( ) to send the character. + */ +void prvvUARTTxReadyISR(void) +{ + pxMBMasterFrameCBTransmitterEmpty(); +} + +/* + * Create an interrupt handler for the receive interrupt for your target + * processor. This function should then call pxMBFrameCBByteReceived( ). The + * protocol stack will then call xMBPortSerialGetByte( ) to retrieve the + * character. + */ +void prvvUARTRxISR(void) +{ + pxMBMasterFrameCBByteReceived(); +} +/******************************************************************************* + * Function Name : USART2_IRQHandler + * Description : This function handles USART2 global interrupt request. + * Input : None + * Output : None + * Return : None + *******************************************************************************/ +void USART2_IRQHandler(void) +{ + rt_interrupt_enter(); + //Òç³ö´íÎó + if (USART_GetFlagStatus(USART2, USART_FLAG_ORE) == SET) + { + prvvUARTRxISR(); + } + //½ÓÊÕÖÐ¶Ï + if (USART_GetITStatus(USART2, USART_IT_RXNE) == SET) + { + USART_ClearITPendingBit(USART2, USART_IT_RXNE); + prvvUARTRxISR(); + } + //·¢ËÍÖÐ¶Ï + if (USART_GetITStatus(USART2, USART_IT_TXE) == SET) + { + prvvUARTTxReadyISR(); + } + rt_interrupt_leave(); +} + +#endif diff --git a/FreeModbus/port/rtt/porttimer.c b/FreeModbus/port/rtt/porttimer.c new file mode 100644 index 0000000..7880434 --- /dev/null +++ b/FreeModbus/port/rtt/porttimer.c @@ -0,0 +1,67 @@ +/* + * FreeModbus Libary: STM32 Port + * Copyright (C) 2013 Armink + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + * + * File: $Id: porttimer.c,v 1.60 2013/08/13 15:07:05 Armink $ + */ + +/* ----------------------- Platform includes --------------------------------*/ +#include "port.h" + +/* ----------------------- Modbus includes ----------------------------------*/ +#include "mb.h" +#include "mbport.h" + +/* ----------------------- static functions ---------------------------------*/ +static struct rt_timer timer; +static void prvvTIMERExpiredISR(void); +static void timer_timeout_ind(void* parameter); + +/* ----------------------- Start implementation -----------------------------*/ +BOOL xMBPortTimersInit(USHORT usTim1Timerout50us) +{ + rt_timer_init(&timer, "plc_recv_timer", + timer_timeout_ind, /* bind timeout callback function */ + RT_NULL, + (50*usTim1Timerout50us)/(1000*1000/RT_TICK_PER_SECOND), + RT_TIMER_FLAG_ONE_SHOT); /* one shot */ + return TRUE; +} + +void vMBPortTimersEnable() +{ + rt_timer_start(&timer); +} + +void vMBPortTimersDisable() +{ + rt_timer_stop(&timer); +} + +void prvvTIMERExpiredISR(void) +{ + (void) pxMBPortCBTimerExpired(); +} +/** + * This function is PLC uart receive timer callback function + * + * @param parameter null + */ +static void timer_timeout_ind(void* parameter) +{ + prvvTIMERExpiredISR(); +} diff --git a/FreeModbus/port/rtt/porttimer_m.c b/FreeModbus/port/rtt/porttimer_m.c new file mode 100644 index 0000000..0a98e41 --- /dev/null +++ b/FreeModbus/port/rtt/porttimer_m.c @@ -0,0 +1,157 @@ +/* + * FreeModbus Libary: STM32 Port + * Copyright (C) 2013 Armink + * + * This library is free software; you can redistribute it and/or + * modify it under the terms of the GNU Lesser General Public + * License as published by the Free Software Foundation; either + * version 2.1 of the License, or (at your option) any later version. + * + * This library is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public + * License along with this library; if not, write to the Free Software + * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA + * + * File: $Id: porttimer_m.c,v 1.60 2013/08/13 15:07:05 Armink add Master Functions$ + */ + +/* ----------------------- Platform includes --------------------------------*/ +#include "port.h" + +/* ----------------------- Modbus includes ----------------------------------*/ +#include "mb.h" +#include "mb_m.h" +#include "mbport.h" + +#if MB_MASTER_RTU_ENABLED > 0 || MB_MASTER_ASCII_ENABLED > 0 +/* ----------------------- Variables ----------------------------------------*/ +static USHORT usT35TimeOut50us; +static USHORT usPrescalerValue = 0; + +/* ----------------------- static functions ---------------------------------*/ +static void prvvTIMERExpiredISR(void); + +/* ----------------------- Start implementation -----------------------------*/ +BOOL xMBMasterPortTimersInit(USHORT usTimeOut50us) +{ + NVIC_InitTypeDef NVIC_InitStructure; + //====================================ʱÖÓ³õʼ»¯=========================== + //ʹÄܶ¨Ê±Æ÷2ʱÖÓ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM2, ENABLE); + //====================================¶¨Ê±Æ÷³õʼ»¯=========================== + //¶¨Ê±Æ÷ʱ¼ä»ùÅäÖÃ˵Ã÷ + //HCLKΪ72MHz£¬APB1¾­¹ý2·ÖƵΪ36MHz + //TIM2µÄʱÖÓ±¶ÆµºóΪ72MHz£¨Ó²¼þ×Ô¶¯±¶Æµ,´ïµ½×î´ó£© + //TIM2µÄ·ÖƵϵÊýΪ3599£¬Ê±¼ä»ùƵÂÊΪ72 / (1 + Prescaler) = 20KHz,»ù׼Ϊ50us + //TIM×î´ó¼ÆÊýֵΪusTim1Timerout50u + usPrescalerValue = (uint16_t) (SystemCoreClock / 20000) - 1; + //±£´æT35¶¨Ê±Æ÷¼ÆÊýÖµ + usT35TimeOut50us = usTimeOut50us; + + //ԤװÔØʹÄÜ + TIM_ARRPreloadConfig(TIM2, ENABLE); + //====================================Öжϳõʼ»¯=========================== + //ÉèÖÃNVICÓÅÏȼ¶·Ö×éΪGroup2£º0-3ÇÀռʽÓÅÏȼ¶£¬0-3µÄÏìӦʽÓÅÏȼ¶ + NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2); + NVIC_InitStructure.NVIC_IRQChannel = TIM2_IRQn; + NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 1; + NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0; + NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE; + NVIC_Init(&NVIC_InitStructure); + //Çå³ýÒç³öÖжϱê־λ + TIM_ClearITPendingBit(TIM2, TIM_IT_Update); + //¶¨Ê±Æ÷3Òç³öÖÐ¶Ï¹Ø±Õ + TIM_ITConfig(TIM2, TIM_IT_Update, DISABLE); + //¶¨Ê±Æ÷3½ûÄÜ + TIM_Cmd(TIM2, DISABLE); + return TRUE; +} + +void vMBMasterPortTimersT35Enable() +{ + TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; + + /* Set current timer mode,don't change it.*/ + vMBMasterSetCurTimerMode(MB_TMODE_T35); + + TIM_TimeBaseStructure.TIM_Prescaler = usPrescalerValue; + TIM_TimeBaseStructure.TIM_ClockDivision = 0; + TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; + TIM_TimeBaseStructure.TIM_Period = (uint16_t) usT35TimeOut50us; + TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure); + + TIM_ClearITPendingBit(TIM2, TIM_IT_Update); + TIM_ITConfig(TIM2, TIM_IT_Update, ENABLE); + TIM_SetCounter(TIM2, 0); + TIM_Cmd(TIM2, ENABLE); +} + +void vMBMasterPortTimersConvertDelayEnable() +{ + TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; + + /* Set current timer mode,don't change it.*/ + vMBMasterSetCurTimerMode(MB_TMODE_CONVERT_DELAY); + + TIM_TimeBaseStructure.TIM_Prescaler = usPrescalerValue; + TIM_TimeBaseStructure.TIM_ClockDivision = 0; + TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; + TIM_TimeBaseStructure.TIM_Period = (uint16_t)(MB_MASTER_DELAY_MS_CONVERT * 1000 / 50); + TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure); + + TIM_ClearITPendingBit(TIM2, TIM_IT_Update); + TIM_ITConfig(TIM2, TIM_IT_Update, ENABLE); + TIM_SetCounter(TIM2, 0); + TIM_Cmd(TIM2, ENABLE); +} + +void vMBMasterPortTimersRespondTimeoutEnable() +{ + TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure; + + /* Set current timer mode,don't change it.*/ + vMBMasterSetCurTimerMode(MB_TMODE_RESPOND_TIMEOUT); + + TIM_TimeBaseStructure.TIM_Prescaler = usPrescalerValue; + TIM_TimeBaseStructure.TIM_ClockDivision = 0; + TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; + TIM_TimeBaseStructure.TIM_Period = (uint16_t)(MB_MASTER_TIMEOUT_MS_RESPOND * 1000 / 50); + TIM_TimeBaseInit(TIM2, &TIM_TimeBaseStructure); + + TIM_ClearITPendingBit(TIM2, TIM_IT_Update); + TIM_ITConfig(TIM2, TIM_IT_Update, ENABLE); + TIM_SetCounter(TIM2, 0); + TIM_Cmd(TIM2, ENABLE); +} + +void vMBMasterPortTimersDisable() +{ + TIM_ClearITPendingBit(TIM2, TIM_IT_Update); + TIM_ITConfig(TIM2, TIM_IT_Update, DISABLE); + TIM_SetCounter(TIM2, 0); + TIM_Cmd(TIM2, DISABLE); +} + +void prvvTIMERExpiredISR(void) +{ + (void) pxMBMasterPortCBTimerExpired(); +} + +void TIM2_IRQHandler(void) +{ + rt_interrupt_enter(); + if (TIM_GetITStatus(TIM2, TIM_IT_Update) != RESET) + { + + TIM_ClearFlag(TIM2, TIM_FLAG_Update); //ÇåÖжϱê¼Ç + TIM_ClearITPendingBit(TIM2, TIM_IT_Update); //Çå³ý¶¨Ê±Æ÷TIM2Òç³öÖжϱê־λ + prvvTIMERExpiredISR(); + } + rt_interrupt_leave(); +} + +#endif diff --git a/RT-Thread-1.2.2/components/drivers/include/drivers/serial.h b/RT-Thread-1.2.2/components/drivers/include/drivers/serial.h index 24b82ef..f9ba505 100644 --- a/RT-Thread-1.2.2/components/drivers/include/drivers/serial.h +++ b/RT-Thread-1.2.2/components/drivers/include/drivers/serial.h @@ -66,9 +66,10 @@ #endif #define RT_DEVICE_CTRL_CONFIG 0x03 /* configure device */ -#define RT_DEVICE_CTRL_SET_INT 0x10 /* enable receive irq */ -#define RT_DEVICE_CTRL_CLR_INT 0x11 /* disable receive irq */ +#define RT_DEVICE_CTRL_SET_INT 0x10 /* enable serial irq */ +#define RT_DEVICE_CTRL_CLR_INT 0x11 /* disable serial irq */ #define RT_DEVICE_CTRL_GET_INT 0x12 +#define RT_DEVICE_CTRL_GET_FLAG 0x13 #define RT_SERIAL_EVENT_RX_IND 0x01 /* Rx indication */ #define RT_SERIAL_EVENT_TX_DONE 0x02 /* Tx complete */ diff --git a/RVMDK/FreeModbus_Slave&Master+RTT+STM32.uvopt b/RVMDK/FreeModbus_Slave&Master+RTT+STM32.uvopt index 40effa5..da7ef68 100644 --- a/RVMDK/FreeModbus_Slave&Master+RTT+STM32.uvopt +++ b/RVMDK/FreeModbus_Slave&Master+RTT+STM32.uvopt @@ -472,10 +472,10 @@ 1 0 0 - 141 + 70 0 1 - 5 + 1 0 ..\APP\src\app_task.c app_task.c @@ -496,7 +496,7 @@ 1 - 5 + 4 5 0 0 @@ -510,7 +510,7 @@ 1 - 6 + 5 5 0 0 @@ -524,14 +524,14 @@ 1 - 7 + 6 5 0 0 0 0 - 38 - 57 + 0 + 0 0 ..\APP\inc\rtconfig.h rtconfig.h @@ -545,7 +545,7 @@ 0 2 - 8 + 7 1 0 0 @@ -559,7 +559,7 @@ 2 - 0 + 8 2 0 0 @@ -573,7 +573,7 @@ 2 - 0 + 9 1 0 0 @@ -585,6 +585,20 @@ ..\RT-Thread-1.2.2\libcpu\arm\cortex-m3\cpuport.c cpuport.c + + 2 + 0 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + ..\BSP\src\usart.c + usart.c + @@ -594,7 +608,7 @@ 0 3 - 13 + 10 1 0 0 @@ -608,7 +622,7 @@ 3 - 14 + 11 1 0 0 @@ -622,7 +636,7 @@ 3 - 15 + 12 1 0 0 @@ -636,7 +650,7 @@ 3 - 16 + 13 1 0 0 @@ -650,7 +664,7 @@ 3 - 17 + 14 1 0 0 @@ -664,7 +678,7 @@ 3 - 18 + 15 1 0 0 @@ -678,7 +692,7 @@ 3 - 19 + 16 1 0 0 @@ -692,7 +706,7 @@ 3 - 20 + 17 1 0 0 @@ -706,7 +720,7 @@ 3 - 21 + 18 1 0 0 @@ -720,7 +734,7 @@ 3 - 22 + 19 1 0 0 @@ -734,7 +748,7 @@ 3 - 23 + 20 1 0 0 @@ -748,7 +762,7 @@ 3 - 24 + 21 1 0 0 @@ -762,7 +776,7 @@ 3 - 25 + 22 1 0 0 @@ -776,7 +790,7 @@ 3 - 26 + 23 1 0 0 @@ -790,7 +804,7 @@ 3 - 27 + 24 1 0 0 @@ -804,7 +818,7 @@ 3 - 28 + 25 1 0 0 @@ -818,7 +832,7 @@ 3 - 29 + 26 1 0 0 @@ -832,7 +846,7 @@ 3 - 30 + 27 1 0 0 @@ -846,7 +860,7 @@ 3 - 31 + 28 1 0 0 @@ -860,11 +874,11 @@ 3 - 32 + 29 1 0 0 - 27 + 0 0 0 0 @@ -874,11 +888,11 @@ 3 - 33 + 30 1 0 0 - 23 + 0 0 0 0 @@ -888,7 +902,7 @@ 3 - 34 + 31 1 0 0 @@ -902,7 +916,7 @@ 3 - 35 + 32 2 0 0 @@ -923,7 +937,7 @@ 0 4 - 36 + 33 1 0 0 @@ -937,11 +951,11 @@ 4 - 37 + 34 1 0 0 - 11 + 0 0 0 0 @@ -958,7 +972,7 @@ 0 5 - 0 + 35 1 0 0 @@ -972,7 +986,7 @@ 5 - 0 + 36 1 0 0 @@ -986,7 +1000,7 @@ 5 - 0 + 37 1 0 0 @@ -1000,7 +1014,7 @@ 5 - 0 + 38 1 0 0 @@ -1014,7 +1028,7 @@ 5 - 0 + 39 1 0 0 @@ -1028,7 +1042,7 @@ 5 - 0 + 40 1 0 0 @@ -1042,7 +1056,7 @@ 5 - 0 + 41 1 0 0 @@ -1056,7 +1070,7 @@ 5 - 0 + 42 1 0 0 @@ -1070,7 +1084,7 @@ 5 - 0 + 43 1 0 0 @@ -1084,7 +1098,7 @@ 5 - 0 + 44 1 0 0 @@ -1098,7 +1112,7 @@ 5 - 0 + 45 1 0 0 @@ -1112,7 +1126,7 @@ 5 - 0 + 46 1 0 0 @@ -1126,7 +1140,7 @@ 5 - 0 + 47 1 0 0 @@ -1140,7 +1154,7 @@ 5 - 0 + 48 1 0 0 @@ -1154,7 +1168,7 @@ 5 - 0 + 49 1 0 0 @@ -1168,7 +1182,7 @@ 5 - 0 + 50 1 0 0 @@ -1188,8 +1202,8 @@ 0 0 - 0 - 0 + 6 + 51 1 0 0 @@ -1202,12 +1216,12 @@ completion.c - 0 - 0 + 6 + 52 1 0 0 - 47 + 0 0 0 0 @@ -1216,8 +1230,8 @@ dataqueue.c - 0 - 0 + 6 + 53 1 0 0 @@ -1230,8 +1244,8 @@ pipe.c - 0 - 0 + 6 + 54 1 0 0 @@ -1244,8 +1258,8 @@ portal.c - 0 - 0 + 6 + 55 1 0 0 @@ -1258,8 +1272,8 @@ ringbuffer.c - 0 - 0 + 6 + 56 1 0 0 @@ -1271,6 +1285,20 @@ ..\RT-Thread-1.2.2\components\drivers\src\wrokqueue.c wrokqueue.c + + 6 + 0 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + ..\RT-Thread-1.2.2\components\drivers\serial\serial.c + serial.c + @@ -1279,12 +1307,12 @@ 0 0 - 6 - 53 + 7 + 57 1 0 0 - 4 + 0 0 0 0 @@ -1293,8 +1321,8 @@ mb.c - 6 - 54 + 7 + 58 1 0 0 @@ -1307,8 +1335,8 @@ mbfunccoils.c - 6 - 55 + 7 + 59 1 0 0 @@ -1321,8 +1349,8 @@ mbfuncdiag.c - 6 - 56 + 7 + 60 1 0 0 @@ -1335,8 +1363,8 @@ mbfuncdisc.c - 6 - 57 + 7 + 61 1 0 0 @@ -1349,8 +1377,8 @@ mbfuncholding.c - 6 - 58 + 7 + 62 1 0 0 @@ -1363,8 +1391,8 @@ mbfuncinput.c - 6 - 59 + 7 + 63 1 0 0 @@ -1377,8 +1405,8 @@ mbfuncother.c - 6 - 60 + 7 + 64 1 0 0 @@ -1391,8 +1419,8 @@ mbutils.c - 6 - 61 + 7 + 65 1 0 0 @@ -1405,12 +1433,12 @@ mbcrc.c - 6 - 62 + 7 + 66 1 0 0 - 22 + 0 0 0 0 @@ -1419,8 +1447,8 @@ mbrtu.c - 6 - 63 + 7 + 67 1 0 0 @@ -1433,8 +1461,8 @@ port.c - 6 - 64 + 7 + 0 1 0 0 @@ -1443,12 +1471,26 @@ 0 0 0 - ..\FreeModbus\port\portevent.c + ..\FreeModbus\port\rtt\portevent.c portevent.c - 6 - 65 + 7 + 0 + 1 + 0 + 0 + 12 + 0 + 55 + 61 + 0 + ..\FreeModbus\port\rtt\portserial.c + portserial.c + + + 7 + 0 1 0 0 @@ -1457,26 +1499,12 @@ 0 0 0 - ..\FreeModbus\port\portserial.c - portserial.c - - - 6 - 66 - 1 - 0 - 0 - 10 - 0 - 0 - 0 - 0 - ..\FreeModbus\port\porttimer.c + ..\FreeModbus\port\rtt\porttimer.c porttimer.c - 6 - 67 + 7 + 71 1 0 0 @@ -1496,8 +1524,8 @@ 0 0 - 7 - 68 + 8 + 72 1 0 0 @@ -1510,8 +1538,8 @@ mb_m.c - 7 - 69 + 8 + 73 1 0 0 @@ -1524,8 +1552,8 @@ mbrtu_m.c - 7 - 70 + 8 + 74 1 0 0 @@ -1538,8 +1566,8 @@ mbfuncholding_m.c - 7 - 71 + 8 + 75 1 0 0 @@ -1552,8 +1580,8 @@ mbfunccoils_m.c - 7 - 72 + 8 + 76 1 0 0 @@ -1566,8 +1594,8 @@ mbfuncinput_m.c - 7 - 73 + 8 + 77 1 0 0 @@ -1580,8 +1608,8 @@ mbfuncdisc_m.c - 7 - 74 + 8 + 0 1 0 0 @@ -1590,12 +1618,12 @@ 0 0 0 - ..\FreeModbus\port\portevent_m.c + ..\FreeModbus\port\rtt\portevent_m.c portevent_m.c - 7 - 75 + 8 + 0 1 0 0 @@ -1604,12 +1632,12 @@ 0 0 0 - ..\FreeModbus\port\portserial_m.c + ..\FreeModbus\port\rtt\portserial_m.c portserial_m.c - 7 - 76 + 8 + 0 1 0 0 @@ -1618,12 +1646,12 @@ 0 0 0 - ..\FreeModbus\port\porttimer_m.c + ..\FreeModbus\port\rtt\porttimer_m.c porttimer_m.c - 7 - 77 + 8 + 81 1 0 0 @@ -1644,8 +1672,8 @@ 2 3 - -32000 - -32000 + -1 + -1 -1 @@ -1662,7 +1690,7 @@ 0 274 - 01000000040000000100000001000000010000000100000001000000FFFFFFFF000000000100000001000000000000002800000028000000010000000100000000000000010000004A443A5C50726F6772616D5C5265706F7369746F72795C467265654D6F646275735F536C6176652D4D61737465722D5254542D53544D33325C4150505C7372635C6170705F7461736B2E63000000000A6170705F7461736B2E6300000000C5D4F200FFFFFFFF0100000010000000C5D4F200FFDC7800BECEA100F0A0A100BCA8E1009CC1B600F7B88600D9ADC200A5C2D700B3A6BE00EAD6A300F6FA7D00B5E99D005FC3CF00C1838300CACAD500010000000100000002000000E6000000660000009006000016030000 + 01000000040000000100000001000000010000000100000001000000FFFFFFFF000000000100000001000000000000002800000028000000010000000100000000000000010000004A443A5C50726F6772616D5C5265706F7369746F72795C467265654D6F646275735F536C6176652D4D61737465722D5254542D53544D33325C4150505C7372635C6170705F7461736B2E63000000000A6170705F7461736B2E6300000000FFDC7800FFFFFFFF0100000010000000C5D4F200FFDC7800BECEA100F0A0A100BCA8E1009CC1B600F7B88600D9ADC200A5C2D700B3A6BE00EAD6A300F6FA7D00B5E99D005FC3CF00C1838300CACAD500010000000100000002000000E6000000660000009006000016030000 @@ -1685,7 +1713,7 @@ 16 - A30100005401000015050000DF010000 + B50000006600000027040000F1000000 @@ -2781,7 +2809,7 @@ 0 16 - 0300000066000000DF000000E7020000 + 0300000066000000DF000000E6020000 16 @@ -3550,14 +3578,14 @@ 2569 - 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 + 000000000D000000000000000040000000000000FFFFFFFFFFFFFFFF260400004F0000002A040000000300000000000002000000040000000100000000000000000000000000000000000000000000000100000077940000000000000000000000000000000000000000000001000000779400000100000077940000000000000020000000000000FFFFFFFFFFFFFFFFB5000000DA00000027040000DE000000000000000100000004000000010000000000000000000000FFFFFFFF06000000CB00000057010000CC000000F08B00005A01000079070000FFFF02000B004354616262656450616E650020000000000000B50000006600000027040000F1000000B50000004F00000027040000DA0000000000000040280046060000000B446973617373656D626C7900000000CB00000001000000FFFFFFFFFFFFFFFF14506572666F726D616E636520416E616C797A6572000000005701000001000000FFFFFFFFFFFFFFFF14506572666F726D616E636520416E616C797A657200000000CC00000001000000FFFFFFFFFFFFFFFF0E4C6F67696320416E616C797A657200000000F08B000001000000FFFFFFFFFFFFFFFF0D436F646520436F766572616765000000005A01000001000000FFFFFFFFFFFFFFFF11496E737472756374696F6E205472616365000000007907000001000000FFFFFFFFFFFFFFFFFFFFFFFF000000000000000000000000000000000000000001000000FFFFFFFFCB00000001000000FFFFFFFFCB000000000000000040000000000000FFFFFFFFFFFFFFFF270400004F0000002B040000A8020000000000000200000004000000010000000000000000000000FFFFFFFF16000000E20500002D8C00002E8C00002F8C0000308C0000318C0000328C0000338C0000348C0000358C0000368C0000378C0000388C0000398C00003A8C00003B8C00003C8C00003D8C00003E8C00003F8C0000408C0000418C0000018000400000000000002B04000066000000DC040000BF0200002B0400004F000000DC040000A80200000000000040410046160000000753796D626F6C7300000000E205000001000000FFFFFFFFFFFFFFFF00000000002D8C000001000000FFFFFFFFFFFFFFFF00000000002E8C000001000000FFFFFFFFFFFFFFFF00000000002F8C000001000000FFFFFFFFFFFFFFFF0000000000308C000001000000FFFFFFFFFFFFFFFF0000000000318C000001000000FFFFFFFFFFFFFFFF0000000000328C000001000000FFFFFFFFFFFFFFFF0000000000338C000001000000FFFFFFFFFFFFFFFF0000000000348C000001000000FFFFFFFFFFFFFFFF0000000000358C000001000000FFFFFFFFFFFFFFFF0000000000368C000001000000FFFFFFFFFFFFFFFF0000000000378C000001000000FFFFFFFFFFFFFFFF0000000000388C000001000000FFFFFFFFFFFFFFFF0000000000398C000001000000FFFFFFFFFFFFFFFF00000000003A8C000001000000FFFFFFFFFFFFFFFF00000000003B8C000001000000FFFFFFFFFFFFFFFF00000000003C8C000001000000FFFFFFFFFFFFFFFF00000000003D8C000001000000FFFFFFFFFFFFFFFF00000000003E8C000001000000FFFFFFFFFFFFFFFF00000000003F8C000001000000FFFFFFFFFFFFFFFF0000000000408C000001000000FFFFFFFFFFFFFFFF0000000000418C000001000000FFFFFFFFFFFFFFFFFFFFFFFF000000000000000000000000000000000000000001000000FFFFFFFFE205000001000000FFFFFFFFE2050000000000000010000001000000FFFFFFFFFFFFFFFFE20000004F000000E6000000FF02000001000000020000100400000001000000E1FEFFFF0E020000FFFFFFFF05000000ED0300006D000000C3000000C400000073940000018000100000010000000000000066000000E200000016030000000000004F000000E2000000FF0200000000000040140056050000000750726F6A65637401000000ED03000001000000FFFFFFFFFFFFFFFF05426F6F6B73010000006D00000001000000FFFFFFFFFFFFFFFF0946756E6374696F6E7301000000C300000001000000FFFFFFFFFFFFFFFF0954656D706C6174657301000000C400000001000000FFFFFFFFFFFFFFFF09526567697374657273000000007394000001000000FFFFFFFFFFFFFFFF00000000000000000000000000000000000000000000000001000000FFFFFFFFED03000001000000FFFFFFFFED030000000000000080000000000000FFFFFFFFFFFFFFFF0000000005020000DC0400000902000000000000010000000400000001000000000000000000000000000000000000000000000001000000C6000000FFFFFFFF0900000098070000E30500008F0700009007000091070000B9050000BA050000BB050000BC050000018000800000000000000000000020020000DC040000BF0200000000000009020000DC040000A80200000000000040820046090000000A43616C6C20537461636B000000009807000001000000FFFFFFFFFFFFFFFF0A43616C6C20537461636B00000000E305000001000000FFFFFFFFFFFFFFFF064C6F63616C73000000008F07000001000000FFFFFFFFFFFFFFFF0757617463682031000000009007000001000000FFFFFFFFFFFFFFFF0757617463682032000000009107000001000000FFFFFFFFFFFFFFFF084D656D6F7279203100000000B905000001000000FFFFFFFFFFFFFFFF084D656D6F7279203200000000BA05000001000000FFFFFFFFFFFFFFFF084D656D6F7279203300000000BB05000001000000FFFFFFFFFFFFFFFF084D656D6F7279203400000000BC05000001000000FFFFFFFFFFFFFFFFFFFFFFFF0000000001000000000000000000000001000000FFFFFFFF6E0200000902000072020000A802000000000000020000000400000000000000000000000000000000000000000000000000000002000000C6000000FFFFFFFF9807000001000000FFFFFFFF9807000001000000C6000000000000000080000001000000FFFFFFFFFFFFFFFF00000000FF0200009006000003030000010000000100001004000000010000005DFEFFFF36010000FFFFFFFF06000000C5000000C70000009307000094070000950700009607000001800080000001000000000000001A03000090060000DF030000000000000303000090060000C80300000000000040820056060000000C4275696C64204F757470757401000000C500000001000000FFFFFFFFFFFFFFFF0D46696E6420496E2046696C657300000000C700000001000000FFFFFFFFFFFFFFFF0755415254202331000000009307000001000000FFFFFFFFFFFFFFFF0755415254202332000000009407000001000000FFFFFFFFFFFFFFFF0755415254202333000000009507000001000000FFFFFFFFFFFFFFFF15446562756720287072696E74662920566965776572000000009607000001000000FFFFFFFFFFFFFFFF00000000000000000000000000000000000000000000000001000000FFFFFFFFC500000001000000FFFFFFFFC5000000000000000000000000000000 59392 File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src\app_task.c - 141 + 70 1 - 5 + 1 diff --git a/RVMDK/FreeModbus_Slave&Master+RTT+STM32.uvproj b/RVMDK/FreeModbus_Slave&Master+RTT+STM32.uvproj index 4422624..68b8150 100644 --- a/RVMDK/FreeModbus_Slave&Master+RTT+STM32.uvproj +++ b/RVMDK/FreeModbus_Slave&Master+RTT+STM32.uvproj @@ -435,6 +435,11 @@ 1 ..\RT-Thread-1.2.2\libcpu\arm\cortex-m3\cpuport.c + + usart.c + 1 + ..\BSP\src\usart.c + @@ -690,6 +695,11 @@ 1 ..\RT-Thread-1.2.2\components\drivers\src\wrokqueue.c + + serial.c + 1 + ..\RT-Thread-1.2.2\components\drivers\serial\serial.c + @@ -753,17 +763,17 @@ portevent.c 1 - ..\FreeModbus\port\portevent.c + ..\FreeModbus\port\rtt\portevent.c portserial.c 1 - ..\FreeModbus\port\portserial.c + ..\FreeModbus\port\rtt\portserial.c porttimer.c 1 - ..\FreeModbus\port\porttimer.c + ..\FreeModbus\port\rtt\porttimer.c user_mb_app.c @@ -808,17 +818,17 @@ portevent_m.c 1 - ..\FreeModbus\port\portevent_m.c + ..\FreeModbus\port\rtt\portevent_m.c portserial_m.c 1 - ..\FreeModbus\port\portserial_m.c + ..\FreeModbus\port\rtt\portserial_m.c porttimer_m.c 1 - ..\FreeModbus\port\porttimer_m.c + ..\FreeModbus\port\rtt\porttimer_m.c user_mb_app_m.c @@ -1258,6 +1268,11 @@ 1 ..\RT-Thread-1.2.2\libcpu\arm\cortex-m3\cpuport.c + + usart.c + 1 + ..\BSP\src\usart.c + @@ -1513,6 +1528,11 @@ 1 ..\RT-Thread-1.2.2\components\drivers\src\wrokqueue.c + + serial.c + 1 + ..\RT-Thread-1.2.2\components\drivers\serial\serial.c + @@ -1576,17 +1596,17 @@ portevent.c 1 - ..\FreeModbus\port\portevent.c + ..\FreeModbus\port\rtt\portevent.c portserial.c 1 - ..\FreeModbus\port\portserial.c + ..\FreeModbus\port\rtt\portserial.c porttimer.c 1 - ..\FreeModbus\port\porttimer.c + ..\FreeModbus\port\rtt\porttimer.c user_mb_app.c @@ -1631,17 +1651,17 @@ portevent_m.c 1 - ..\FreeModbus\port\portevent_m.c + ..\FreeModbus\port\rtt\portevent_m.c portserial_m.c 1 - ..\FreeModbus\port\portserial_m.c + ..\FreeModbus\port\rtt\portserial_m.c porttimer_m.c 1 - ..\FreeModbus\port\porttimer_m.c + ..\FreeModbus\port\rtt\porttimer_m.c user_mb_app_m.c diff --git a/RVMDK/FreeModbus_Slave&Master+RTT+STM32_STM32F103CBT6_FLASH.dep b/RVMDK/FreeModbus_Slave&Master+RTT+STM32_STM32F103CBT6_FLASH.dep index 2dcd601..d229b6d 100644 --- a/RVMDK/FreeModbus_Slave&Master+RTT+STM32_STM32F103CBT6_FLASH.dep +++ b/RVMDK/FreeModbus_Slave&Master+RTT+STM32_STM32F103CBT6_FLASH.dep @@ -5,9 +5,9 @@ I (C:\Program Files\Keil\ARM\RV31\INC\stdlib.h)(0x4BD5D7FE) I (C:\Program Files\Keil\ARM\RV31\INC\stdio.h)(0x4BA13B96) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -26,7 +26,7 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_rcc.h)(0x5313C6B9) I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_tim.h)(0x5313C6B8) I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_usart.h)(0x5313C6B7) I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) -I (..\BSP\inc\bsp.h)(0x5313C6B7) +I (..\BSP\inc\bsp.h)(0x545B158F) I (..\APP\inc\delay_conf.h)(0x541BD3AC) I (..\APP\inc\cpuusage.h)(0x5313C6B7) I (..\FreeModbus\port\user_mb_app.h)(0x5313C6B6) @@ -46,9 +46,9 @@ I (C:\Program Files\Keil\ARM\RV31\INC\stdlib.h)(0x4BD5D7FE) I (C:\Program Files\Keil\ARM\RV31\INC\stdio.h)(0x4BA13B96) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -67,7 +67,7 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_rcc.h)(0x5313C6B9) I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_tim.h)(0x5313C6B8) I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_usart.h)(0x5313C6B7) I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) -I (..\BSP\inc\bsp.h)(0x5313C6B7) +I (..\BSP\inc\bsp.h)(0x545B158F) I (..\APP\inc\delay_conf.h)(0x541BD3AC) I (..\APP\inc\cpuusage.h)(0x5313C6B7) I (..\FreeModbus\port\user_mb_app.h)(0x5313C6B6) @@ -83,7 +83,7 @@ I (..\FreeModbus\modbus\include\mbframe.h)(0x5313C6B8) I (..\FreeModbus\modbus\include\mbutils.h)(0x5313C6B7) F (..\APP\src\stm32f10x_it.c)(0x5313C6B7)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\stm32f10x_it.o" --omf_browse ".\Output\stm32f10x_it.crf" --depend ".\Output\stm32f10x_it.d") I (..\APP\inc\stm32f10x_it.h)(0x5313C6B8) -I (..\BSP\inc\bsp.h)(0x5313C6B7) +I (..\BSP\inc\bsp.h)(0x545B158F) I (..\APP\inc\stm32f10x_conf.h)(0x5313C6B8) I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_adc.h)(0x5313C6B8) I (..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x\stm32f10x.h)(0x5313C6B8) @@ -100,18 +100,18 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_tim.h)(0x5313C6B8) I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_usart.h)(0x5313C6B7) I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) I (..\APP\inc\delay_conf.h)(0x541BD3AC) F (..\APP\inc\delay_conf.h)(0x541BD3AC)() F (..\APP\inc\stm32f10x_conf.h)(0x5313C6B8)() -F (..\APP\inc\rtconfig.h)(0x544E2C43)() -F (..\BSP\src\bsp.c)(0x5313C6B8)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\bsp.o" --omf_browse ".\Output\bsp.crf" --depend ".\Output\bsp.d") -I (..\BSP\inc\bsp.h)(0x5313C6B7) +F (..\APP\inc\rtconfig.h)(0x54576D0D)() +F (..\BSP\src\bsp.c)(0x545B15D4)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\bsp.o" --omf_browse ".\Output\bsp.crf" --depend ".\Output\bsp.d") +I (..\BSP\inc\bsp.h)(0x545B158F) I (..\APP\inc\stm32f10x_conf.h)(0x5313C6B8) I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_adc.h)(0x5313C6B8) I (..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x\stm32f10x.h)(0x5313C6B8) @@ -129,21 +129,50 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_usart.h)(0x5313C6B7) I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) +I (..\BSP\inc\usart.h)(0x5406D3FE) F (..\RT-Thread-1.2.2\libcpu\arm\cortex-m3\context_rvds.S)(0x54471BB0)(--cpu Cortex-M3 -g --apcs=interwork -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" --list ".\Output\list\context_rvds.lst" --xref -o ".\Output\context_rvds.o" --depend ".\Output\context_rvds.d") F (..\RT-Thread-1.2.2\libcpu\arm\cortex-m3\cpuport.c)(0x54471BB0)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\cpuport.o" --omf_browse ".\Output\cpuport.crf" --depend ".\Output\cpuport.d") I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) +F (..\BSP\src\usart.c)(0x545C7A43)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\usart.o" --omf_browse ".\Output\usart.crf" --depend ".\Output\usart.d") +I (..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x\stm32f10x.h)(0x5313C6B8) +I (..\Libaries\CMSIS_MDK\CM3\CoreSupport\core_cm3.h)(0x5313C6B6) +I (C:\Program Files\Keil\ARM\RV31\INC\stdint.h)(0x4BA13B96) +I (..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x\system_stm32f10x.h)(0x5313C6B6) +I (..\APP\inc\stm32f10x_conf.h)(0x5313C6B8) +I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_adc.h)(0x5313C6B8) +I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_dma.h)(0x5313C6B7) +I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_exti.h)(0x5313C6B8) +I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_flash.h)(0x5313C6B7) +I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_gpio.h)(0x5313C6B6) +I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_iwdg.h)(0x5313C6B6) +I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_rcc.h)(0x5313C6B9) +I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_tim.h)(0x5313C6B8) +I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_usart.h)(0x5313C6B7) +I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) +I (..\BSP\inc\usart.h)(0x5406D3FE) +I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) +I (..\APP\inc\rtconfig.h)(0x54576D0D) +I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) +I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) +I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) +I (..\BSP\inc\bsp.h)(0x545B158F) +I (..\RT-Thread-1.2.2\components\drivers\include\rtdevice.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\components\drivers\include\drivers/serial.h)(0x545C73E4) F (..\Libaries\STM32F10x_StdPeriph_Driver\src\misc.c)(0x5313C6B6)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\misc.o" --omf_browse ".\Output\misc.crf" --depend ".\Output\misc.d") I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x\stm32f10x.h)(0x5313C6B8) @@ -530,43 +559,43 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) F (..\RT-Thread-1.2.2\src\clock.c)(0x54471BB1)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\clock.o" --omf_browse ".\Output\clock.crf" --depend ".\Output\clock.d") I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) F (..\RT-Thread-1.2.2\src\cpuusage.c)(0x54471BB1)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\cpuusage.o" --omf_browse ".\Output\cpuusage.crf" --depend ".\Output\cpuusage.d") I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) F (..\RT-Thread-1.2.2\src\device.c)(0x54471BB1)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\device.o" --omf_browse ".\Output\device.crf" --depend ".\Output\device.d") I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) F (..\RT-Thread-1.2.2\src\idle.c)(0x54471BB1)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\idle.o" --omf_browse ".\Output\idle.crf" --depend ".\Output\idle.d") I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) F (..\RT-Thread-1.2.2\src\ipc.c)(0x54471BB1)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\ipc.o" --omf_browse ".\Output\ipc.crf" --depend ".\Output\ipc.d") I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -574,17 +603,17 @@ I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) F (..\RT-Thread-1.2.2\src\irq.c)(0x54471BB1)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\irq.o" --omf_browse ".\Output\irq.crf" --depend ".\Output\irq.d") I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) F (..\RT-Thread-1.2.2\src\kservice.c)(0x54471BB1)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\kservice.o" --omf_browse ".\Output\kservice.crf" --depend ".\Output\kservice.d") I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -592,53 +621,53 @@ I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) F (..\RT-Thread-1.2.2\src\mem.c)(0x54471BB1)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\mem.o" --omf_browse ".\Output\mem.crf" --depend ".\Output\mem.d") I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) F (..\RT-Thread-1.2.2\src\memheap.c)(0x54471BB1)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\memheap.o" --omf_browse ".\Output\memheap.crf" --depend ".\Output\memheap.d") I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) F (..\RT-Thread-1.2.2\src\mempool.c)(0x54471BB1)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\mempool.o" --omf_browse ".\Output\mempool.crf" --depend ".\Output\mempool.d") I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) F (..\RT-Thread-1.2.2\src\module.c)(0x54471BB1)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\module.o" --omf_browse ".\Output\module.crf" --depend ".\Output\module.d") I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) F (..\RT-Thread-1.2.2\src\object.c)(0x54471BB1)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\object.o" --omf_browse ".\Output\object.crf" --depend ".\Output\object.d") I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) F (..\RT-Thread-1.2.2\src\scheduler.c)(0x54471BB1)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\scheduler.o" --omf_browse ".\Output\scheduler.crf" --depend ".\Output\scheduler.d") I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -646,26 +675,26 @@ I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) F (..\RT-Thread-1.2.2\src\slab.c)(0x54471BB1)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\slab.o" --omf_browse ".\Output\slab.crf" --depend ".\Output\slab.d") I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) F (..\RT-Thread-1.2.2\src\thread.c)(0x54471BB1)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\thread.o" --omf_browse ".\Output\thread.crf" --depend ".\Output\thread.d") I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) F (..\RT-Thread-1.2.2\src\timer.c)(0x54471BB1)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\timer.o" --omf_browse ".\Output\timer.crf" --depend ".\Output\timer.d") I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -673,61 +702,78 @@ I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) F (..\RT-Thread-1.2.2\components\drivers\src\completion.c)(0x54471BAF)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\completion.o" --omf_browse ".\Output\completion.crf" --depend ".\Output\completion.d") I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) I (..\RT-Thread-1.2.2\components\drivers\include\rtdevice.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\components\drivers\include\drivers/serial.h)(0x545C73E4) F (..\RT-Thread-1.2.2\components\drivers\src\dataqueue.c)(0x54471BAF)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\dataqueue.o" --omf_browse ".\Output\dataqueue.crf" --depend ".\Output\dataqueue.d") I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) I (..\RT-Thread-1.2.2\components\drivers\include\rtdevice.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\components\drivers\include\drivers/serial.h)(0x545C73E4) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) F (..\RT-Thread-1.2.2\components\drivers\src\pipe.c)(0x54471BAF)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\pipe.o" --omf_browse ".\Output\pipe.crf" --depend ".\Output\pipe.d") I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) I (..\RT-Thread-1.2.2\components\drivers\include\rtdevice.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\components\drivers\include\drivers/serial.h)(0x545C73E4) F (..\RT-Thread-1.2.2\components\drivers\src\portal.c)(0x54471BAF)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\portal.o" --omf_browse ".\Output\portal.crf" --depend ".\Output\portal.d") I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) I (..\RT-Thread-1.2.2\components\drivers\include\rtdevice.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\components\drivers\include\drivers/serial.h)(0x545C73E4) F (..\RT-Thread-1.2.2\components\drivers\src\ringbuffer.c)(0x54471BAF)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\ringbuffer.o" --omf_browse ".\Output\ringbuffer.crf" --depend ".\Output\ringbuffer.d") I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) I (..\RT-Thread-1.2.2\components\drivers\include\rtdevice.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\components\drivers\include\drivers/serial.h)(0x545C73E4) I (C:\Program Files\Keil\ARM\RV31\INC\string.h)(0x4BA13B9A) F (..\RT-Thread-1.2.2\components\drivers\src\wrokqueue.c)(0x54471BAF)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\wrokqueue.o" --omf_browse ".\Output\wrokqueue.crf" --depend ".\Output\wrokqueue.d") I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) I (..\RT-Thread-1.2.2\components\drivers\include\rtdevice.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\components\drivers\include\drivers/serial.h)(0x545C73E4) +F (..\RT-Thread-1.2.2\components\drivers\serial\serial.c)(0x54471BAF)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\serial.o" --omf_browse ".\Output\serial.crf" --depend ".\Output\serial.d") +I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) +I (..\APP\inc\rtconfig.h)(0x54576D0D) +I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) +I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) +I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\components\drivers\include\rtdevice.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\components\drivers\include\drivers/serial.h)(0x545C73E4) F (..\FreeModbus\modbus\mb.c)(0x5313C6B5)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\mb.o" --omf_browse ".\Output\mb.crf" --depend ".\Output\mb.d") I (C:\Program Files\Keil\ARM\RV31\INC\stdlib.h)(0x4BD5D7FE) I (C:\Program Files\Keil\ARM\RV31\INC\string.h)(0x4BA13B9A) @@ -750,9 +796,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -786,9 +832,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -821,9 +867,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -855,9 +901,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -889,9 +935,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -923,9 +969,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -957,9 +1003,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -988,9 +1034,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -1018,9 +1064,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -1052,15 +1098,15 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) I (C:\Program Files\Keil\ARM\RV31\INC\assert.h)(0x4BA13B9C) I (C:\Program Files\Keil\ARM\RV31\INC\inttypes.h)(0x4BA25EFA) -F (..\FreeModbus\port\portevent.c)(0x533D0F94)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\portevent.o" --omf_browse ".\Output\portevent.crf" --depend ".\Output\portevent.d") +F (..\FreeModbus\port\rtt\portevent.c)(0x533D0F94)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\portevent.o" --omf_browse ".\Output\portevent.crf" --depend ".\Output\portevent.d") I (..\FreeModbus\modbus\include\mb.h)(0x5313C6B6) I (..\FreeModbus\port\port.h)(0x5313C6B6) I (..\APP\inc\stm32f10x_conf.h)(0x5313C6B8) @@ -1081,9 +1127,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -1091,7 +1137,7 @@ I (C:\Program Files\Keil\ARM\RV31\INC\assert.h)(0x4BA13B9C) I (C:\Program Files\Keil\ARM\RV31\INC\inttypes.h)(0x4BA25EFA) I (..\FreeModbus\modbus\include\mbport.h)(0x533CF721) I (..\FreeModbus\modbus\include\mbproto.h)(0x5313C6B7) -F (..\FreeModbus\port\portserial.c)(0x53B39742)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\portserial.o" --omf_browse ".\Output\portserial.crf" --depend ".\Output\portserial.d") +F (..\FreeModbus\port\rtt\portserial.c)(0x545C7A66)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\portserial.o" --omf_browse ".\Output\portserial.crf" --depend ".\Output\portserial.d") I (..\FreeModbus\port\port.h)(0x5313C6B6) I (..\APP\inc\stm32f10x_conf.h)(0x5313C6B8) I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_adc.h)(0x5313C6B8) @@ -1111,9 +1157,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -1122,7 +1168,10 @@ I (C:\Program Files\Keil\ARM\RV31\INC\inttypes.h)(0x4BA25EFA) I (..\FreeModbus\modbus\include\mb.h)(0x5313C6B6) I (..\FreeModbus\modbus\include\mbport.h)(0x533CF721) I (..\FreeModbus\modbus\include\mbproto.h)(0x5313C6B7) -F (..\FreeModbus\port\porttimer.c)(0x5313C6B8)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\porttimer.o" --omf_browse ".\Output\porttimer.crf" --depend ".\Output\porttimer.d") +I (..\RT-Thread-1.2.2\components\drivers\include\rtdevice.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\components\drivers\include\drivers/serial.h)(0x545C73E4) +I (..\BSP\inc\bsp.h)(0x545B158F) +F (..\FreeModbus\port\rtt\porttimer.c)(0x545B1028)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\porttimer.o" --omf_browse ".\Output\porttimer.crf" --depend ".\Output\porttimer.d") I (..\FreeModbus\port\port.h)(0x5313C6B6) I (..\APP\inc\stm32f10x_conf.h)(0x5313C6B8) I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_adc.h)(0x5313C6B8) @@ -1142,9 +1191,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -1175,9 +1224,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -1210,9 +1259,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -1247,9 +1296,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -1284,9 +1333,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -1319,9 +1368,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -1354,9 +1403,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -1389,9 +1438,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -1402,7 +1451,7 @@ I (..\FreeModbus\modbus\include\mbport.h)(0x533CF721) I (..\FreeModbus\modbus\include\mbproto.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mb_m.h)(0x533B8C43) I (..\FreeModbus\modbus\include\mbframe.h)(0x5313C6B8) -F (..\FreeModbus\port\portevent_m.c)(0x533D0F3D)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\portevent_m.o" --omf_browse ".\Output\portevent_m.crf" --depend ".\Output\portevent_m.d") +F (..\FreeModbus\port\rtt\portevent_m.c)(0x533D0F3D)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\portevent_m.o" --omf_browse ".\Output\portevent_m.crf" --depend ".\Output\portevent_m.d") I (..\FreeModbus\modbus\include\mb.h)(0x5313C6B6) I (..\FreeModbus\port\port.h)(0x5313C6B6) I (..\APP\inc\stm32f10x_conf.h)(0x5313C6B8) @@ -1423,9 +1472,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -1434,7 +1483,7 @@ I (C:\Program Files\Keil\ARM\RV31\INC\inttypes.h)(0x4BA25EFA) I (..\FreeModbus\modbus\include\mbport.h)(0x533CF721) I (..\FreeModbus\modbus\include\mbproto.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mb_m.h)(0x533B8C43) -F (..\FreeModbus\port\portserial_m.c)(0x53B39754)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\portserial_m.o" --omf_browse ".\Output\portserial_m.crf" --depend ".\Output\portserial_m.d") +F (..\FreeModbus\port\rtt\portserial_m.c)(0x53B39754)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\portserial_m.o" --omf_browse ".\Output\portserial_m.crf" --depend ".\Output\portserial_m.d") I (..\FreeModbus\port\port.h)(0x5313C6B6) I (..\APP\inc\stm32f10x_conf.h)(0x5313C6B8) I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_adc.h)(0x5313C6B8) @@ -1454,9 +1503,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -1465,7 +1514,7 @@ I (C:\Program Files\Keil\ARM\RV31\INC\inttypes.h)(0x4BA25EFA) I (..\FreeModbus\modbus\include\mb.h)(0x5313C6B6) I (..\FreeModbus\modbus\include\mbport.h)(0x533CF721) I (..\FreeModbus\modbus\include\mbproto.h)(0x5313C6B7) -F (..\FreeModbus\port\porttimer_m.c)(0x5313C6B6)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\porttimer_m.o" --omf_browse ".\Output\porttimer_m.crf" --depend ".\Output\porttimer_m.d") +F (..\FreeModbus\port\rtt\porttimer_m.c)(0x5458A000)(-c --cpu Cortex-M3 -g -O0 -Otime --apcs=interwork --split_sections -I..\Libaries\CMSIS_MDK\CM3\CoreSupport -I..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x -I..\Libaries\STM32F10x_StdPeriph_Driver\inc -I..\Libaries\USB-FS-Device_Driver\inc -I..\BSP\inc -I..\APP\inc -I..\RT-Thread-1.2.2\include -I..\RT-Thread-1.2.2\components\drivers\include -I..\RT-Thread-1.2.2\components\drivers\include\drivers -I..\FreeModbus\modbus\include -I..\FreeModbus\modbus\rtu -I..\FreeModbus\port -I "C:\Program Files\Keil\ARM\INC" -I "C:\Program Files\Keil\ARM\INC\ST\STM32F10x" -DUSE_STDPERIPH_DRIVER -DSTM32F10X_MD -o ".\Output\porttimer_m.o" --omf_browse ".\Output\porttimer_m.crf" --depend ".\Output\porttimer_m.d") I (..\FreeModbus\port\port.h)(0x5313C6B6) I (..\APP\inc\stm32f10x_conf.h)(0x5313C6B8) I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\stm32f10x_adc.h)(0x5313C6B8) @@ -1485,9 +1534,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) @@ -1519,9 +1568,9 @@ I (..\Libaries\STM32F10x_StdPeriph_Driver\inc\misc.h)(0x5313C6B7) I (..\FreeModbus\modbus\include\mbconfig.h)(0x5313C6B7) I (..\RT-Thread-1.2.2\include\rthw.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtthread.h)(0x54471BAF) -I (..\APP\inc\rtconfig.h)(0x544E2C43) +I (..\APP\inc\rtconfig.h)(0x54576D0D) I (..\RT-Thread-1.2.2\include\rtdebug.h)(0x54471BAF) -I (..\RT-Thread-1.2.2\include\rtdef.h)(0x54471BAF) +I (..\RT-Thread-1.2.2\include\rtdef.h)(0x545C1075) I (C:\Program Files\Keil\ARM\RV31\INC\stdarg.h)(0x4BD5D7FE) I (..\RT-Thread-1.2.2\include\rtservice.h)(0x54471BAF) I (..\RT-Thread-1.2.2\include\rtm.h)(0x54471BAF) diff --git a/RVMDK/FreeModbus_Slave&Master+RTT+STM32_uvopt.bak b/RVMDK/FreeModbus_Slave&Master+RTT+STM32_uvopt.bak index b6c74cb..52f041c 100644 --- a/RVMDK/FreeModbus_Slave&Master+RTT+STM32_uvopt.bak +++ b/RVMDK/FreeModbus_Slave&Master+RTT+STM32_uvopt.bak @@ -460,8 +460,8 @@ 0 0 0 - 1 - 4 + 0 + 0 0 ..\APP\src\app.c app.c @@ -472,10 +472,10 @@ 1 0 0 - 6 + 5 0 - 31 - 66 + 43 + 43 0 ..\APP\src\app_task.c app_task.c @@ -488,8 +488,8 @@ 0 54 0 - 99 - 112 + 0 + 0 0 ..\APP\src\stm32f10x_it.c stm32f10x_it.c @@ -497,20 +497,6 @@ 1 4 - 1 - 0 - 0 - 0 - 0 - 25 - 38 - 0 - ..\APP\src\cpuusage.c - cpuusage.c - - - 1 - 5 5 0 0 @@ -524,7 +510,7 @@ 1 - 6 + 5 5 0 0 @@ -538,7 +524,7 @@ 1 - 7 + 6 5 0 0 @@ -559,7 +545,7 @@ 0 2 - 8 + 7 1 0 0 @@ -571,6 +557,20 @@ ..\BSP\src\bsp.c bsp.c + + 2 + 8 + 2 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + ..\RT-Thread-1.2.2\libcpu\arm\cortex-m3\context_rvds.S + context_rvds.S + 2 9 @@ -582,51 +582,9 @@ 0 0 0 - ..\RT-Thread-1.1.1\libcpu\arm\common\backtrace.c - backtrace.c - - - 2 - 10 - 1 - 0 - 0 - 0 - 0 - 0 - 0 - 0 - ..\RT-Thread-1.1.1\libcpu\arm\common\showmem.c - showmem.c - - - 2 - 11 - 1 - 0 - 0 - 0 - 0 - 0 - 0 - 0 - ..\RT-Thread-1.1.1\libcpu\arm\cortex-m3\cpuport.c + ..\RT-Thread-1.2.2\libcpu\arm\cortex-m3\cpuport.c cpuport.c - - 2 - 12 - 2 - 0 - 0 - 0 - 0 - 36 - 49 - 0 - ..\RT-Thread-1.1.1\libcpu\arm\cortex-m3\context_rvds.S - context_rvds.S - @@ -636,7 +594,7 @@ 0 3 - 13 + 10 1 0 0 @@ -650,7 +608,7 @@ 3 - 14 + 11 1 0 0 @@ -664,7 +622,7 @@ 3 - 15 + 12 1 0 0 @@ -678,7 +636,7 @@ 3 - 16 + 13 1 0 0 @@ -692,7 +650,7 @@ 3 - 17 + 14 1 0 0 @@ -706,7 +664,7 @@ 3 - 18 + 15 1 0 0 @@ -720,7 +678,7 @@ 3 - 19 + 16 1 0 0 @@ -734,7 +692,7 @@ 3 - 20 + 17 1 0 0 @@ -748,7 +706,7 @@ 3 - 21 + 18 1 0 0 @@ -762,7 +720,7 @@ 3 - 22 + 19 1 0 0 @@ -776,7 +734,7 @@ 3 - 23 + 20 1 0 0 @@ -790,7 +748,7 @@ 3 - 24 + 21 1 0 0 @@ -804,7 +762,7 @@ 3 - 25 + 22 1 0 0 @@ -818,7 +776,7 @@ 3 - 26 + 23 1 0 0 @@ -832,7 +790,7 @@ 3 - 27 + 24 1 0 0 @@ -846,7 +804,7 @@ 3 - 28 + 25 1 0 0 @@ -860,7 +818,7 @@ 3 - 29 + 26 1 0 0 @@ -874,7 +832,7 @@ 3 - 30 + 27 1 0 0 @@ -888,7 +846,7 @@ 3 - 31 + 28 1 0 0 @@ -902,35 +860,35 @@ 3 - 32 + 29 1 0 0 - 27 + 0 0 - 199 - 212 + 0 + 0 0 ..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_tim.c stm32f10x_tim.c 3 - 33 + 30 1 0 0 - 23 + 0 0 - 946 - 963 + 0 + 0 0 ..\Libaries\STM32F10x_StdPeriph_Driver\src\stm32f10x_usart.c stm32f10x_usart.c 3 - 34 + 31 1 0 0 @@ -944,7 +902,7 @@ 3 - 35 + 32 2 0 0 @@ -965,7 +923,7 @@ 0 4 - 36 + 33 1 0 0 @@ -979,14 +937,14 @@ 4 - 37 + 34 1 0 0 - 11 + 0 0 - 149 - 161 + 0 + 0 0 ..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x\system_stm32f10x.c system_stm32f10x.c @@ -998,6 +956,48 @@ 0 0 0 + + 5 + 35 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + ..\RT-Thread-1.2.2\src\clock.c + clock.c + + + 5 + 36 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + ..\RT-Thread-1.2.2\src\cpuusage.c + cpuusage.c + + + 5 + 37 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + ..\RT-Thread-1.2.2\src\device.c + device.c + 5 38 @@ -1006,11 +1006,11 @@ 0 0 0 - 40 - 54 + 0 + 0 0 - ..\RT-Thread-1.1.1\src\clock.c - clock.c + ..\RT-Thread-1.2.2\src\idle.c + idle.c 5 @@ -1023,8 +1023,8 @@ 0 0 0 - ..\RT-Thread-1.1.1\src\device.c - device.c + ..\RT-Thread-1.2.2\src\ipc.c + ipc.c 5 @@ -1037,8 +1037,8 @@ 0 0 0 - ..\RT-Thread-1.1.1\src\idle.c - idle.c + ..\RT-Thread-1.2.2\src\irq.c + irq.c 5 @@ -1051,8 +1051,8 @@ 0 0 0 - ..\RT-Thread-1.1.1\src\ipc.c - ipc.c + ..\RT-Thread-1.2.2\src\kservice.c + kservice.c 5 @@ -1062,11 +1062,11 @@ 0 0 0 - 44 - 65 + 0 + 0 0 - ..\RT-Thread-1.1.1\src\irq.c - irq.c + ..\RT-Thread-1.2.2\src\mem.c + mem.c 5 @@ -1079,8 +1079,8 @@ 0 0 0 - ..\RT-Thread-1.1.1\src\kservice.c - kservice.c + ..\RT-Thread-1.2.2\src\memheap.c + memheap.c 5 @@ -1093,8 +1093,8 @@ 0 0 0 - ..\RT-Thread-1.1.1\src\mem.c - mem.c + ..\RT-Thread-1.2.2\src\mempool.c + mempool.c 5 @@ -1107,8 +1107,8 @@ 0 0 0 - ..\RT-Thread-1.1.1\src\memheap.c - memheap.c + ..\RT-Thread-1.2.2\src\module.c + module.c 5 @@ -1121,8 +1121,8 @@ 0 0 0 - ..\RT-Thread-1.1.1\src\mempool.c - mempool.c + ..\RT-Thread-1.2.2\src\object.c + object.c 5 @@ -1135,8 +1135,8 @@ 0 0 0 - ..\RT-Thread-1.1.1\src\module.c - module.c + ..\RT-Thread-1.2.2\src\scheduler.c + scheduler.c 5 @@ -1149,8 +1149,8 @@ 0 0 0 - ..\RT-Thread-1.1.1\src\object.c - object.c + ..\RT-Thread-1.2.2\src\slab.c + slab.c 5 @@ -1163,8 +1163,8 @@ 0 0 0 - ..\RT-Thread-1.1.1\src\scheduler.c - scheduler.c + ..\RT-Thread-1.2.2\src\thread.c + thread.c 5 @@ -1177,11 +1177,18 @@ 0 0 0 - ..\RT-Thread-1.1.1\src\slab.c - slab.c + ..\RT-Thread-1.2.2\src\timer.c + timer.c + + + + RT-Thread Drivers + 0 + 0 + 0 - 5 + 6 51 1 0 @@ -1191,11 +1198,11 @@ 0 0 0 - ..\RT-Thread-1.1.1\src\thread.c - thread.c + ..\RT-Thread-1.2.2\components\drivers\src\completion.c + completion.c - 5 + 6 52 1 0 @@ -1205,29 +1212,22 @@ 0 0 0 - ..\RT-Thread-1.1.1\src\timer.c - timer.c + ..\RT-Thread-1.2.2\components\drivers\src\dataqueue.c + dataqueue.c - - - - FreeModbusSlave - 0 - 0 - 0 6 53 1 0 0 - 4 + 0 0 - 357 - 376 + 0 + 0 0 - ..\FreeModbus\modbus\mb.c - mb.c + ..\RT-Thread-1.2.2\components\drivers\src\pipe.c + pipe.c 6 @@ -1240,8 +1240,8 @@ 0 0 0 - ..\FreeModbus\modbus\functions\mbfunccoils.c - mbfunccoils.c + ..\RT-Thread-1.2.2\components\drivers\src\portal.c + portal.c 6 @@ -1254,8 +1254,8 @@ 0 0 0 - ..\FreeModbus\modbus\functions\mbfuncdiag.c - mbfuncdiag.c + ..\RT-Thread-1.2.2\components\drivers\src\ringbuffer.c + ringbuffer.c 6 @@ -1268,26 +1268,89 @@ 0 0 0 - ..\FreeModbus\modbus\functions\mbfuncdisc.c - mbfuncdisc.c + ..\RT-Thread-1.2.2\components\drivers\src\wrokqueue.c + wrokqueue.c + + + + FreeModbusSlave + 1 + 0 + 0 - 6 + 7 57 1 0 0 0 0 - 65 - 90 + 0 + 0 + 0 + ..\FreeModbus\modbus\mb.c + mb.c + + + 7 + 58 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + ..\FreeModbus\modbus\functions\mbfunccoils.c + mbfunccoils.c + + + 7 + 59 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + ..\FreeModbus\modbus\functions\mbfuncdiag.c + mbfuncdiag.c + + + 7 + 60 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + ..\FreeModbus\modbus\functions\mbfuncdisc.c + mbfuncdisc.c + + + 7 + 61 + 1 + 0 + 0 + 0 + 0 + 0 + 0 0 ..\FreeModbus\modbus\functions\mbfuncholding.c mbfuncholding.c - 6 - 58 + 7 + 62 1 0 0 @@ -1300,8 +1363,8 @@ mbfuncinput.c - 6 - 59 + 7 + 63 1 0 0 @@ -1314,8 +1377,8 @@ mbfuncother.c - 6 - 60 + 7 + 64 1 0 0 @@ -1328,8 +1391,8 @@ mbutils.c - 6 - 61 + 7 + 65 1 0 0 @@ -1342,22 +1405,22 @@ mbcrc.c - 6 - 62 + 7 + 66 1 0 0 - 22 + 0 0 - 139 - 160 + 0 + 0 0 ..\FreeModbus\modbus\rtu\mbrtu.c mbrtu.c - 6 - 63 + 7 + 67 1 0 0 @@ -1370,8 +1433,8 @@ port.c - 6 - 64 + 7 + 68 1 0 0 @@ -1383,69 +1446,6 @@ ..\FreeModbus\port\portevent.c portevent.c - - 6 - 65 - 1 - 0 - 0 - 0 - 0 - 56 - 56 - 0 - ..\FreeModbus\port\portserial.c - portserial.c - - - 6 - 66 - 1 - 0 - 0 - 10 - 0 - 69 - 83 - 0 - ..\FreeModbus\port\porttimer.c - porttimer.c - - - 6 - 67 - 1 - 0 - 0 - 0 - 0 - 102 - 112 - 0 - ..\FreeModbus\port\user_mb_app.c - user_mb_app.c - - - - - FreeModbusMaster - 0 - 0 - 0 - - 7 - 68 - 1 - 0 - 0 - 0 - 0 - 299 - 334 - 0 - ..\FreeModbus\modbus\mb_m.c - mb_m.c - 7 69 @@ -1454,67 +1454,11 @@ 0 0 0 - 328 - 341 - 0 - ..\FreeModbus\modbus\rtu\mbrtu_m.c - mbrtu_m.c - - - 7 - 73 - 1 - 0 - 0 - 0 - 0 0 0 0 - ..\FreeModbus\modbus\functions\mbfuncholding_m.c - mbfuncholding_m.c - - - 7 - 74 - 1 - 0 - 0 - 0 - 0 - 0 - 0 - 0 - ..\FreeModbus\modbus\functions\mbfunccoils_m.c - mbfunccoils_m.c - - - 7 - 75 - 1 - 0 - 0 - 0 - 0 - 0 - 0 - 0 - ..\FreeModbus\modbus\functions\mbfuncinput_m.c - mbfuncinput_m.c - - - 7 - 76 - 1 - 0 - 0 - 0 - 0 - 0 - 0 - 0 - ..\FreeModbus\modbus\functions\mbfuncdisc_m.c - mbfuncdisc_m.c + ..\FreeModbus\port\portserial.c + portserial.c 7 @@ -1527,8 +1471,8 @@ 0 0 0 - ..\FreeModbus\port\portevent_m.c - portevent_m.c + ..\FreeModbus\port\porttimer.c + porttimer.c 7 @@ -1538,29 +1482,148 @@ 0 0 0 - 77 - 77 + 0 + 0 + 0 + ..\FreeModbus\port\user_mb_app.c + user_mb_app.c + + + + + FreeModbusMaster + 0 + 0 + 0 + + 8 + 72 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + ..\FreeModbus\modbus\mb_m.c + mb_m.c + + + 8 + 73 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + ..\FreeModbus\modbus\rtu\mbrtu_m.c + mbrtu_m.c + + + 8 + 74 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + ..\FreeModbus\modbus\functions\mbfuncholding_m.c + mbfuncholding_m.c + + + 8 + 75 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + ..\FreeModbus\modbus\functions\mbfunccoils_m.c + mbfunccoils_m.c + + + 8 + 76 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + ..\FreeModbus\modbus\functions\mbfuncinput_m.c + mbfuncinput_m.c + + + 8 + 77 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + ..\FreeModbus\modbus\functions\mbfuncdisc_m.c + mbfuncdisc_m.c + + + 8 + 78 + 1 + 0 + 0 + 0 + 0 + 0 + 0 + 0 + ..\FreeModbus\port\portevent_m.c + portevent_m.c + + + 8 + 79 + 1 + 0 + 0 + 0 + 0 + 0 + 0 0 ..\FreeModbus\port\portserial_m.c portserial_m.c - 7 - 72 + 8 + 80 1 0 0 - 17 + 0 0 - 49 - 72 + 0 + 0 0 ..\FreeModbus\port\porttimer_m.c porttimer_m.c - 7 - 0 + 8 + 81 1 0 0 @@ -1589,17 +1652,17 @@ -1 - 259 - 220 - 1480 - 898 + 234 + 234 + 1494 + 971 0 - 60 - 01000000040000000100000001000000010000000100000001000000FFFFFFFF00000000010000000100000000000000280000002800000000000000 + 274 + 01000000040000000100000001000000010000000100000001000000FFFFFFFF000000000100000001000000000000002800000028000000010000000100000000000000010000004A443A5C50726F6772616D5C5265706F7369746F72795C467265654D6F646275735F536C6176652D4D61737465722D5254542D53544D33325C4150505C7372635C6170705F7461736B2E63000000000A6170705F7461736B2E6300000000FFDC7800FFFFFFFF0100000010000000C5D4F200FFDC7800BECEA100F0A0A100BCA8E1009CC1B600F7B88600D9ADC200A5C2D700B3A6BE00EAD6A300F6FA7D00B5E99D005FC3CF00C1838300CACAD500010000000100000002000000E6000000660000009006000016030000 @@ -1622,7 +1685,27 @@ 16 - 8501000035010000F7040000C0010000 + B50000006600000027040000F1000000 + + + + 1 + 1 + 0 + 0 + 0 + 0 + 32767 + 0 + 4096 + 0 + + 16 + 0200000002000000020100003C010000 + + + 16 + 0A0000000A0000006E0000006E000000 @@ -1638,7 +1721,7 @@ 0 16 - 0300000066000000DF000000E7020000 + 0300000066000000DF000000E6020000 16 @@ -1658,7 +1741,7 @@ 0 16 - 0300000066000000DF000000E7020000 + 0300000066000000DF000000E6020000 16 @@ -1785,6 +1868,26 @@ 62020000FD000000780400006C030000 + + 183 + 183 + 1 + 0 + 0 + 0 + 32767 + 0 + 4096 + 0 + + 16 + 02000000160000000200000030000000 + + + 16 + 0A0000000A0000006E0000006E000000 + + 1913 1913 @@ -1865,6 +1968,26 @@ 62020000FD000000780400006C030000 + + 1938 + 1938 + 0 + 0 + 0 + 0 + 32767 + 0 + 16384 + 0 + + 16 + 000000000000000052010000D6010000 + + + 16 + B7000000CD00000009020000A3020000 + + 1939 1939 @@ -1878,7 +2001,7 @@ 0 16 - 030000001B0300008D060000B0030000 + 030000001A0300008D060000AF030000 16 @@ -1898,7 +2021,7 @@ 0 16 - 030000001B0300008D060000B0030000 + 030000001A0300008D060000AF030000 16 @@ -1918,7 +2041,7 @@ 0 16 - 030000001B0300008D060000B0030000 + 030000001A0300008D060000AF030000 16 @@ -1938,7 +2061,7 @@ 0 16 - 030000001B0300008D060000B0030000 + 030000001A0300008D060000AF030000 16 @@ -1978,7 +2101,7 @@ 0 16 - 0300000066000000DF000000E7020000 + 0300000066000000DF000000E6020000 16 @@ -1998,7 +2121,7 @@ 0 16 - 0300000066000000DF000000E7020000 + 0300000066000000DF000000E6020000 16 @@ -2018,7 +2141,7 @@ 0 16 - 000000001803000090060000C9030000 + 000000001703000090060000C8030000 16 @@ -2058,7 +2181,7 @@ 0 16 - 030000001B0300008D060000B0030000 + 030000001A0300008D060000AF030000 16 @@ -2125,6 +2248,46 @@ 0A0000000A0000006E0000006E000000 + + 2506 + 2506 + 0 + 0 + 0 + 0 + 32767 + 0 + 4096 + 0 + + 16 + 13030000660000009D040000A6010000 + + + 16 + B7000000CD000000470200005D020000 + + + + 2507 + 2507 + 0 + 0 + 0 + 0 + 32767 + 0 + 4096 + 0 + + 16 + 03000000C60100009D0400001F020000 + + + 16 + B7000000CD0000000703000042010000 + + 343 343 @@ -2618,7 +2781,7 @@ 0 16 - 0300000066000000DF000000E7020000 + 0300000066000000DF000000E6020000 16 @@ -2645,6 +2808,66 @@ BD030000C30100002B0600004E020000 + + 436 + 436 + 0 + 0 + 0 + 0 + 32767 + 0 + 4096 + 0 + + 16 + 03000000B10200003D0600001A030000 + + + 16 + B7000000CD00000060010000A3020000 + + + + 437 + 437 + 0 + 0 + 0 + 0 + 32767 + 0 + 4096 + 0 + + 16 + 03000000C60100009D0400001F020000 + + + 16 + B7000000CD000000470200005D020000 + + + + 440 + 440 + 0 + 0 + 0 + 0 + 32767 + 0 + 4096 + 0 + + 16 + 03000000C60100009D0400001F020000 + + + 16 + B7000000CD000000470200005D020000 + + 49710 49710 @@ -2665,6 +2888,26 @@ 0A0000000A0000006E0000006E000000 + + 49777 + 49777 + 1 + 0 + 0 + 0 + 32767 + 0 + 4096 + 0 + + 16 + FA0300007F0000009D0400009A000000 + + + 16 + 0A0000000A0000006E0000006E000000 + + 49799 49799 @@ -2825,6 +3068,26 @@ 0A0000000A0000006E0000006E000000 + + 50009 + 50009 + 1 + 0 + 0 + 0 + 32767 + 0 + 4096 + 0 + + 16 + FA0300007C0000001B04000097000000 + + + 16 + 0A0000000A0000006E0000006E000000 + + 50027 50027 @@ -2885,6 +3148,46 @@ 0A0000000A0000006E0000006E000000 + + 50125 + 50125 + 1 + 0 + 0 + 0 + 32767 + 0 + 4096 + 0 + + 16 + FA0300007F0000009D0400009A000000 + + + 16 + 0A0000000A0000006E0000006E000000 + + + + 50211 + 50211 + 1 + 0 + 0 + 0 + 32767 + 0 + 4096 + 0 + + 16 + 2E0400007F000000D90400009A000000 + + + 16 + 0A0000000A0000006E0000006E000000 + + 50234 50234 @@ -2925,6 +3228,166 @@ 0A0000000A0000006E0000006E000000 + + 50310 + 50310 + 0 + 0 + 0 + 0 + 32767 + 0 + 4096 + 0 + + 16 + 03000000C702000003000000C7020000 + + + 16 + 0A0000000A0000006E0000006E000000 + + + + 50311 + 50311 + 1 + 0 + 0 + 0 + 32767 + 0 + 4096 + 0 + + 16 + 130300007C0000009D04000097000000 + + + 16 + 0A0000000A0000006E0000006E000000 + + + + 50312 + 50312 + 0 + 0 + 0 + 0 + 32767 + 0 + 4096 + 0 + + 16 + 03000000DC01000093010000F7010000 + + + 16 + 0A0000000A0000006E0000006E000000 + + + + 50313 + 50313 + 0 + 0 + 0 + 0 + 32767 + 0 + 4096 + 0 + + 16 + 03000000DC01000093010000F7010000 + + + 16 + 0A0000000A0000006E0000006E000000 + + + + 50314 + 50314 + 1 + 0 + 0 + 0 + 32767 + 0 + 4096 + 0 + + 16 + 03000000DC0100009D040000F7010000 + + + 16 + 0A0000000A0000006E0000006E000000 + + + + 50315 + 50315 + 1 + 0 + 0 + 0 + 32767 + 0 + 4096 + 0 + + 16 + 03000000DC0100009D040000F7010000 + + + 16 + 0A0000000A0000006E0000006E000000 + + + + 50316 + 50316 + 0 + 0 + 0 + 0 + 32767 + 0 + 4096 + 0 + + 16 + 03000000DC01000093010000F7010000 + + + 16 + 0A0000000A0000006E0000006E000000 + + + + 50317 + 50317 + 1 + 0 + 0 + 0 + 32767 + 0 + 4096 + 0 + + 16 + 130300007C0000009D04000097000000 + + + 16 + 0A0000000A0000006E0000006E000000 + + 59392 59392 @@ -2958,7 +3421,7 @@ 0 16 - 00000000C903000090060000DC030000 + 00000000C803000090060000DB030000 16 @@ -3065,16 +3528,36 @@ 0A0000000A0000006E0000006E000000 + + 59400 + 59400 + 0 + 0 + 0 + 0 + 612 + 0 + 8192 + 2 + + 16 + 00000000380000006F02000054000000 + + + 16 + 0A0000000A0000006E0000006E000000 + + 2569 - 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 + 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 59392 File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uild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src\app_task.c + 5 + 43 + 43 + + + + + diff --git a/RVMDK/FreeModbus_Slave&Master+RTT+STM32_uvproj.bak b/RVMDK/FreeModbus_Slave&Master+RTT+STM32_uvproj.bak index eee83db..4422624 100644 --- a/RVMDK/FreeModbus_Slave&Master+RTT+STM32_uvproj.bak +++ b/RVMDK/FreeModbus_Slave&Master+RTT+STM32_uvproj.bak @@ -400,11 +400,6 @@ 1 ..\APP\src\stm32f10x_it.c - - cpuusage.c - 1 - ..\APP\src\cpuusage.c - delay_conf.h 5 @@ -431,24 +426,14 @@ ..\BSP\src\bsp.c - backtrace.c - 1 - ..\RT-Thread-1.1.1\libcpu\arm\common\backtrace.c - - - showmem.c - 1 - ..\RT-Thread-1.1.1\libcpu\arm\common\showmem.c + context_rvds.S + 2 + ..\RT-Thread-1.2.2\libcpu\arm\cortex-m3\context_rvds.S cpuport.c 1 - ..\RT-Thread-1.1.1\libcpu\arm\cortex-m3\cpuport.c - - - context_rvds.S - 2 - ..\RT-Thread-1.1.1\libcpu\arm\cortex-m3\context_rvds.S + ..\RT-Thread-1.2.2\libcpu\arm\cortex-m3\cpuport.c @@ -593,77 +578,117 @@ clock.c 1 - ..\RT-Thread-1.1.1\src\clock.c + ..\RT-Thread-1.2.2\src\clock.c + + + cpuusage.c + 1 + ..\RT-Thread-1.2.2\src\cpuusage.c device.c 1 - ..\RT-Thread-1.1.1\src\device.c + ..\RT-Thread-1.2.2\src\device.c idle.c 1 - ..\RT-Thread-1.1.1\src\idle.c + ..\RT-Thread-1.2.2\src\idle.c ipc.c 1 - ..\RT-Thread-1.1.1\src\ipc.c + ..\RT-Thread-1.2.2\src\ipc.c irq.c 1 - ..\RT-Thread-1.1.1\src\irq.c + ..\RT-Thread-1.2.2\src\irq.c kservice.c 1 - ..\RT-Thread-1.1.1\src\kservice.c + ..\RT-Thread-1.2.2\src\kservice.c mem.c 1 - ..\RT-Thread-1.1.1\src\mem.c + ..\RT-Thread-1.2.2\src\mem.c memheap.c 1 - ..\RT-Thread-1.1.1\src\memheap.c + ..\RT-Thread-1.2.2\src\memheap.c mempool.c 1 - ..\RT-Thread-1.1.1\src\mempool.c + ..\RT-Thread-1.2.2\src\mempool.c module.c 1 - ..\RT-Thread-1.1.1\src\module.c + ..\RT-Thread-1.2.2\src\module.c object.c 1 - ..\RT-Thread-1.1.1\src\object.c + ..\RT-Thread-1.2.2\src\object.c scheduler.c 1 - ..\RT-Thread-1.1.1\src\scheduler.c + ..\RT-Thread-1.2.2\src\scheduler.c slab.c 1 - ..\RT-Thread-1.1.1\src\slab.c + ..\RT-Thread-1.2.2\src\slab.c thread.c 1 - ..\RT-Thread-1.1.1\src\thread.c + ..\RT-Thread-1.2.2\src\thread.c timer.c 1 - ..\RT-Thread-1.1.1\src\timer.c + ..\RT-Thread-1.2.2\src\timer.c + + + + + RT-Thread Drivers + + + completion.c + 1 + ..\RT-Thread-1.2.2\components\drivers\src\completion.c + + + dataqueue.c + 1 + ..\RT-Thread-1.2.2\components\drivers\src\dataqueue.c + + + pipe.c + 1 + ..\RT-Thread-1.2.2\components\drivers\src\pipe.c + + + portal.c + 1 + ..\RT-Thread-1.2.2\components\drivers\src\portal.c + + + ringbuffer.c + 1 + ..\RT-Thread-1.2.2\components\drivers\src\ringbuffer.c + + + wrokqueue.c + 1 + ..\RT-Thread-1.2.2\components\drivers\src\wrokqueue.c @@ -1128,7 +1153,7 @@ 0 - 2 + 1 1 0 1 @@ -1143,7 +1168,7 @@ USE_STDPERIPH_DRIVER,STM32F10X_MD - ..\Libaries\CMSIS_MDK\CM3\CoreSupport;..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x;..\Libaries\STM32F10x_StdPeriph_Driver\inc;..\Libaries\USB-FS-Device_Driver\inc;..\BSP\inc;..\APP\inc;..\RT-Thread-1.1.1\include;..\RT-Thread-1.1.1\libcpu\arm\stm32;..\FreeModbus\modbus\include;..\FreeModbus\modbus\rtu;..\FreeModbus\port + ..\Libaries\CMSIS_MDK\CM3\CoreSupport;..\Libaries\CMSIS_MDK\CM3\DeviceSupport\ST\STM32F10x;..\Libaries\STM32F10x_StdPeriph_Driver\inc;..\Libaries\USB-FS-Device_Driver\inc;..\BSP\inc;..\APP\inc;..\RT-Thread-1.2.2\include;..\RT-Thread-1.2.2\components\drivers\include;..\RT-Thread-1.2.2\components\drivers\include\drivers;..\FreeModbus\modbus\include;..\FreeModbus\modbus\rtu;..\FreeModbus\port @@ -1198,11 +1223,6 @@ 1 ..\APP\src\stm32f10x_it.c - - cpuusage.c - 1 - ..\APP\src\cpuusage.c - delay_conf.h 5 @@ -1229,24 +1249,14 @@ ..\BSP\src\bsp.c - backtrace.c - 1 - ..\RT-Thread-1.1.1\libcpu\arm\common\backtrace.c - - - showmem.c - 1 - ..\RT-Thread-1.1.1\libcpu\arm\common\showmem.c + context_rvds.S + 2 + ..\RT-Thread-1.2.2\libcpu\arm\cortex-m3\context_rvds.S cpuport.c 1 - ..\RT-Thread-1.1.1\libcpu\arm\cortex-m3\cpuport.c - - - context_rvds.S - 2 - ..\RT-Thread-1.1.1\libcpu\arm\cortex-m3\context_rvds.S + ..\RT-Thread-1.2.2\libcpu\arm\cortex-m3\cpuport.c @@ -1391,77 +1401,117 @@ clock.c 1 - ..\RT-Thread-1.1.1\src\clock.c + ..\RT-Thread-1.2.2\src\clock.c + + + cpuusage.c + 1 + ..\RT-Thread-1.2.2\src\cpuusage.c device.c 1 - ..\RT-Thread-1.1.1\src\device.c + ..\RT-Thread-1.2.2\src\device.c idle.c 1 - ..\RT-Thread-1.1.1\src\idle.c + ..\RT-Thread-1.2.2\src\idle.c ipc.c 1 - ..\RT-Thread-1.1.1\src\ipc.c + ..\RT-Thread-1.2.2\src\ipc.c irq.c 1 - ..\RT-Thread-1.1.1\src\irq.c + ..\RT-Thread-1.2.2\src\irq.c kservice.c 1 - ..\RT-Thread-1.1.1\src\kservice.c + ..\RT-Thread-1.2.2\src\kservice.c mem.c 1 - ..\RT-Thread-1.1.1\src\mem.c + ..\RT-Thread-1.2.2\src\mem.c memheap.c 1 - ..\RT-Thread-1.1.1\src\memheap.c + ..\RT-Thread-1.2.2\src\memheap.c mempool.c 1 - ..\RT-Thread-1.1.1\src\mempool.c + ..\RT-Thread-1.2.2\src\mempool.c module.c 1 - ..\RT-Thread-1.1.1\src\module.c + ..\RT-Thread-1.2.2\src\module.c object.c 1 - ..\RT-Thread-1.1.1\src\object.c + ..\RT-Thread-1.2.2\src\object.c scheduler.c 1 - ..\RT-Thread-1.1.1\src\scheduler.c + ..\RT-Thread-1.2.2\src\scheduler.c slab.c 1 - ..\RT-Thread-1.1.1\src\slab.c + ..\RT-Thread-1.2.2\src\slab.c thread.c 1 - ..\RT-Thread-1.1.1\src\thread.c + ..\RT-Thread-1.2.2\src\thread.c timer.c 1 - ..\RT-Thread-1.1.1\src\timer.c + ..\RT-Thread-1.2.2\src\timer.c + + + + + RT-Thread Drivers + + + completion.c + 1 + ..\RT-Thread-1.2.2\components\drivers\src\completion.c + + + dataqueue.c + 1 + ..\RT-Thread-1.2.2\components\drivers\src\dataqueue.c + + + pipe.c + 1 + ..\RT-Thread-1.2.2\components\drivers\src\pipe.c + + + portal.c + 1 + ..\RT-Thread-1.2.2\components\drivers\src\portal.c + + + ringbuffer.c + 1 + ..\RT-Thread-1.2.2\components\drivers\src\ringbuffer.c + + + wrokqueue.c + 1 + ..\RT-Thread-1.2.2\components\drivers\src\wrokqueue.c diff --git a/RVMDK/JLinkLog.txt b/RVMDK/JLinkLog.txt index be43c72..53a076f 100644 --- a/RVMDK/JLinkLog.txt +++ b/RVMDK/JLinkLog.txt @@ -1,835 +1,976 @@ -T0AF0 000:870 SEGGER J-Link V4.15n (beta) Log File (0000ms, 0869ms total) -T0AF0 000:870 DLL Compiled: Jun 18 2010 19:55:09 (0000ms, 0869ms total) -T0AF0 000:870 Logging started @ 2014-10-27 19:30 (0000ms, 0869ms total) -T0AF0 000:870 JLINK_SetWarnOutHandler(...) (0000ms, 0869ms total) -T0AF0 000:870 JLINK_OpenEx(...) +T183C 000:850 SEGGER J-Link V4.15n (beta) Log File (0001ms, 0849ms total) +T183C 000:850 DLL Compiled: Jun 18 2010 19:55:09 (0001ms, 0849ms total) +T183C 000:850 Logging started @ 2014-11-07 15:59 (0001ms, 0849ms total) +T183C 000:851 JLINK_SetWarnOutHandler(...) (0000ms, 0850ms total) +T183C 000:851 JLINK_OpenEx(...) Firmware: J-Link ARM V7 compiled Jun 20 2012 19:45:53 Hardware: V7.00 S/N: 19087980 -Feature(s): RDI, FlashDL, FlashBP, JFlash, GDBFull returns O.K. (0186ms, 0869ms total) -T0AF0 001:056 JLINK_SetErrorOutHandler(...) (0000ms, 1055ms total) -T0AF0 001:057 JLINK_ExecCommand("ProjectFile = "D:\Program\Repository\FreeModbus_Slave-Master-RTT-STM32\RVMDK\JLinkSettings.ini"", ...) returns 0x00 (0000ms, 1055ms total) -T0AF0 001:059 JLINK_ExecCommand("DisableConnectionTimeout", ...) returns 0x00 (0000ms, 1055ms total) -T0AF0 001:059 JLINK_TIF_Select(JLINKARM_TIF_JTAG) returns 0x00 (0000ms, 1055ms total) -T0AF0 001:059 JLINK_SetSpeed(2000) (0000ms, 1055ms total) -T0AF0 001:059 JLINK_GetHardwareVersion() returns 0x11170 (0000ms, 1055ms total) -T0AF0 001:059 JLINK_GetDLLVersion() returns 41514 (0000ms, 1055ms total) -T0AF0 001:059 JLINK_GetFirmwareString(...) (0000ms, 1055ms total) -T0AF0 001:064 JLINK_GetDLLVersion() returns 41514 (0000ms, 1055ms total) -T0AF0 001:064 JLINK_GetCompileDateTime() (0000ms, 1055ms total) -T0AF0 001:065 JLINK_GetFirmwareString(...) (0000ms, 1055ms total) -T0AF0 001:067 JLINK_GetHardwareVersion() returns 0x11170 (0000ms, 1055ms total) -T0AF0 001:071 JLINK_Reset() >0x2F8 JTAG>TotalIRLen = 9, IRPrint = 0x0011 >0x30 JTAG> >0x210 JTAG> >0x118 JTAG> >0xD8 JTAG> >0x198 JTAG> >0x38 JTAG> >0x118 JTAG> >0xD8 JTAG> >0x2F0 JTAG> >0x2F0 JTAG> >0x198 JTAG> >0x198 JTAG>Found Cortex-M3 r1p1, Little endian. >0xD8 JTAG> >0x240 JTAG> >0x198 JTAG> >0x198 JTAG>TPIU fitted. >0x198 JTAG> >0x198 JTAG> FPUnit: 6 code (BP) slots and 2 literal slots >0x198 JTAG> >0x250 JTAG> >0x240 JTAG> >0x280 JTAG> >0x198 JTAG> >0x198 JTAG> >0x198 JTAG> >0x198 JTAG> - >0x198 JTAG> >0x240 JTAG> >0x240 JTAG> >0x198 JTAG> >0x198 JTAG> >0x17A8 JTAG> >0x240 JTAG> >0x198 JTAG> >0x17A8 JTAG> >0x198 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> (0072ms, 1055ms total) -T0AF0 001:143 JLINK_GetIdData(...) ScanLen=9 NumDevices=2 aId[0]=0x3BA00477 aIrRead[0]=0 aScanLen[0]=0 aScanRead[0]=0 (0000ms, 1127ms total) -T0AF0 001:143 JLINK_JTAG_GetDeviceID(DeviceIndex = 0) returns 0x3BA00477 (0000ms, 1127ms total) -T0AF0 001:143 JLINK_JTAG_GetDeviceInfo(DeviceIndex = 0) returns 0x00 (0000ms, 1127ms total) -T0AF0 001:143 JLINK_JTAG_GetDeviceID(DeviceIndex = 1) returns 0x16410041 (0000ms, 1127ms total) -T0AF0 001:143 JLINK_JTAG_GetDeviceInfo(DeviceIndex = 1) returns 0x00 (0000ms, 1127ms total) -T0AF0 001:143 JLINK_GetDebugInfo(0x100) -- Value=0xE00FF003 returns 0x00 (0000ms, 1127ms total) -T0AF0 001:145 JLINK_ReadMem (0xE00FF000, 0x0018 Bytes, ...) >0x320 JTAG> -- Data: 03 F0 F0 FF 03 20 F0 FF 03 30 F0 FF 03 10 F0 FF ... returns 0x00 (0001ms, 1127ms total) -T0AF0 001:146 JLINK_ReadMemU32(0xE000ED00, 0x0001 Items, ...) >0x1F0 JTAG> -- Data: 31 C2 1F 41 returns 0x01 (0001ms, 1128ms total) -T0AF0 001:148 JLINK_Halt() returns 0x00 (0000ms, 1129ms total) -T0AF0 001:148 JLINK_IsHalted() returns TRUE (0000ms, 1129ms total) -T0AF0 001:148 JLINK_ReadMemU32(0xE000EDF0, 0x0001 Items, ...) >0x1F0 JTAG> -- Data: 03 00 03 00 returns 0x01 (0001ms, 1129ms total) -T0AF0 001:149 JLINK_WriteU32(0xE000EDF0, 0xA05F0003) >0x1F0 JTAG> returns 0x00 (0001ms, 1130ms total) -T0AF0 001:150 JLINK_WriteU32(0xE000EDFC, 0x01000000) >0x1F0 JTAG> returns 0x00 (0001ms, 1131ms total) -T0AF0 001:151 JLINK_ReadMemU32(0xE0002000, 0x0001 Items, ...) >0x1F0 JTAG> -- Data: 60 02 00 00 returns 0x01 (0001ms, 1132ms total) -T0AF0 001:152 JLINK_ReadMemU32(0xE0001000, 0x0001 Items, ...) >0x1F0 JTAG> -- Data: 01 00 00 40 returns 0x01 (0001ms, 1133ms total) -T0AF0 001:159 JLINK_ExecCommand("Device = STM32F103CB", ...) +Feature(s): RDI, FlashDL, FlashBP, JFlash, GDBFull returns O.K. (0153ms, 0850ms total) +T183C 001:004 JLINK_SetErrorOutHandler(...) (0000ms, 1003ms total) +T183C 001:004 JLINK_ExecCommand("ProjectFile = "D:\Program\Repository\FreeModbus_Slave-Master-RTT-STM32\RVMDK\JLinkSettings.ini"", ...) returns 0x00 (0001ms, 1003ms total) +T183C 001:007 JLINK_ExecCommand("DisableConnectionTimeout", ...) returns 0x00 (0000ms, 1004ms total) +T183C 001:007 JLINK_TIF_Select(JLINKARM_TIF_JTAG) returns 0x00 (0000ms, 1004ms total) +T183C 001:007 JLINK_SetSpeed(2000) (0001ms, 1004ms total) +T183C 001:008 JLINK_GetHardwareVersion() returns 0x11170 (0000ms, 1005ms total) +T183C 001:008 JLINK_GetDLLVersion() returns 41514 (0000ms, 1005ms total) +T183C 001:008 JLINK_GetFirmwareString(...) (0000ms, 1005ms total) +T183C 001:013 JLINK_GetDLLVersion() returns 41514 (0000ms, 1005ms total) +T183C 001:013 JLINK_GetCompileDateTime() (0000ms, 1005ms total) +T183C 001:014 JLINK_GetFirmwareString(...) (0000ms, 1005ms total) +T183C 001:015 JLINK_GetHardwareVersion() returns 0x11170 (0000ms, 1005ms total) +T183C 001:020 JLINK_Reset() >0x2F8 JTAG>TotalIRLen = 9, IRPrint = 0x0011 >0x30 JTAG> >0x210 JTAG> >0x118 JTAG> >0xD8 JTAG> >0x198 JTAG> >0x38 JTAG> >0x118 JTAG> >0xD8 JTAG> >0x2F0 JTAG> >0x2F0 JTAG> >0x198 JTAG> >0x198 JTAG>Found Cortex-M3 r1p1, Little endian. >0xD8 JTAG> >0x240 JTAG> >0x198 JTAG> >0x198 JTAG>TPIU fitted. >0x198 JTAG> >0x198 JTAG> FPUnit: 6 code (BP) slots and 2 literal slots >0x198 JTAG> >0x250 JTAG> >0x240 JTAG> >0x280 JTAG> >0x198 JTAG> >0x198 JTAG> >0x198 JTAG> >0x198 JTAG> + >0x240 JTAG> >0x240 JTAG> >0x198 JTAG> >0x198 JTAG> >0x17A8 JTAG> >0x240 JTAG> >0x198 JTAG> >0x17A8 JTAG> >0x198 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> (0069ms, 1005ms total) +T183C 001:089 JLINK_GetIdData(...) ScanLen=9 NumDevices=2 aId[0]=0x3BA00477 aIrRead[0]=0 aScanLen[0]=0 aScanRead[0]=0 (0001ms, 1074ms total) +T183C 001:090 JLINK_JTAG_GetDeviceID(DeviceIndex = 0) returns 0x3BA00477 (0000ms, 1075ms total) +T183C 001:090 JLINK_JTAG_GetDeviceInfo(DeviceIndex = 0) returns 0x00 (0000ms, 1075ms total) +T183C 001:090 JLINK_JTAG_GetDeviceID(DeviceIndex = 1) returns 0x16410041 (0000ms, 1075ms total) +T183C 001:090 JLINK_JTAG_GetDeviceInfo(DeviceIndex = 1) returns 0x00 (0000ms, 1075ms total) +T183C 001:090 JLINK_GetDebugInfo(0x100) -- Value=0xE00FF003 returns 0x00 (0000ms, 1075ms total) +T183C 001:091 JLINK_ReadMem (0xE00FF000, 0x0018 Bytes, ...) >0x320 JTAG> -- Data: 03 F0 F0 FF 03 20 F0 FF 03 30 F0 FF 03 10 F0 FF ... returns 0x00 (0002ms, 1075ms total) +T183C 001:093 JLINK_ReadMemU32(0xE000ED00, 0x0001 Items, ...) >0x1F0 JTAG> -- Data: 31 C2 1F 41 returns 0x01 (0001ms, 1077ms total) +T183C 001:095 JLINK_Halt() returns 0x00 (0000ms, 1078ms total) +T183C 001:095 JLINK_IsHalted() returns TRUE (0000ms, 1078ms total) +T183C 001:095 JLINK_ReadMemU32(0xE000EDF0, 0x0001 Items, ...) >0x1F0 JTAG> -- Data: 03 00 03 00 returns 0x01 (0001ms, 1078ms total) +T183C 001:096 JLINK_WriteU32(0xE000EDF0, 0xA05F0003) >0x1F0 JTAG> returns 0x00 (0001ms, 1079ms total) +T183C 001:097 JLINK_WriteU32(0xE000EDFC, 0x01000000) >0x1F0 JTAG> returns 0x00 (0002ms, 1080ms total) +T183C 001:099 JLINK_ReadMemU32(0xE0002000, 0x0001 Items, ...) >0x1F0 JTAG> -- Data: 60 02 00 00 returns 0x01 (0001ms, 1082ms total) +T183C 001:100 JLINK_ReadMemU32(0xE0001000, 0x0001 Items, ...) >0x1F0 JTAG> -- Data: 01 00 00 40 returns 0x01 (0001ms, 1083ms total) +T183C 001:112 JLINK_ExecCommand("Device = STM32F103CB", ...) JLINK_ExecCommand("map ram 0x20000000 - 0x20004FFF", ...) returns 0x00 (0000ms, 0000ms total) JLINK_AddMirrorAreaEx(Addr = 0x00000000, Size = 0x00000000) (0000ms, 0000ms total) - returns 0x00 (0001ms, 1134ms total) -T0AF0 001:160 JLINK_GetHWStatus(...) returns 0x00 (0000ms, 1135ms total) -T0AF0 001:166 JLINK_GetNumBPUnits(Type = 0xFFFFFF00) >0x2F8 JTAG>TotalIRLen = 9, IRPrint = 0x0011 >0x30 JTAG> >0x210 JTAG> >0x118 JTAG> >0xD8 JTAG> >0x198 JTAG> >0x38 JTAG> >0x118 JTAG> >0xD8 JTAG> >0x2F0 JTAG> >0x2F0 JTAG> >0x198 JTAG> >0x198 JTAG>Found Cortex-M3 r1p1, Little endian. >0xD8 JTAG> >0x240 JTAG> >0x198 JTAG> >0x198 JTAG>TPIU fitted. >0x198 JTAG> >0x198 JTAG> FPUnit: 6 code (BP) slots and 2 literal slots >0x198 JTAG> returns 0x06 (0026ms, 1135ms total) -T0AF0 001:192 JLINK_GetNumBPUnits(Type = 0xF0) returns 0x800 (0000ms, 1161ms total) -T0AF0 001:192 JLINK_GetNumWPUnits() returns 0x04 (0000ms, 1161ms total) -T0AF0 001:196 JLINK_GetSpeed() returns 0x7D0 (0000ms, 1161ms total) -T0AF0 001:199 JLINK_ReadMemU32(0xE000E004, 0x0001 Items, ...) >0x200 JTAG> -- Data: 01 00 00 00 returns 0x01 (0001ms, 1161ms total) -T0AF0 001:200 JLINK_WriteMem(0xE0001000, 0x001C Bytes, ...) -- Data: 01 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 ... >0x310 JTAG> returns 0x1C (0001ms, 1162ms total) -T0AF0 001:201 JLINK_ReadMem (0xE0001000, 0x001C Bytes, ...) >0x358 JTAG> -- Data: 01 00 00 40 00 00 00 00 00 00 00 00 00 00 00 00 ... returns 0x00 (0002ms, 1163ms total) -T0AF0 001:203 JLINK_Halt() returns 0x00 (0000ms, 1165ms total) -T0AF0 001:203 JLINK_IsHalted() returns TRUE (0000ms, 1165ms total) -T0AF0 001:204 JLINK_WriteMem(0x20000000, 0x0164 Bytes, ...) -- Data: 00 BE 0A E0 0D 78 2D 06 68 40 08 24 40 00 00 D3 ... >0x1270 JTAG> returns 0x164 (0005ms, 1165ms total) -T0AF0 001:209 JLINK_WriteReg(R0, 0x08000000) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_WriteReg(R1, 0x007A1200) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_WriteReg(R2, 0x00000001) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_WriteReg(R15, 0x20000038) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1170ms total) -T0AF0 001:209 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) >0x1F0 JTAG> returns 0x00000001 (0001ms, 1170ms total) -T0AF0 001:210 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0027ms, 1171ms total) -T0AF0 001:237 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1198ms total) -T0AF0 001:245 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_ClrBPEx(BPHandle = 0x00000001) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(R0, 0x08000000) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(R1, 0x007A1200) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(R2, 0x00000001) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(R15, 0x2000007C) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000002 (0000ms, 1198ms total) -T0AF0 001:245 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0014ms, 1198ms total) -T0AF0 001:259 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1212ms total) -T0AF0 001:311 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0007ms, 1212ms total) -T0AF0 001:318 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1212ms total) -T0AF0 001:318 JLINK_ClrBPEx(BPHandle = 0x00000002) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:318 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(R0, 0x00000001) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(R1, 0x007A1200) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(R2, 0x00000001) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(R15, 0x2000006A) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000003 (0000ms, 1212ms total) -T0AF0 001:371 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0014ms, 1212ms total) -T0AF0 001:385 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1226ms total) -T0AF0 001:393 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1226ms total) -T0AF0 001:393 JLINK_ClrBPEx(BPHandle = 0x00000003) returns 0x00 (0000ms, 1226ms total) -T0AF0 001:393 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1226ms total) -T0AF0 001:399 JLINK_WriteMem(0x20000000, 0x0164 Bytes, ...) -- Data: 00 BE 0A E0 0D 78 2D 06 68 40 08 24 40 00 00 D3 ... >0x1270 JTAG> returns 0x164 (0005ms, 1226ms total) -T0AF0 001:404 JLINK_WriteReg(R0, 0x08000000) returns 0x00 (0000ms, 1231ms total) -T0AF0 001:404 JLINK_WriteReg(R1, 0x007A1200) returns 0x00 (0000ms, 1231ms total) -T0AF0 001:404 JLINK_WriteReg(R2, 0x00000002) returns 0x00 (0000ms, 1231ms total) -T0AF0 001:404 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1231ms total) -T0AF0 001:404 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1231ms total) -T0AF0 001:404 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1231ms total) -T0AF0 001:404 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1231ms total) -T0AF0 001:404 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1231ms total) -T0AF0 001:404 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0001ms, 1231ms total) -T0AF0 001:405 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1232ms total) -T0AF0 001:405 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1232ms total) -T0AF0 001:405 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1232ms total) -T0AF0 001:405 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1232ms total) -T0AF0 001:405 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1232ms total) -T0AF0 001:405 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1232ms total) -T0AF0 001:405 JLINK_WriteReg(R15, 0x20000038) returns 0x00 (0000ms, 1232ms total) -T0AF0 001:405 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1232ms total) -T0AF0 001:405 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1232ms total) -T0AF0 001:405 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1232ms total) -T0AF0 001:405 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1232ms total) -T0AF0 001:405 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) >0x1F0 JTAG> returns 0x00000004 (0001ms, 1232ms total) -T0AF0 001:406 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1233ms total) -T0AF0 001:422 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1249ms total) -T0AF0 001:430 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1249ms total) -T0AF0 001:430 JLINK_ClrBPEx(BPHandle = 0x00000004) returns 0x00 (0000ms, 1249ms total) -T0AF0 001:430 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1249ms total) -T0AF0 001:430 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: B0 34 00 20 BD 02 00 08 1D 06 00 08 73 02 00 08 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1249ms total) -T0AF0 001:441 JLINK_WriteReg(R0, 0x08000000) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000005 (0000ms, 1260ms total) -T0AF0 001:441 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0017ms, 1260ms total) -T0AF0 001:458 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1277ms total) -T0AF0 001:511 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1277ms total) -T0AF0 001:519 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1277ms total) -T0AF0 001:519 JLINK_ClrBPEx(BPHandle = 0x00000005) returns 0x00 (0000ms, 1277ms total) -T0AF0 001:519 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1277ms total) -T0AF0 001:519 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 07 00 85 46 18 B0 20 B5 FF F7 66 FF BD E8 20 40 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1277ms total) -T0AF0 001:530 JLINK_WriteReg(R0, 0x08000400) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000006 (0000ms, 1288ms total) -T0AF0 001:530 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1288ms total) -T0AF0 001:546 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1304ms total) -T0AF0 001:598 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1304ms total) -T0AF0 001:606 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1304ms total) -T0AF0 001:606 JLINK_ClrBPEx(BPHandle = 0x00000006) returns 0x00 (0000ms, 1304ms total) -T0AF0 001:606 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1304ms total) -T0AF0 001:606 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 05 F4 E0 61 09 0A 10 4D 6B 5C 45 68 DD 40 85 60 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1304ms total) -T0AF0 001:617 JLINK_WriteReg(R0, 0x08000800) returns 0x00 (0000ms, 1315ms total) -T0AF0 001:617 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1315ms total) -T0AF0 001:617 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1315ms total) -T0AF0 001:617 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1315ms total) -T0AF0 001:617 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1315ms total) -T0AF0 001:617 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1315ms total) -T0AF0 001:617 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1315ms total) -T0AF0 001:617 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1315ms total) -T0AF0 001:617 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1315ms total) -T0AF0 001:617 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1315ms total) -T0AF0 001:617 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1315ms total) -T0AF0 001:617 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1315ms total) -T0AF0 001:617 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1315ms total) -T0AF0 001:617 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1315ms total) -T0AF0 001:617 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1315ms total) -T0AF0 001:617 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1315ms total) -T0AF0 001:617 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0001ms, 1315ms total) -T0AF0 001:618 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1316ms total) -T0AF0 001:618 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1316ms total) -T0AF0 001:618 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1316ms total) -T0AF0 001:618 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000007 (0000ms, 1316ms total) -T0AF0 001:618 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0015ms, 1316ms total) -T0AF0 001:633 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1331ms total) -T0AF0 001:685 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1331ms total) -T0AF0 001:693 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1331ms total) -T0AF0 001:693 JLINK_ClrBPEx(BPHandle = 0x00000007) returns 0x00 (0000ms, 1331ms total) -T0AF0 001:693 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1331ms total) -T0AF0 001:693 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 23 FF 40 F2 25 51 0C 48 00 F0 40 F8 01 28 06 D1 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1331ms total) -T0AF0 001:704 JLINK_WriteReg(R0, 0x08000C00) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:704 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:704 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:704 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:704 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:704 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:704 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:704 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:704 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:704 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:704 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:704 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:704 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:704 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:704 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:704 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:704 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:705 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:705 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:705 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1342ms total) -T0AF0 001:705 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000008 (0000ms, 1342ms total) -T0AF0 001:705 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1342ms total) -T0AF0 001:721 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1358ms total) -T0AF0 001:772 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0007ms, 1358ms total) -T0AF0 001:779 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1358ms total) -T0AF0 001:779 JLINK_ClrBPEx(BPHandle = 0x00000008) returns 0x00 (0000ms, 1358ms total) -T0AF0 001:779 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1358ms total) -T0AF0 001:780 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 64 2D FC D3 02 F0 46 FD 80 1B 0A 28 F0 D3 01 F0 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1358ms total) -T0AF0 001:791 JLINK_WriteReg(R0, 0x08001000) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000009 (0000ms, 1369ms total) -T0AF0 001:791 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0017ms, 1369ms total) -T0AF0 001:808 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1386ms total) -T0AF0 001:860 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1386ms total) -T0AF0 001:868 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1386ms total) -T0AF0 001:868 JLINK_ClrBPEx(BPHandle = 0x00000009) returns 0x00 (0000ms, 1386ms total) -T0AF0 001:868 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1386ms total) -T0AF0 001:868 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 00 90 01 E0 03 20 00 90 00 98 BD E8 FC 9F 00 00 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1386ms total) -T0AF0 001:879 JLINK_WriteReg(R0, 0x08001400) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1397ms total) -T0AF0 001:879 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x0000000A (0000ms, 1397ms total) -T0AF0 001:879 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0018ms, 1397ms total) -T0AF0 001:897 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1415ms total) -T0AF0 001:949 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1415ms total) -T0AF0 001:957 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1415ms total) -T0AF0 001:957 JLINK_ClrBPEx(BPHandle = 0x0000000A) returns 0x00 (0000ms, 1415ms total) -T0AF0 001:957 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1415ms total) -T0AF0 001:957 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 00 0F 09 D0 40 46 01 F0 F5 F8 82 46 04 E0 4F F0 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1415ms total) -T0AF0 001:968 JLINK_WriteReg(R0, 0x08001800) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1426ms total) -T0AF0 001:968 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x0000000B (0000ms, 1426ms total) -T0AF0 001:968 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1426ms total) -T0AF0 001:984 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1442ms total) -T0AF0 002:036 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1442ms total) -T0AF0 002:044 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1442ms total) -T0AF0 002:044 JLINK_ClrBPEx(BPHandle = 0x0000000B) returns 0x00 (0000ms, 1442ms total) -T0AF0 002:044 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1442ms total) -T0AF0 002:044 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 7C 02 00 20 6D 1E 00 08 88 02 00 20 8C 02 00 20 ... >0x31C0 JTAG> returns 0x400 (0010ms, 1442ms total) -T0AF0 002:054 JLINK_WriteReg(R0, 0x08001C00) returns 0x00 (0001ms, 1452ms total) -T0AF0 002:055 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1453ms total) -T0AF0 002:055 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1453ms total) -T0AF0 002:055 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1453ms total) -T0AF0 002:055 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1453ms total) -T0AF0 002:055 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1453ms total) -T0AF0 002:055 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1453ms total) -T0AF0 002:055 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1453ms total) -T0AF0 002:055 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1453ms total) -T0AF0 002:055 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1453ms total) -T0AF0 002:055 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1453ms total) -T0AF0 002:055 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1453ms total) -T0AF0 002:055 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1453ms total) -T0AF0 002:055 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1453ms total) -T0AF0 002:055 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1453ms total) -T0AF0 002:055 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1453ms total) -T0AF0 002:055 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1453ms total) -T0AF0 002:055 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1453ms total) -T0AF0 002:055 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1453ms total) -T0AF0 002:055 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1453ms total) -T0AF0 002:055 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x0000000C (0000ms, 1453ms total) -T0AF0 002:055 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0015ms, 1453ms total) -T0AF0 002:071 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1468ms total) -T0AF0 002:123 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1468ms total) -T0AF0 002:131 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1468ms total) -T0AF0 002:131 JLINK_ClrBPEx(BPHandle = 0x0000000C) returns 0x00 (0000ms, 1468ms total) -T0AF0 002:131 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1468ms total) -T0AF0 002:131 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: BA F1 00 0F 03 D0 BA F1 01 0F 4F D1 26 E0 0E E0 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1468ms total) -T0AF0 002:142 JLINK_WriteReg(R0, 0x08002000) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1479ms total) -T0AF0 002:142 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x0000000D (0000ms, 1479ms total) -T0AF0 002:142 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1479ms total) -T0AF0 002:158 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1495ms total) -T0AF0 002:210 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1495ms total) -T0AF0 002:218 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1495ms total) -T0AF0 002:218 JLINK_ClrBPEx(BPHandle = 0x0000000D) returns 0x00 (0000ms, 1495ms total) -T0AF0 002:218 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1495ms total) -T0AF0 002:219 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 34 00 27 49 09 78 88 42 0A D1 27 48 00 EB C4 00 ... >0x31C0 JTAG> returns 0x400 (0010ms, 1495ms total) -T0AF0 002:229 JLINK_WriteReg(R0, 0x08002400) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:229 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:229 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:229 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:229 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:229 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:229 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:229 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:229 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:229 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:230 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:230 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:230 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:230 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:230 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:230 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:230 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:230 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:230 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:230 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1505ms total) -T0AF0 002:230 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x0000000E (0000ms, 1505ms total) -T0AF0 002:230 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0015ms, 1505ms total) -T0AF0 002:245 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1520ms total) -T0AF0 002:297 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1520ms total) -T0AF0 002:305 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1520ms total) -T0AF0 002:305 JLINK_ClrBPEx(BPHandle = 0x0000000E) returns 0x00 (0000ms, 1520ms total) -T0AF0 002:305 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1520ms total) -T0AF0 002:305 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 02 98 BD E8 FE 8F 00 00 E0 01 00 20 D8 01 00 20 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1520ms total) -T0AF0 002:316 JLINK_WriteReg(R0, 0x08002800) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1531ms total) -T0AF0 002:316 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x0000000F (0001ms, 1531ms total) -T0AF0 002:317 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1532ms total) -T0AF0 002:333 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1548ms total) -T0AF0 002:385 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1548ms total) -T0AF0 002:393 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1548ms total) -T0AF0 002:393 JLINK_ClrBPEx(BPHandle = 0x0000000F) returns 0x00 (0000ms, 1548ms total) -T0AF0 002:393 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1548ms total) -T0AF0 002:393 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: E9 FA 00 BF 00 98 FD F7 E5 FA 00 BF 25 B9 00 20 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1548ms total) -T0AF0 002:404 JLINK_WriteReg(R0, 0x08002C00) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000010 (0000ms, 1559ms total) -T0AF0 002:404 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0017ms, 1559ms total) -T0AF0 002:421 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1576ms total) -T0AF0 002:473 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1576ms total) -T0AF0 002:481 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1576ms total) -T0AF0 002:481 JLINK_ClrBPEx(BPHandle = 0x00000010) returns 0x00 (0000ms, 1576ms total) -T0AF0 002:481 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1576ms total) -T0AF0 002:481 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 0D 1A 00 BF 00 BF 28 46 00 F0 51 FC 00 20 70 BD ... >0x31C0 JTAG> returns 0x400 (0011ms, 1576ms total) -T0AF0 002:492 JLINK_WriteReg(R0, 0x08003000) returns 0x00 (0001ms, 1587ms total) -T0AF0 002:493 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000011 (0000ms, 1588ms total) -T0AF0 002:493 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1588ms total) -T0AF0 002:509 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1604ms total) -T0AF0 002:561 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1604ms total) -T0AF0 002:569 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1604ms total) -T0AF0 002:569 JLINK_ClrBPEx(BPHandle = 0x00000011) returns 0x00 (0000ms, 1604ms total) -T0AF0 002:569 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1604ms total) -T0AF0 002:569 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 70 B5 04 46 00 BF 12 48 00 68 18 B1 20 46 10 49 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1604ms total) -T0AF0 002:580 JLINK_WriteReg(R0, 0x08003400) returns 0x00 (0000ms, 1615ms total) -T0AF0 002:580 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1615ms total) -T0AF0 002:580 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1615ms total) -T0AF0 002:580 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1615ms total) -T0AF0 002:580 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1615ms total) -T0AF0 002:580 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1615ms total) -T0AF0 002:580 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1615ms total) -T0AF0 002:580 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1615ms total) -T0AF0 002:580 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1615ms total) -T0AF0 002:580 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1615ms total) -T0AF0 002:580 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1615ms total) -T0AF0 002:580 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1615ms total) -T0AF0 002:580 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1615ms total) -T0AF0 002:580 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1615ms total) -T0AF0 002:580 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1615ms total) -T0AF0 002:580 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1615ms total) -T0AF0 002:580 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0001ms, 1615ms total) -T0AF0 002:581 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1616ms total) -T0AF0 002:581 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1616ms total) -T0AF0 002:581 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1616ms total) -T0AF0 002:581 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000012 (0000ms, 1616ms total) -T0AF0 002:581 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0015ms, 1616ms total) -T0AF0 002:596 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1631ms total) -T0AF0 002:648 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0007ms, 1631ms total) -T0AF0 002:655 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1631ms total) -T0AF0 002:655 JLINK_ClrBPEx(BPHandle = 0x00000012) returns 0x00 (0001ms, 1631ms total) -T0AF0 002:656 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1632ms total) -T0AF0 002:656 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: FF F7 0E FB 20 46 FF F7 B1 FC 00 BF 03 48 FF F7 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1632ms total) -T0AF0 002:667 JLINK_WriteReg(R0, 0x08003800) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000013 (0000ms, 1643ms total) -T0AF0 002:667 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0017ms, 1643ms total) -T0AF0 002:684 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1660ms total) -T0AF0 002:736 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1660ms total) -T0AF0 002:744 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1660ms total) -T0AF0 002:744 JLINK_ClrBPEx(BPHandle = 0x00000013) returns 0x00 (0000ms, 1660ms total) -T0AF0 002:744 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1660ms total) -T0AF0 002:744 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: FF F7 FC FA 43 46 3A 46 31 46 20 46 CD F8 00 90 ... >0x31C0 JTAG> returns 0x400 (0010ms, 1660ms total) -T0AF0 002:754 JLINK_WriteReg(R0, 0x08003C00) returns 0x00 (0000ms, 1670ms total) -T0AF0 002:754 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1670ms total) -T0AF0 002:754 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0001ms, 1670ms total) -T0AF0 002:755 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1671ms total) -T0AF0 002:755 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1671ms total) -T0AF0 002:755 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1671ms total) -T0AF0 002:755 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1671ms total) -T0AF0 002:755 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1671ms total) -T0AF0 002:755 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1671ms total) -T0AF0 002:755 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1671ms total) -T0AF0 002:755 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1671ms total) -T0AF0 002:755 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1671ms total) -T0AF0 002:755 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1671ms total) -T0AF0 002:755 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1671ms total) -T0AF0 002:755 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1671ms total) -T0AF0 002:755 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1671ms total) -T0AF0 002:755 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1671ms total) -T0AF0 002:755 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1671ms total) -T0AF0 002:755 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1671ms total) -T0AF0 002:755 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1671ms total) -T0AF0 002:755 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000014 (0000ms, 1671ms total) -T0AF0 002:755 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1671ms total) -T0AF0 002:771 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1687ms total) -T0AF0 002:823 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1687ms total) -T0AF0 002:831 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1687ms total) -T0AF0 002:831 JLINK_ClrBPEx(BPHandle = 0x00000014) returns 0x00 (0000ms, 1687ms total) -T0AF0 002:831 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1687ms total) -T0AF0 002:831 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 27 71 02 48 FC F7 6C FE 70 BD 00 00 00 44 00 40 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1687ms total) -T0AF0 002:842 JLINK_WriteReg(R0, 0x08004000) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000015 (0000ms, 1698ms total) -T0AF0 002:842 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1698ms total) -T0AF0 002:858 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1714ms total) -T0AF0 002:910 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1714ms total) -T0AF0 002:918 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1714ms total) -T0AF0 002:918 JLINK_ClrBPEx(BPHandle = 0x00000015) returns 0x00 (0000ms, 1714ms total) -T0AF0 002:918 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1714ms total) -T0AF0 002:919 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: CA E7 00 00 00 08 01 40 00 0C 01 40 00 44 00 40 ... >0x31C0 JTAG> returns 0x400 (0010ms, 1714ms total) -T0AF0 002:929 JLINK_WriteReg(R0, 0x08004400) returns 0x00 (0000ms, 1724ms total) -T0AF0 002:929 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1724ms total) -T0AF0 002:929 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1724ms total) -T0AF0 002:929 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1724ms total) -T0AF0 002:929 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0001ms, 1724ms total) -T0AF0 002:930 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1725ms total) -T0AF0 002:930 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1725ms total) -T0AF0 002:930 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1725ms total) -T0AF0 002:930 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1725ms total) -T0AF0 002:930 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1725ms total) -T0AF0 002:930 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1725ms total) -T0AF0 002:930 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1725ms total) -T0AF0 002:930 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1725ms total) -T0AF0 002:930 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1725ms total) -T0AF0 002:930 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1725ms total) -T0AF0 002:930 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1725ms total) -T0AF0 002:930 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1725ms total) -T0AF0 002:930 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1725ms total) -T0AF0 002:930 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1725ms total) -T0AF0 002:930 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1725ms total) -T0AF0 002:930 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000016 (0000ms, 1725ms total) -T0AF0 002:930 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1725ms total) -T0AF0 002:946 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1741ms total) -T0AF0 002:999 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1741ms total) -T0AF0 003:007 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1741ms total) -T0AF0 003:007 JLINK_ClrBPEx(BPHandle = 0x00000016) returns 0x00 (0000ms, 1741ms total) -T0AF0 003:007 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1741ms total) -T0AF0 003:008 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 8D F8 07 00 01 A8 FB F7 11 FF FB F7 3D FE 01 20 ... >0x31C0 JTAG> returns 0x400 (0010ms, 1741ms total) -T0AF0 003:018 JLINK_WriteReg(R0, 0x08004800) returns 0x00 (0000ms, 1751ms total) -T0AF0 003:018 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1751ms total) -T0AF0 003:018 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1751ms total) -T0AF0 003:018 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1751ms total) -T0AF0 003:018 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1751ms total) -T0AF0 003:018 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1751ms total) -T0AF0 003:018 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1751ms total) -T0AF0 003:018 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0001ms, 1751ms total) -T0AF0 003:019 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1752ms total) -T0AF0 003:019 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1752ms total) -T0AF0 003:019 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1752ms total) -T0AF0 003:019 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1752ms total) -T0AF0 003:019 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1752ms total) -T0AF0 003:019 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1752ms total) -T0AF0 003:019 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1752ms total) -T0AF0 003:019 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1752ms total) -T0AF0 003:019 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1752ms total) -T0AF0 003:019 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1752ms total) -T0AF0 003:019 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1752ms total) -T0AF0 003:019 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1752ms total) -T0AF0 003:019 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000017 (0000ms, 1752ms total) -T0AF0 003:019 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0015ms, 1752ms total) -T0AF0 003:034 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1767ms total) -T0AF0 003:086 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1767ms total) -T0AF0 003:094 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1767ms total) -T0AF0 003:094 JLINK_ClrBPEx(BPHandle = 0x00000017) returns 0x00 (0000ms, 1767ms total) -T0AF0 003:094 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1767ms total) -T0AF0 003:095 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 80 41 00 C1 81 40 01 C0 80 41 01 C0 80 41 00 C1 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1767ms total) -T0AF0 003:106 JLINK_WriteReg(R0, 0x08004C00) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_WriteReg(R1, 0x00000290) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000018 (0000ms, 1778ms total) -T0AF0 003:106 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1778ms total) -T0AF0 003:122 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1794ms total) -T0AF0 003:174 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1794ms total) -T0AF0 003:182 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1794ms total) -T0AF0 003:182 JLINK_ClrBPEx(BPHandle = 0x00000018) returns 0x00 (0000ms, 1794ms total) -T0AF0 003:182 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1794ms total) -T0AF0 003:182 JLINK_WriteReg(R0, 0x00000002) returns 0x00 (0000ms, 1794ms total) -T0AF0 003:182 JLINK_WriteReg(R1, 0x00000290) returns 0x00 (0000ms, 1794ms total) -T0AF0 003:182 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1794ms total) -T0AF0 003:182 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1794ms total) -T0AF0 003:182 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1794ms total) -T0AF0 003:182 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1794ms total) -T0AF0 003:182 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1794ms total) -T0AF0 003:182 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1794ms total) -T0AF0 003:182 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1794ms total) -T0AF0 003:182 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1794ms total) -T0AF0 003:182 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1794ms total) -T0AF0 003:182 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0001ms, 1794ms total) -T0AF0 003:183 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1795ms total) -T0AF0 003:183 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1795ms total) -T0AF0 003:183 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1795ms total) -T0AF0 003:183 JLINK_WriteReg(R15, 0x2000006A) returns 0x00 (0000ms, 1795ms total) -T0AF0 003:183 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1795ms total) -T0AF0 003:183 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1795ms total) -T0AF0 003:183 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1795ms total) -T0AF0 003:183 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1795ms total) -T0AF0 003:183 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000019 (0000ms, 1795ms total) -T0AF0 003:183 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0015ms, 1795ms total) -T0AF0 003:198 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0007ms, 1810ms total) -T0AF0 003:205 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1810ms total) -T0AF0 003:205 JLINK_ClrBPEx(BPHandle = 0x00000019) returns 0x00 (0000ms, 1810ms total) -T0AF0 003:205 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1810ms total) -T0AF0 003:260 JLINK_WriteMem(0x20000000, 0x0164 Bytes, ...) -- Data: 00 BE 0A E0 0D 78 2D 06 68 40 08 24 40 00 00 D3 ... >0x1270 JTAG> returns 0x164 (0005ms, 1810ms total) -T0AF0 003:265 JLINK_WriteReg(R0, 0x08000000) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_WriteReg(R1, 0x007A1200) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_WriteReg(R2, 0x00000003) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_WriteReg(R15, 0x20000038) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1815ms total) -T0AF0 003:265 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) >0x1F0 JTAG> returns 0x0000001A (0001ms, 1815ms total) -T0AF0 003:266 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0015ms, 1816ms total) -T0AF0 003:281 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1831ms total) -T0AF0 003:289 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1831ms total) -T0AF0 003:289 JLINK_ClrBPEx(BPHandle = 0x0000001A) returns 0x00 (0000ms, 1831ms total) -T0AF0 003:289 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1831ms total) -T0AF0 003:289 JLINK_WriteReg(R0, 0xFFFFFFFF) returns 0x00 (0000ms, 1831ms total) -T0AF0 003:289 JLINK_WriteReg(R1, 0x08000000) returns 0x00 (0000ms, 1831ms total) -T0AF0 003:289 JLINK_WriteReg(R2, 0x00004E90) returns 0x00 (0000ms, 1831ms total) -T0AF0 003:289 JLINK_WriteReg(R3, 0x04C11DB7) returns 0x00 (0000ms, 1831ms total) -T0AF0 003:289 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1831ms total) -T0AF0 003:289 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1831ms total) -T0AF0 003:289 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0001ms, 1831ms total) -T0AF0 003:290 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1832ms total) -T0AF0 003:290 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1832ms total) -T0AF0 003:290 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1832ms total) -T0AF0 003:290 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1832ms total) -T0AF0 003:290 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1832ms total) -T0AF0 003:290 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1832ms total) -T0AF0 003:290 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1832ms total) -T0AF0 003:290 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1832ms total) -T0AF0 003:290 JLINK_WriteReg(R15, 0x20000002) returns 0x00 (0000ms, 1832ms total) -T0AF0 003:290 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1832ms total) -T0AF0 003:290 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1832ms total) -T0AF0 003:290 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1832ms total) -T0AF0 003:290 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1832ms total) -T0AF0 003:290 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x0000001B (0000ms, 1832ms total) -T0AF0 003:290 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0015ms, 1832ms total) -T0AF0 003:305 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1847ms total) -T0AF0 003:357 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1847ms total) -T0AF0 003:409 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1847ms total) -T0AF0 003:461 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1847ms total) -T0AF0 003:513 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1847ms total) -T0AF0 003:565 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1847ms total) -T0AF0 003:573 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1847ms total) -T0AF0 003:573 JLINK_ClrBPEx(BPHandle = 0x0000001B) returns 0x00 (0000ms, 1847ms total) -T0AF0 003:573 JLINK_ReadReg(R0) returns 0xFAC1812C (0000ms, 1847ms total) -T0AF0 003:575 JLINK_WriteReg(R0, 0x00000003) returns 0x00 (0000ms, 1847ms total) -T0AF0 003:575 JLINK_WriteReg(R1, 0x08000000) returns 0x00 (0000ms, 1847ms total) -T0AF0 003:575 JLINK_WriteReg(R2, 0x00004E90) returns 0x00 (0000ms, 1847ms total) -T0AF0 003:575 JLINK_WriteReg(R3, 0x04C11DB7) returns 0x00 (0000ms, 1847ms total) -T0AF0 003:575 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1847ms total) -T0AF0 003:575 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1847ms total) -T0AF0 003:575 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1847ms total) -T0AF0 003:575 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1847ms total) -T0AF0 003:576 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1848ms total) -T0AF0 003:576 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1848ms total) -T0AF0 003:576 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1848ms total) -T0AF0 003:576 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1848ms total) -T0AF0 003:576 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1848ms total) -T0AF0 003:576 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1848ms total) -T0AF0 003:576 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1848ms total) -T0AF0 003:576 JLINK_WriteReg(R15, 0x2000006A) returns 0x00 (0000ms, 1848ms total) -T0AF0 003:576 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1848ms total) -T0AF0 003:576 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1848ms total) -T0AF0 003:576 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1848ms total) -T0AF0 003:576 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1848ms total) -T0AF0 003:576 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x0000001C (0000ms, 1848ms total) -T0AF0 003:576 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0014ms, 1848ms total) -T0AF0 003:590 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0009ms, 1862ms total) -T0AF0 003:599 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1862ms total) -T0AF0 003:599 JLINK_ClrBPEx(BPHandle = 0x0000001C) returns 0x00 (0000ms, 1862ms total) -T0AF0 003:599 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1862ms total) -T0AF0 003:653 JLINK_WriteU32(0xE000EDFC, 0x00000000) >0x1F0 JTAG> returns 0x00 (0002ms, 1862ms total) -T0AF0 003:655 JLINK_SetResetType(JLINKARM_RESET_TYPE_NORMAL) returns JLINKARM_RESET_TYPE_NORMAL (0000ms, 1864ms total) -T0AF0 003:655 JLINK_Reset() >0x2F8 JTAG>TotalIRLen = 9, IRPrint = 0x0011 >0x30 JTAG> >0x210 JTAG> >0x118 JTAG> >0xD8 JTAG> >0x198 JTAG> >0x38 JTAG> >0x118 JTAG> >0xD8 JTAG> >0x2F0 JTAG> >0x2F0 JTAG> >0x198 JTAG> >0x198 JTAG>Found Cortex-M3 r1p1, Little endian. >0xD8 JTAG> >0x240 JTAG> >0x198 JTAG> >0x198 JTAG>TPIU fitted. >0x198 JTAG> >0x198 JTAG> FPUnit: 6 code (BP) slots and 2 literal slots >0x198 JTAG> >0x250 JTAG> >0x240 JTAG> >0x280 JTAG> >0x198 JTAG> >0x198 JTAG> >0x198 JTAG> >0x198 JTAG> - >0x240 JTAG> >0x240 JTAG> >0x198 JTAG> >0x198 JTAG> >0x240 JTAG> >0x198 JTAG> >0x17A8 JTAG> >0x198 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> (0069ms, 1864ms total) -T0AF0 003:727 JLINK_Close() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x240 JTAG> >0x240 JTAG> >0x08 JTAG> (0062ms, 1933ms total) + returns 0x00 (0000ms, 1084ms total) +T183C 001:112 JLINK_GetHWStatus(...) returns 0x00 (0001ms, 1084ms total) +T183C 001:121 JLINK_GetNumBPUnits(Type = 0xFFFFFF00) >0x2F8 JTAG>TotalIRLen = 9, IRPrint = 0x0011 >0x30 JTAG> >0x210 JTAG> >0x118 JTAG> >0xD8 JTAG> >0x198 JTAG> >0x38 JTAG> >0x118 JTAG> >0xD8 JTAG> >0x2F0 JTAG> >0x2F0 JTAG> >0x198 JTAG> >0x198 JTAG>Found Cortex-M3 r1p1, Little endian. >0xD8 JTAG> >0x240 JTAG> >0x198 JTAG> >0x198 JTAG>TPIU fitted. >0x198 JTAG> >0x198 JTAG> FPUnit: 6 code (BP) slots and 2 literal slots >0x198 JTAG> returns 0x06 (0032ms, 1085ms total) +T183C 001:153 JLINK_GetNumBPUnits(Type = 0xF0) returns 0x800 (0000ms, 1117ms total) +T183C 001:153 JLINK_GetNumWPUnits() returns 0x04 (0000ms, 1117ms total) +T183C 001:161 JLINK_GetSpeed() returns 0x7D0 (0000ms, 1117ms total) +T183C 001:166 JLINK_ReadMemU32(0xE000E004, 0x0001 Items, ...) >0x200 JTAG> -- Data: 01 00 00 00 returns 0x01 (0001ms, 1117ms total) +T183C 001:167 JLINK_WriteMem(0xE0001000, 0x001C Bytes, ...) -- Data: 01 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 ... >0x310 JTAG> returns 0x1C (0002ms, 1118ms total) +T183C 001:169 JLINK_ReadMem (0xE0001000, 0x001C Bytes, ...) >0x358 JTAG> -- Data: 01 00 00 40 00 00 00 00 00 00 00 00 00 00 00 00 ... returns 0x00 (0001ms, 1120ms total) +T183C 001:170 JLINK_Halt() returns 0x00 (0000ms, 1121ms total) +T183C 001:170 JLINK_IsHalted() returns TRUE (0000ms, 1121ms total) +T183C 001:177 JLINK_WriteMem(0x20000000, 0x0164 Bytes, ...) -- Data: 00 BE 0A E0 0D 78 2D 06 68 40 08 24 40 00 00 D3 ... >0x1270 JTAG> returns 0x164 (0005ms, 1121ms total) +T183C 001:182 JLINK_WriteReg(R0, 0x08000000) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_WriteReg(R1, 0x007A1200) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_WriteReg(R2, 0x00000001) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_WriteReg(R15, 0x20000038) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1126ms total) +T183C 001:182 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) >0x1F0 JTAG> returns 0x00000001 (0001ms, 1126ms total) +T183C 001:183 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0027ms, 1127ms total) +T183C 001:210 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1154ms total) +T183C 001:218 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1154ms total) +T183C 001:218 JLINK_ClrBPEx(BPHandle = 0x00000001) returns 0x00 (0000ms, 1154ms total) +T183C 001:218 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(R0, 0x08000000) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(R1, 0x007A1200) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(R2, 0x00000001) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(R15, 0x2000007C) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1154ms total) +T183C 001:219 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000002 (0000ms, 1154ms total) +T183C 001:219 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0014ms, 1154ms total) +T183C 001:233 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1168ms total) +T183C 001:285 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1168ms total) +T183C 001:293 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1168ms total) +T183C 001:293 JLINK_ClrBPEx(BPHandle = 0x00000002) returns 0x00 (0000ms, 1168ms total) +T183C 001:293 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1168ms total) +T183C 001:344 JLINK_WriteReg(R0, 0x00000001) returns 0x00 (0000ms, 1168ms total) +T183C 001:344 JLINK_WriteReg(R1, 0x007A1200) returns 0x00 (0001ms, 1168ms total) +T183C 001:345 JLINK_WriteReg(R2, 0x00000001) returns 0x00 (0000ms, 1169ms total) +T183C 001:345 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1169ms total) +T183C 001:345 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1169ms total) +T183C 001:345 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1169ms total) +T183C 001:345 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1169ms total) +T183C 001:345 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1169ms total) +T183C 001:345 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1169ms total) +T183C 001:345 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1169ms total) +T183C 001:345 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1169ms total) +T183C 001:345 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1169ms total) +T183C 001:345 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1169ms total) +T183C 001:345 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1169ms total) +T183C 001:345 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1169ms total) +T183C 001:345 JLINK_WriteReg(R15, 0x2000006A) returns 0x00 (0000ms, 1169ms total) +T183C 001:345 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1169ms total) +T183C 001:345 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1169ms total) +T183C 001:345 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1169ms total) +T183C 001:345 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1169ms total) +T183C 001:345 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000003 (0000ms, 1169ms total) +T183C 001:345 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0013ms, 1169ms total) +T183C 001:358 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0009ms, 1182ms total) +T183C 001:367 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1182ms total) +T183C 001:367 JLINK_ClrBPEx(BPHandle = 0x00000003) returns 0x00 (0000ms, 1182ms total) +T183C 001:367 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1182ms total) +T183C 001:374 JLINK_WriteMem(0x20000000, 0x0164 Bytes, ...) -- Data: 00 BE 0A E0 0D 78 2D 06 68 40 08 24 40 00 00 D3 ... >0x1270 JTAG> returns 0x164 (0005ms, 1182ms total) +T183C 001:379 JLINK_WriteReg(R0, 0x08000000) returns 0x00 (0000ms, 1187ms total) +T183C 001:379 JLINK_WriteReg(R1, 0x007A1200) returns 0x00 (0000ms, 1187ms total) +T183C 001:379 JLINK_WriteReg(R2, 0x00000002) returns 0x00 (0000ms, 1187ms total) +T183C 001:379 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1187ms total) +T183C 001:379 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1187ms total) +T183C 001:379 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1187ms total) +T183C 001:379 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1187ms total) +T183C 001:379 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1187ms total) +T183C 001:379 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1187ms total) +T183C 001:379 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0001ms, 1187ms total) +T183C 001:380 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1188ms total) +T183C 001:380 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1188ms total) +T183C 001:380 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1188ms total) +T183C 001:380 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1188ms total) +T183C 001:380 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1188ms total) +T183C 001:380 JLINK_WriteReg(R15, 0x20000038) returns 0x00 (0000ms, 1188ms total) +T183C 001:380 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1188ms total) +T183C 001:380 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1188ms total) +T183C 001:380 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1188ms total) +T183C 001:380 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1188ms total) +T183C 001:380 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) >0x1F0 JTAG> returns 0x00000004 (0001ms, 1188ms total) +T183C 001:381 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1189ms total) +T183C 001:397 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1205ms total) +T183C 001:405 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1205ms total) +T183C 001:405 JLINK_ClrBPEx(BPHandle = 0x00000004) returns 0x00 (0000ms, 1205ms total) +T183C 001:405 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1205ms total) +T183C 001:405 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: A8 38 00 20 BD 02 00 08 85 06 00 08 73 02 00 08 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1205ms total) +T183C 001:416 JLINK_WriteReg(R0, 0x08000000) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1216ms total) +T183C 001:416 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000005 (0000ms, 1216ms total) +T183C 001:416 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1216ms total) +T183C 001:432 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0000ms, 1232ms total) +T183C 001:483 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0007ms, 1232ms total) +T183C 001:490 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1232ms total) +T183C 001:490 JLINK_ClrBPEx(BPHandle = 0x00000005) returns 0x00 (0000ms, 1232ms total) +T183C 001:490 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1232ms total) +T183C 001:491 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 07 00 85 46 18 B0 20 B5 FF F7 66 FF BD E8 20 40 ... >0x31C0 JTAG> returns 0x400 (0010ms, 1232ms total) +T183C 001:501 JLINK_WriteReg(R0, 0x08000400) returns 0x00 (0000ms, 1242ms total) +T183C 001:501 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1242ms total) +T183C 001:501 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1242ms total) +T183C 001:501 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1242ms total) +T183C 001:501 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1242ms total) +T183C 001:501 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1242ms total) +T183C 001:501 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1242ms total) +T183C 001:501 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1242ms total) +T183C 001:501 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1242ms total) +T183C 001:501 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1242ms total) +T183C 001:501 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1242ms total) +T183C 001:501 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1242ms total) +T183C 001:501 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1242ms total) +T183C 001:501 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1242ms total) +T183C 001:501 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1242ms total) +T183C 001:501 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1242ms total) +T183C 001:501 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1242ms total) +T183C 001:501 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1242ms total) +T183C 001:501 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1242ms total) +T183C 001:501 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0001ms, 1242ms total) +T183C 001:502 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000006 (0000ms, 1243ms total) +T183C 001:502 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0015ms, 1243ms total) +T183C 001:517 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1258ms total) +T183C 001:569 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0007ms, 1258ms total) +T183C 001:576 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1258ms total) +T183C 001:576 JLINK_ClrBPEx(BPHandle = 0x00000006) returns 0x00 (0000ms, 1258ms total) +T183C 001:576 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1258ms total) +T183C 001:577 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 48 02 FF F7 DB FF 10 BD 10 B5 01 21 04 20 FF F7 ... >0x31C0 JTAG> returns 0x400 (0010ms, 1258ms total) +T183C 001:587 JLINK_WriteReg(R0, 0x08000800) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1268ms total) +T183C 001:587 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000007 (0000ms, 1268ms total) +T183C 001:587 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1268ms total) +T183C 001:603 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0000ms, 1284ms total) +T183C 001:654 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1284ms total) +T183C 001:662 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1284ms total) +T183C 001:662 JLINK_ClrBPEx(BPHandle = 0x00000007) returns 0x00 (0000ms, 1284ms total) +T183C 001:662 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1284ms total) +T183C 001:662 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 00 0C 00 40 00 10 00 40 00 14 00 40 00 40 01 40 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1284ms total) +T183C 001:673 JLINK_WriteReg(R0, 0x08000C00) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1295ms total) +T183C 001:673 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000008 (0000ms, 1295ms total) +T183C 001:673 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0015ms, 1295ms total) +T183C 001:688 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1310ms total) +T183C 001:740 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0007ms, 1310ms total) +T183C 001:747 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1310ms total) +T183C 001:747 JLINK_ClrBPEx(BPHandle = 0x00000008) returns 0x00 (0000ms, 1310ms total) +T183C 001:747 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1310ms total) +T183C 001:748 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: A5 71 65 71 C4 F8 14 80 C4 F8 18 80 4F F0 00 00 ... >0x31C0 JTAG> returns 0x400 (0010ms, 1310ms total) +T183C 001:758 JLINK_WriteReg(R0, 0x08001000) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1320ms total) +T183C 001:758 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000009 (0000ms, 1320ms total) +T183C 001:758 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0015ms, 1320ms total) +T183C 001:773 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1335ms total) +T183C 001:825 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1335ms total) +T183C 001:833 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1335ms total) +T183C 001:833 JLINK_ClrBPEx(BPHandle = 0x00000009) returns 0x00 (0000ms, 1335ms total) +T183C 001:833 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1335ms total) +T183C 001:833 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 04 EB 51 71 C9 10 49 1C 01 F0 FF 08 05 E0 20 46 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1335ms total) +T183C 001:844 JLINK_WriteReg(R0, 0x08001400) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1346ms total) +T183C 001:844 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x0000000A (0000ms, 1346ms total) +T183C 001:844 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0015ms, 1346ms total) +T183C 001:859 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1361ms total) +T183C 001:912 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1361ms total) +T183C 001:920 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1361ms total) +T183C 001:920 JLINK_ClrBPEx(BPHandle = 0x0000000A) returns 0x00 (0000ms, 1361ms total) +T183C 001:920 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1361ms total) +T183C 001:920 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: E1 17 04 EB 51 71 C9 10 49 1C 01 F0 FF 08 05 E0 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1361ms total) +T183C 001:931 JLINK_WriteReg(R0, 0x08001800) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1372ms total) +T183C 001:931 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x0000000B (0000ms, 1372ms total) +T183C 001:931 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0017ms, 1372ms total) +T183C 001:948 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1389ms total) +T183C 002:000 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1389ms total) +T183C 002:008 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1389ms total) +T183C 002:008 JLINK_ClrBPEx(BPHandle = 0x0000000B) returns 0x00 (0000ms, 1389ms total) +T183C 002:008 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1389ms total) +T183C 002:009 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 02 28 40 DB 68 46 03 F0 19 FB 00 98 40 78 06 02 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1389ms total) +T183C 002:020 JLINK_WriteReg(R0, 0x08001C00) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1400ms total) +T183C 002:020 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x0000000C (0000ms, 1400ms total) +T183C 002:020 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1400ms total) +T183C 002:036 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1416ms total) +T183C 002:088 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1416ms total) +T183C 002:096 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1416ms total) +T183C 002:096 JLINK_ClrBPEx(BPHandle = 0x0000000C) returns 0x00 (0000ms, 1416ms total) +T183C 002:096 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1416ms total) +T183C 002:097 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 36 48 00 68 90 47 39 49 08 70 00 20 03 F0 02 FA ... >0x31C0 JTAG> returns 0x400 (0011ms, 1416ms total) +T183C 002:108 JLINK_WriteReg(R0, 0x08002000) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1427ms total) +T183C 002:108 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x0000000D (0000ms, 1427ms total) +T183C 002:108 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0017ms, 1427ms total) +T183C 002:125 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1444ms total) +T183C 002:176 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1444ms total) +T183C 002:184 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1444ms total) +T183C 002:184 JLINK_ClrBPEx(BPHandle = 0x0000000D) returns 0x00 (0000ms, 1444ms total) +T183C 002:184 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1444ms total) +T183C 002:185 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 68 1A C1 17 00 EB 51 71 C9 10 A0 EB C1 01 1F FA ... >0x31C0 JTAG> returns 0x400 (0011ms, 1444ms total) +T183C 002:196 JLINK_WriteReg(R0, 0x08002400) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1455ms total) +T183C 002:196 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x0000000E (0000ms, 1455ms total) +T183C 002:196 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1455ms total) +T183C 002:212 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1471ms total) +T183C 002:264 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1471ms total) +T183C 002:272 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1471ms total) +T183C 002:272 JLINK_ClrBPEx(BPHandle = 0x0000000E) returns 0x00 (0000ms, 1471ms total) +T183C 002:272 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1471ms total) +T183C 002:272 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 04 28 10 DB 0B 48 01 88 0B 48 02 F0 C9 FC 50 B9 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1471ms total) +T183C 002:283 JLINK_WriteReg(R0, 0x08002800) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1482ms total) +T183C 002:283 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x0000000F (0000ms, 1482ms total) +T183C 002:283 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1482ms total) +T183C 002:299 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1498ms total) +T183C 002:351 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1498ms total) +T183C 002:359 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1498ms total) +T183C 002:359 JLINK_ClrBPEx(BPHandle = 0x0000000F) returns 0x00 (0000ms, 1498ms total) +T183C 002:359 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1498ms total) +T183C 002:359 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 1F FA 88 F2 00 2A EB DC 00 E0 01 20 BD E8 F0 83 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1498ms total) +T183C 002:370 JLINK_WriteReg(R0, 0x08002C00) returns 0x00 (0000ms, 1509ms total) +T183C 002:370 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1509ms total) +T183C 002:370 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1509ms total) +T183C 002:370 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1509ms total) +T183C 002:370 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1509ms total) +T183C 002:370 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1509ms total) +T183C 002:370 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1509ms total) +T183C 002:370 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1509ms total) +T183C 002:370 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1509ms total) +T183C 002:370 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1509ms total) +T183C 002:370 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1509ms total) +T183C 002:370 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1509ms total) +T183C 002:370 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0001ms, 1509ms total) +T183C 002:371 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1510ms total) +T183C 002:371 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1510ms total) +T183C 002:371 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1510ms total) +T183C 002:371 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1510ms total) +T183C 002:371 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1510ms total) +T183C 002:371 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1510ms total) +T183C 002:371 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1510ms total) +T183C 002:371 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000010 (0000ms, 1510ms total) +T183C 002:371 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0015ms, 1510ms total) +T183C 002:386 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1525ms total) +T183C 002:438 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1525ms total) +T183C 002:446 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1525ms total) +T183C 002:446 JLINK_ClrBPEx(BPHandle = 0x00000010) returns 0x00 (0000ms, 1525ms total) +T183C 002:446 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1525ms total) +T183C 002:446 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: FD D0 00 BF 27 B9 00 20 00 BF 00 28 FD D0 00 BF ... >0x31C0 JTAG> returns 0x400 (0011ms, 1525ms total) +T183C 002:457 JLINK_WriteReg(R0, 0x08003000) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1536ms total) +T183C 002:457 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000011 (0000ms, 1536ms total) +T183C 002:457 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1536ms total) +T183C 002:473 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1552ms total) +T183C 002:525 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1552ms total) +T183C 002:533 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1552ms total) +T183C 002:533 JLINK_ClrBPEx(BPHandle = 0x00000011) returns 0x00 (0000ms, 1552ms total) +T183C 002:533 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1552ms total) +T183C 002:534 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 02 0F 05 D0 E8 6A 30 42 07 D0 4F F0 00 09 04 E0 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1552ms total) +T183C 002:545 JLINK_WriteReg(R0, 0x08003400) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1563ms total) +T183C 002:545 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000012 (0000ms, 1563ms total) +T183C 002:545 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0015ms, 1563ms total) +T183C 002:560 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1578ms total) +T183C 002:612 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1578ms total) +T183C 002:620 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1578ms total) +T183C 002:620 JLINK_ClrBPEx(BPHandle = 0x00000012) returns 0x00 (0000ms, 1578ms total) +T183C 002:620 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1578ms total) +T183C 002:621 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 20 60 28 6B 18 B1 2A 6B 28 46 00 99 90 47 08 E0 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1578ms total) +T183C 002:632 JLINK_WriteReg(R0, 0x08003800) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1589ms total) +T183C 002:632 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000013 (0000ms, 1589ms total) +T183C 002:632 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1589ms total) +T183C 002:648 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1605ms total) +T183C 002:700 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1605ms total) +T183C 002:708 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1605ms total) +T183C 002:708 JLINK_ClrBPEx(BPHandle = 0x00000013) returns 0x00 (0000ms, 1605ms total) +T183C 002:708 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1605ms total) +T183C 002:709 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 08 80 4B 48 01 68 05 F1 10 00 08 44 48 49 08 60 ... >0x31C0 JTAG> returns 0x400 (0010ms, 1605ms total) +T183C 002:719 JLINK_WriteReg(R0, 0x08003C00) returns 0x00 (0000ms, 1615ms total) +T183C 002:719 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1615ms total) +T183C 002:719 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0001ms, 1615ms total) +T183C 002:720 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1616ms total) +T183C 002:720 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1616ms total) +T183C 002:720 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1616ms total) +T183C 002:720 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1616ms total) +T183C 002:720 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1616ms total) +T183C 002:720 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1616ms total) +T183C 002:720 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1616ms total) +T183C 002:720 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1616ms total) +T183C 002:720 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1616ms total) +T183C 002:720 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1616ms total) +T183C 002:720 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1616ms total) +T183C 002:720 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1616ms total) +T183C 002:720 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1616ms total) +T183C 002:720 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1616ms total) +T183C 002:720 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1616ms total) +T183C 002:720 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1616ms total) +T183C 002:720 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1616ms total) +T183C 002:720 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000014 (0000ms, 1616ms total) +T183C 002:720 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0015ms, 1616ms total) +T183C 002:735 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1631ms total) +T183C 002:787 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1631ms total) +T183C 002:795 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1631ms total) +T183C 002:795 JLINK_ClrBPEx(BPHandle = 0x00000014) returns 0x00 (0000ms, 1631ms total) +T183C 002:795 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1631ms total) +T183C 002:795 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 2A 46 01 21 20 46 FF F7 07 FF 20 46 FF F7 22 FD ... >0x31C0 JTAG> returns 0x400 (0011ms, 1631ms total) +T183C 002:806 JLINK_WriteReg(R0, 0x08004000) returns 0x00 (0000ms, 1642ms total) +T183C 002:806 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1642ms total) +T183C 002:806 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1642ms total) +T183C 002:806 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1642ms total) +T183C 002:806 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1642ms total) +T183C 002:806 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1642ms total) +T183C 002:806 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1642ms total) +T183C 002:806 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1642ms total) +T183C 002:806 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1642ms total) +T183C 002:806 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0001ms, 1642ms total) +T183C 002:807 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1643ms total) +T183C 002:807 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1643ms total) +T183C 002:807 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1643ms total) +T183C 002:807 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1643ms total) +T183C 002:807 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1643ms total) +T183C 002:807 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1643ms total) +T183C 002:807 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1643ms total) +T183C 002:807 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1643ms total) +T183C 002:807 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1643ms total) +T183C 002:807 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1643ms total) +T183C 002:807 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000015 (0000ms, 1643ms total) +T183C 002:807 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1643ms total) +T183C 002:823 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1659ms total) +T183C 002:875 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0007ms, 1659ms total) +T183C 002:882 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1659ms total) +T183C 002:882 JLINK_ClrBPEx(BPHandle = 0x00000015) returns 0x00 (0000ms, 1659ms total) +T183C 002:882 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1659ms total) +T183C 002:883 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 00 60 20 85 1E E0 16 F4 80 6F 19 D0 0C 20 FF F7 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1659ms total) +T183C 002:894 JLINK_WriteReg(R0, 0x08004400) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1670ms total) +T183C 002:894 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000016 (0000ms, 1670ms total) +T183C 002:894 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1670ms total) +T183C 002:910 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1686ms total) +T183C 002:962 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0007ms, 1686ms total) +T183C 002:969 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1686ms total) +T183C 002:970 JLINK_ClrBPEx(BPHandle = 0x00000016) returns 0x00 (0000ms, 1687ms total) +T183C 002:970 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1687ms total) +T183C 002:970 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 88 47 20 46 FF F7 32 FB 01 28 07 D1 28 46 FB F7 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1687ms total) +T183C 002:981 JLINK_WriteReg(R0, 0x08004800) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1698ms total) +T183C 002:981 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000017 (0000ms, 1698ms total) +T183C 002:981 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0017ms, 1698ms total) +T183C 002:998 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1715ms total) +T183C 003:050 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1715ms total) +T183C 003:058 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1715ms total) +T183C 003:058 JLINK_ClrBPEx(BPHandle = 0x00000017) returns 0x00 (0000ms, 1715ms total) +T183C 003:058 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1715ms total) +T183C 003:059 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 70 BD 2D E9 F8 43 04 46 0D 46 16 46 1F 46 DD E9 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1715ms total) +T183C 003:070 JLINK_WriteReg(R0, 0x08004C00) returns 0x00 (0000ms, 1726ms total) +T183C 003:070 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1726ms total) +T183C 003:070 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1726ms total) +T183C 003:070 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1726ms total) +T183C 003:070 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1726ms total) +T183C 003:070 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1726ms total) +T183C 003:070 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1726ms total) +T183C 003:070 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1726ms total) +T183C 003:070 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1726ms total) +T183C 003:070 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1726ms total) +T183C 003:070 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1726ms total) +T183C 003:070 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1726ms total) +T183C 003:070 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1726ms total) +T183C 003:070 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0001ms, 1726ms total) +T183C 003:071 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1727ms total) +T183C 003:071 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1727ms total) +T183C 003:071 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1727ms total) +T183C 003:071 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1727ms total) +T183C 003:071 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1727ms total) +T183C 003:071 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1727ms total) +T183C 003:071 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000018 (0000ms, 1727ms total) +T183C 003:071 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0015ms, 1727ms total) +T183C 003:086 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1742ms total) +T183C 003:138 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0009ms, 1742ms total) +T183C 003:147 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1742ms total) +T183C 003:147 JLINK_ClrBPEx(BPHandle = 0x00000018) returns 0x00 (0000ms, 1742ms total) +T183C 003:147 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1742ms total) +T183C 003:148 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: B0 F5 80 6F 14 D1 A0 68 A0 F5 C0 61 26 39 05 D1 ... >0x31C0 JTAG> returns 0x400 (0010ms, 1742ms total) +T183C 003:158 JLINK_WriteReg(R0, 0x08005000) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1752ms total) +T183C 003:158 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000019 (0001ms, 1752ms total) +T183C 003:159 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0015ms, 1753ms total) +T183C 003:174 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0002ms, 1768ms total) +T183C 003:227 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1768ms total) +T183C 003:235 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1768ms total) +T183C 003:235 JLINK_ClrBPEx(BPHandle = 0x00000019) returns 0x00 (0000ms, 1768ms total) +T183C 003:235 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1768ms total) +T183C 003:235 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: D8 02 00 20 10 B5 02 48 FE F7 08 FE 10 BD 00 00 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1768ms total) +T183C 003:246 JLINK_WriteReg(R0, 0x08005400) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1779ms total) +T183C 003:246 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x0000001A (0000ms, 1779ms total) +T183C 003:246 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1779ms total) +T183C 003:262 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1795ms total) +T183C 003:314 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0007ms, 1795ms total) +T183C 003:322 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1795ms total) +T183C 003:322 JLINK_ClrBPEx(BPHandle = 0x0000001A) returns 0x00 (0000ms, 1795ms total) +T183C 003:322 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1795ms total) +T183C 003:322 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 20 B1 02 28 07 D0 03 28 12 D1 09 E0 01 20 FF F7 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1795ms total) +T183C 003:333 JLINK_WriteReg(R0, 0x08005800) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1806ms total) +T183C 003:333 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x0000001B (0000ms, 1806ms total) +T183C 003:333 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1806ms total) +T183C 003:349 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1822ms total) +T183C 003:402 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1822ms total) +T183C 003:410 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1822ms total) +T183C 003:410 JLINK_ClrBPEx(BPHandle = 0x0000001B) returns 0x00 (0000ms, 1822ms total) +T183C 003:410 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1822ms total) +T183C 003:411 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: 0C 48 00 88 FF 28 09 DC 9D F8 00 20 09 49 08 88 ... >0x31C0 JTAG> returns 0x400 (0010ms, 1822ms total) +T183C 003:421 JLINK_WriteReg(R0, 0x08005C00) returns 0x00 (0000ms, 1832ms total) +T183C 003:421 JLINK_WriteReg(R1, 0x00000400) returns 0x00 (0000ms, 1832ms total) +T183C 003:421 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1832ms total) +T183C 003:421 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1832ms total) +T183C 003:421 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1832ms total) +T183C 003:421 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1832ms total) +T183C 003:421 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1832ms total) +T183C 003:421 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1832ms total) +T183C 003:421 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1832ms total) +T183C 003:421 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0001ms, 1832ms total) +T183C 003:422 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1833ms total) +T183C 003:422 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1833ms total) +T183C 003:422 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1833ms total) +T183C 003:422 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1833ms total) +T183C 003:422 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1833ms total) +T183C 003:422 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1833ms total) +T183C 003:422 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1833ms total) +T183C 003:422 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1833ms total) +T183C 003:422 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1833ms total) +T183C 003:422 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1833ms total) +T183C 003:422 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x0000001C (0000ms, 1833ms total) +T183C 003:422 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0015ms, 1833ms total) +T183C 003:437 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0002ms, 1848ms total) +T183C 003:490 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1848ms total) +T183C 003:498 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1848ms total) +T183C 003:498 JLINK_ClrBPEx(BPHandle = 0x0000001C) returns 0x00 (0000ms, 1848ms total) +T183C 003:498 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1848ms total) +T183C 003:499 JLINK_WriteMem(0x20000164, 0x0400 Bytes, ...) -- Data: D0 10 F0 30 31 F1 33 F3 F2 32 36 F6 F7 37 F5 35 ... >0x31C0 JTAG> returns 0x400 (0011ms, 1848ms total) +T183C 003:510 JLINK_WriteReg(R0, 0x08006000) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_WriteReg(R1, 0x000001AC) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_WriteReg(R15, 0x200000F4) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1859ms total) +T183C 003:510 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x0000001D (0000ms, 1859ms total) +T183C 003:510 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1859ms total) +T183C 003:526 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1875ms total) +T183C 003:578 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1875ms total) +T183C 003:586 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1875ms total) +T183C 003:586 JLINK_ClrBPEx(BPHandle = 0x0000001D) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(R0, 0x00000002) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(R1, 0x000001AC) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(R2, 0x20000164) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(R15, 0x2000006A) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1875ms total) +T183C 003:586 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0001ms, 1875ms total) +T183C 003:587 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x0000001E (0000ms, 1876ms total) +T183C 003:587 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1876ms total) +T183C 003:603 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0007ms, 1892ms total) +T183C 003:610 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1892ms total) +T183C 003:610 JLINK_ClrBPEx(BPHandle = 0x0000001E) returns 0x00 (0000ms, 1892ms total) +T183C 003:610 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1892ms total) +T183C 003:668 JLINK_WriteMem(0x20000000, 0x0164 Bytes, ...) -- Data: 00 BE 0A E0 0D 78 2D 06 68 40 08 24 40 00 00 D3 ... >0x1270 JTAG> returns 0x164 (0005ms, 1892ms total) +T183C 003:673 JLINK_WriteReg(R0, 0x08000000) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_WriteReg(R1, 0x007A1200) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_WriteReg(R2, 0x00000003) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_WriteReg(R3, 0x00000000) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_WriteReg(R15, 0x20000038) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1897ms total) +T183C 003:673 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) >0x1F0 JTAG> returns 0x0000001F (0001ms, 1897ms total) +T183C 003:674 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1898ms total) +T183C 003:690 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1914ms total) +T183C 003:698 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1914ms total) +T183C 003:698 JLINK_ClrBPEx(BPHandle = 0x0000001F) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(R0, 0xFFFFFFFF) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(R1, 0x08000000) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(R2, 0x000061AC) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(R3, 0x04C11DB7) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(R15, 0x20000002) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1914ms total) +T183C 003:698 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000020 (0000ms, 1914ms total) +T183C 003:698 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0016ms, 1914ms total) +T183C 003:714 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1930ms total) +T183C 003:766 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1930ms total) +T183C 003:818 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1930ms total) +T183C 003:870 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1930ms total) +T183C 003:922 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1930ms total) +T183C 003:974 JLINK_IsHalted() >0x198 JTAG> returns FALSE (0001ms, 1930ms total) +T183C 004:026 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0009ms, 1930ms total) +T183C 004:035 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1930ms total) +T183C 004:035 JLINK_ClrBPEx(BPHandle = 0x00000020) returns 0x00 (0000ms, 1930ms total) +T183C 004:035 JLINK_ReadReg(R0) returns 0x145DC10C (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(R0, 0x00000003) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(R1, 0x08000000) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(R2, 0x000061AC) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(R3, 0x04C11DB7) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(R4, 0x00000000) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(R5, 0x00000000) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(R6, 0x00000000) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(R7, 0x00000000) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(R8, 0x00000000) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(R9, 0x20000160) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(R10, 0x00000000) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(R11, 0x00000000) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(R12, 0x00000000) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(R13, 0x20000800) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(R14, 0x20000001) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(R15, 0x2000006A) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(XPSR, 0x01000000) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(MSP, 0x20000800) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(PSP, 0x20000800) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_WriteReg(CFBP, 0x00000000) returns 0x00 (0000ms, 1930ms total) +T183C 004:038 JLINK_SetBPEx(Addr = 0x20000000, Type = 0xFFFFFFF2) returns 0x00000021 (0000ms, 1930ms total) +T183C 004:038 JLINK_Go() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x310 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x218 JTAG> >0x240 JTAG> >0x240 JTAG> (0015ms, 1930ms total) +T183C 004:053 JLINK_IsHalted() >0x198 JTAG> >0x17A8 JTAG> >0x1F0 JTAG> returns TRUE (0008ms, 1945ms total) +T183C 004:061 JLINK_ReadReg(R15) returns 0x20000000 (0000ms, 1945ms total) +T183C 004:061 JLINK_ClrBPEx(BPHandle = 0x00000021) returns 0x00 (0000ms, 1945ms total) +T183C 004:061 JLINK_ReadReg(R0) returns 0x00000000 (0000ms, 1945ms total) +T183C 004:116 JLINK_WriteU32(0xE000EDFC, 0x00000000) >0x1F0 JTAG> returns 0x00 (0001ms, 1945ms total) +T183C 004:117 JLINK_SetResetType(JLINKARM_RESET_TYPE_NORMAL) returns JLINKARM_RESET_TYPE_NORMAL (0000ms, 1946ms total) +T183C 004:117 JLINK_Reset() >0x2F8 JTAG>TotalIRLen = 9, IRPrint = 0x0011 >0x30 JTAG> >0x210 JTAG> >0x118 JTAG> >0xD8 JTAG> >0x198 JTAG> >0x38 JTAG> >0x118 JTAG> >0xD8 JTAG> >0x2F0 JTAG> >0x2F0 JTAG> >0x198 JTAG> >0x198 JTAG>Found Cortex-M3 r1p1, Little endian. >0xD8 JTAG> >0x240 JTAG> >0x198 JTAG> >0x198 JTAG>TPIU fitted. >0x198 JTAG> >0x198 JTAG> FPUnit: 6 code (BP) slots and 2 literal slots >0x198 JTAG> >0x250 JTAG> >0x240 JTAG> >0x280 JTAG> >0x198 JTAG> >0x198 JTAG> >0x198 JTAG> >0x198 JTAG> + >0x240 JTAG> >0x240 JTAG> >0x198 JTAG> >0x198 JTAG> >0x240 JTAG> >0x198 JTAG> >0x17A8 JTAG> >0x198 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> (0071ms, 1946ms total) +T183C 004:192 JLINK_Close() >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x1F0 JTAG> >0x240 JTAG> >0x240 JTAG> >0x08 JTAG> (0037ms, 2017ms total)