提交 489b3822 编写于 作者: R Rogerz Zhang

Merge remote-tracking branch 'official/master' into auto-ci

......@@ -10,3 +10,4 @@
*.idb
*.ilk
build
*~
......@@ -49,8 +49,6 @@ struct at91_mci {
rt_uint32_t current_status;
};
static struct at91_mci *at_mci;
/*
* Reset the controller and restore most of the state
*/
......@@ -592,8 +590,9 @@ static void at91_mci_completed_command(struct at91_mci *mci, rt_uint32_t status)
/*
* Handle an interrupt
*/
static void at91_mci_irq(int irq)
static void at91_mci_irq(int irq, void *param)
{
struct at91_mci *mci = (struct at91_mci *)param;
rt_int32_t completed = 0;
rt_uint32_t int_status, int_mask;
......@@ -635,13 +634,13 @@ static void at91_mci_irq(int irq)
if (int_status & AT91_MCI_TXBUFE)
{
mci_dbg("TX buffer empty\n");
at91_mci_handle_transmitted(at_mci);
at91_mci_handle_transmitted(mci);
}
if (int_status & AT91_MCI_ENDRX)
{
mci_dbg("ENDRX\n");
at91_mci_post_dma_read(at_mci);
at91_mci_post_dma_read(mci);
}
if (int_status & AT91_MCI_RXBUFF)
......@@ -668,7 +667,7 @@ static void at91_mci_irq(int irq)
if (int_status & AT91_MCI_BLKE)
{
mci_dbg("Block transfer has ended\n");
if (at_mci->req->data && at_mci->req->data->blks > 1)
if (mci->req->data && mci->req->data->blks > 1)
{
/* multi block write : complete multi write
* command and send stop */
......@@ -684,7 +683,7 @@ static void at91_mci_irq(int irq)
rt_mmcsd_signal_sdio_irq(host->mmc);*/
if (int_status & AT91_MCI_SDIOIRQB)
sdio_irq_wakeup(at_mci->host);
sdio_irq_wakeup(mci->host);
if (int_status & AT91_MCI_TXRDY)
mci_dbg("Ready to transmit\n");
......@@ -695,7 +694,7 @@ static void at91_mci_irq(int irq)
if (int_status & AT91_MCI_CMDRDY)
{
mci_dbg("Command ready\n");
completed = at91_mci_handle_cmdrdy(at_mci);
completed = at91_mci_handle_cmdrdy(mci);
}
}
......@@ -703,7 +702,7 @@ static void at91_mci_irq(int irq)
{
mci_dbg("Completed command\n");
at91_mci_write(AT91_MCI_IDR, 0xffffffff & ~(AT91_MCI_SDIOIRQA | AT91_MCI_SDIOIRQB));
at91_mci_completed_command(at_mci, int_status);
at91_mci_completed_command(mci, int_status);
}
else
at91_mci_write(AT91_MCI_IDR, int_status & ~(AT91_MCI_SDIOIRQA | AT91_MCI_SDIOIRQB));
......@@ -791,7 +790,7 @@ static const struct rt_mmcsd_host_ops ops = {
at91_mci_enable_sdio_irq,
};
void at91_mci_detect(int irq)
void at91_mci_detect(int irq, void *param)
{
rt_kprintf("mmcsd gpio detected\n");
}
......@@ -819,7 +818,7 @@ static void mci_gpio_init()
rt_int32_t at91_mci_init(void)
{
struct rt_mmcsd_host *host;
//struct at91_mci *mci;
struct at91_mci *mci;
host = mmcsd_alloc_host();
if (!host)
......@@ -827,14 +826,14 @@ rt_int32_t at91_mci_init(void)
return -RT_ERROR;
}
at_mci = rt_malloc(sizeof(struct at91_mci));
if (!at_mci)
mci = rt_malloc(sizeof(struct at91_mci));
if (!mci)
{
rt_kprintf("alloc mci failed\n");
goto err;
}
rt_memset(at_mci, 0, sizeof(struct at91_mci));
rt_memset(mci, 0, sizeof(struct at91_mci));
host->ops = &ops;
host->freq_min = 375000;
......@@ -846,7 +845,7 @@ rt_int32_t at91_mci_init(void)
host->max_blk_size = 512;
host->max_blk_count = 4096;
at_mci->host = host;
mci->host = host;
mci_gpio_init();
at91_sys_write(AT91_PMC_PCER, 1 << AT91SAM9260_ID_MCI); //enable MCI clock
......@@ -855,14 +854,16 @@ rt_int32_t at91_mci_init(void)
at91_mci_enable();
/* instal interrupt */
rt_hw_interrupt_install(AT91SAM9260_ID_MCI, at91_mci_irq, RT_NULL);
rt_hw_interrupt_install(AT91SAM9260_ID_MCI, at91_mci_irq,
(void *)mci, "MMC");
rt_hw_interrupt_umask(AT91SAM9260_ID_MCI);
rt_hw_interrupt_install(gpio_to_irq(AT91_PIN_PA7), at91_mci_detect, RT_NULL);
rt_hw_interrupt_install(gpio_to_irq(AT91_PIN_PA7),
at91_mci_detect, RT_NULL, "MMC_DETECT");
rt_hw_interrupt_umask(gpio_to_irq(AT91_PIN_PA7));
rt_timer_init(&at_mci->timer, "mci_timer",
rt_timer_init(&mci->timer, "mci_timer",
at91_timeout_timer,
at_mci,
mci,
RT_TICK_PER_SECOND,
RT_TIMER_FLAG_PERIODIC);
......@@ -870,7 +871,7 @@ rt_int32_t at91_mci_init(void)
//rt_sem_init(&mci->sem_ack, "sd_ack", 0, RT_IPC_FLAG_FIFO);
host->private_data = at_mci;
host->private_data = mci;
mmcsd_change(host);
......
......@@ -92,9 +92,10 @@ struct rt_device uart4_device;
/**
* This function will handle serial
*/
void rt_serial_handler(int vector)
void rt_serial_handler(int vector, void *param)
{
int status;
struct rt_device *dev = (rt_device_t)param;
switch (vector)
{
......@@ -105,7 +106,7 @@ void rt_serial_handler(int vector)
{
return;
}
rt_hw_serial_isr(&uart1_device);
rt_hw_serial_isr(dev);
break;
#endif
#ifdef RT_USING_UART1
......@@ -115,7 +116,7 @@ void rt_serial_handler(int vector)
{
return;
}
rt_hw_serial_isr(&uart2_device);
rt_hw_serial_isr(dev);
break;
#endif
#ifdef RT_USING_UART2
......@@ -125,7 +126,7 @@ void rt_serial_handler(int vector)
{
return;
}
rt_hw_serial_isr(&uart3_device);
rt_hw_serial_isr(dev);
break;
#endif
#ifdef RT_USING_UART3
......@@ -135,7 +136,7 @@ void rt_serial_handler(int vector)
{
return;
}
rt_hw_serial_isr(&uart4_device);
rt_hw_serial_isr(dev);
break;
#endif
default: break;
......@@ -176,7 +177,8 @@ void rt_hw_uart_init(void)
at91_sys_write(AT91_PIOB + PIO_PDR, (1<<4)|(1<<5));
uart_port_init(AT91SAM9260_BASE_US0);
/* install interrupt handler */
rt_hw_interrupt_install(AT91SAM9260_ID_US0, rt_serial_handler, RT_NULL);
rt_hw_interrupt_install(AT91SAM9260_ID_US0, rt_serial_handler,
(void *)&uart1_device, "UART0");
rt_hw_interrupt_umask(AT91SAM9260_ID_US0);
#endif
#ifdef RT_USING_UART1
......@@ -188,7 +190,8 @@ void rt_hw_uart_init(void)
at91_sys_write(AT91_PIOB + PIO_PDR, (1<<6)|(1<<7));
uart_port_init(AT91SAM9260_BASE_US1);
/* install interrupt handler */
rt_hw_interrupt_install(AT91SAM9260_ID_US1, rt_serial_handler, RT_NULL);
rt_hw_interrupt_install(AT91SAM9260_ID_US1, rt_serial_handler,
(void *)&uart2_device, "UART1");
rt_hw_interrupt_umask(AT91SAM9260_ID_US1);
#endif
#ifdef RT_USING_UART2
......@@ -200,7 +203,8 @@ void rt_hw_uart_init(void)
at91_sys_write(AT91_PIOB + PIO_PDR, (1<<8)|(1<<9));
uart_port_init(AT91SAM9260_BASE_US2);
/* install interrupt handler */
rt_hw_interrupt_install(AT91SAM9260_ID_US2, rt_serial_handler, RT_NULL);
rt_hw_interrupt_install(AT91SAM9260_ID_US2, rt_serial_handler,
(void *)&uart3_device, "UART2");
rt_hw_interrupt_umask(AT91SAM9260_ID_US2);
#endif
#ifdef RT_USING_UART3
......@@ -212,7 +216,8 @@ void rt_hw_uart_init(void)
at91_sys_write(AT91_PIOB + PIO_PDR, (1<<10)|(1<<11));
uart_port_init(AT91SAM9260_BASE_US3);
/* install interrupt handler */
rt_hw_interrupt_install(AT91SAM9260_ID_US3, rt_serial_handler, RT_NULL);
rt_hw_interrupt_install(AT91SAM9260_ID_US3, rt_serial_handler,
(void *)&uart4_device, "UART3");
rt_hw_interrupt_umask(AT91SAM9260_ID_US3);
#endif
......@@ -246,7 +251,7 @@ static rt_uint32_t pit_cnt; /* access only w/system irq blocked */
/**
* This function will handle rtos timer
*/
void rt_timer_handler(int vector)
void rt_timer_handler(int vector, void *param)
{
#ifdef RT_USING_DBGU
if (at91_sys_read(AT91_DBGU + AT91_US_CSR) & 0x1) {
......@@ -309,7 +314,8 @@ static void at91sam926x_pit_init(void)
at91sam926x_pit_init();
/* install interrupt handler */
rt_hw_interrupt_install(AT91_ID_SYS, rt_timer_handler, RT_NULL);
rt_hw_interrupt_install(AT91_ID_SYS, rt_timer_handler,
RT_NULL, "system");
rt_hw_interrupt_umask(AT91_ID_SYS);
}
......
......@@ -103,9 +103,9 @@ static void udelay(rt_uint32_t us)
for (len = 0; len < 10; len++ );
}
static void rt_macb_isr(int irq)
static void rt_macb_isr(int irq, void *param)
{
struct rt_macb_eth *macb = &macb_device;
struct rt_macb_eth *macb = (struct rt_macb_eth *)param;
rt_device_t dev = &(macb->parent.parent);
rt_uint32_t status, rsr, tsr;
......@@ -150,7 +150,7 @@ static void rt_macb_isr(int irq)
}
static void macb_mdio_write(struct rt_macb_eth *macb, rt_uint8_t reg, rt_uint16_t value)
static int macb_mdio_write(struct rt_macb_eth *macb, rt_uint8_t reg, rt_uint16_t value)
{
unsigned long netctl;
unsigned long netstat;
......@@ -179,7 +179,7 @@ static void macb_mdio_write(struct rt_macb_eth *macb, rt_uint8_t reg, rt_uint16_
rt_sem_release(&macb->mdio_bus_lock);
}
static rt_uint16_t macb_mdio_read(struct rt_macb_eth *macb, rt_uint8_t reg)
static int macb_mdio_read(struct rt_macb_eth *macb, rt_uint8_t reg)
{
unsigned long netctl;
unsigned long netstat;
......@@ -298,12 +298,21 @@ void macb_update_link(void *param)
{
struct rt_macb_eth *macb = (struct rt_macb_eth *)param;
rt_device_t dev = &macb->parent.parent;
rt_uint32_t status, status_change = 0;
int status, status_change = 0;
rt_uint32_t link;
rt_uint32_t media;
rt_uint16_t adv, lpa;
/* Do a fake read */
status = macb_mdio_read(macb, MII_BMSR);
if (status < 0)
return;
/* Read link and autonegotiation status */
status = macb_mdio_read(macb, MII_BMSR);
if (status < 0)
return;
if ((status & BMSR_LSTATUS) == 0)
link = 0;
else
......@@ -403,7 +412,8 @@ static rt_err_t rt_macb_init(rt_device_t dev)
| MACB_BIT(HRESP)));
/* instal interrupt */
rt_hw_interrupt_install(AT91SAM9260_ID_EMAC, rt_macb_isr, RT_NULL);
rt_hw_interrupt_install(AT91SAM9260_ID_EMAC, rt_macb_isr,
(void *)macb, "emac");
rt_hw_interrupt_umask(AT91SAM9260_ID_EMAC);
rt_timer_init(&macb->timer, "link_timer",
......
......@@ -22,6 +22,8 @@
#define RT_USING_OVERFLOW_CHECK
#define RT_USING_INTERRUPT_INFO
/* Using Hook */
#define RT_USING_HOOK
......
......@@ -18,6 +18,7 @@
/* Thread Debug */
#define RT_DEBUG
#define RT_USING_OVERFLOW_CHECK
#define RT_USING_INTERRUPT_INFO
/* Using Hook */
#define RT_USING_HOOK
......
......@@ -25,7 +25,7 @@
/* UART interrupt enable register value */
#define UARTIER_IME (1 << 3)
#define UARTIER_ILE (1 << 2)
#define UARTIER_ILE (1 << 2)
#define UARTIER_ITXE (1 << 1)
#define UARTIER_IRXE (1 << 0)
......@@ -59,7 +59,7 @@ struct rt_uart_soc3210
rt_uint8_t rx_buffer[RT_UART_RX_BUFFER_SIZE];
}uart_device;
static void rt_uart_irqhandler(int irqno)
static void rt_uart_irqhandler(int irqno, void *param)
{
rt_ubase_t level;
rt_uint8_t isr;
......@@ -142,7 +142,7 @@ static rt_err_t rt_uart_open(rt_device_t dev, rt_uint16_t oflag)
UART_IER(uart->hw_base) |= UARTIER_IRXE;
/* install interrupt */
rt_hw_interrupt_install(uart->irq, rt_uart_irqhandler, RT_NULL);
rt_hw_interrupt_install(uart->irq, rt_uart_irqhandler, RT_NULL, "UART");
rt_hw_interrupt_umask(uart->irq);
}
return RT_EOK;
......
......@@ -27,7 +27,7 @@
/**
* This is the timer interrupt service routine.
*/
void rt_hw_timer_handler()
void rt_hw_timer_handler(int vector, void* param)
{
/* increase a OS tick */
rt_tick_increase();
......@@ -39,7 +39,7 @@ void rt_hw_timer_handler()
/**
* This function will initial OS timer
*/
void rt_hw_timer_init()
void rt_hw_timer_init(void)
{
rt_uint32_t val;
......@@ -52,33 +52,6 @@ void rt_hw_timer_init()
/* clear counter */
OST_CNT = 0;
#if 0
switch (RTC_DIV)
{
case 1:
val = OST_TCSR_PRESCALE1;
break;
case 4:
val = OST_TCSR_PRESCALE4;
break;
case 16:
val = OST_TCSR_PRESCALE16;
break;
case 64:
val = OST_TCSR_PRESCALE64;
break;
case 256:
val = OST_TCSR_PRESCALE256;
break;
case 1024:
val = OST_TCSR_PRESCALE1024;
break;
default:
val = OST_TCSR_PRESCALE4;
break;
}
#endif
#ifdef RTC_SRC_EXTAL
OST_CSR = (val | OST_TCSR_EXT_EN);
#else
......@@ -89,7 +62,7 @@ void rt_hw_timer_init()
TCU_TMCR = TCU_TMCR_OSTMCL;
TCU_TESR = TCU_TESR_OSTST;
rt_hw_interrupt_install(IRQ_TCU0, rt_hw_timer_handler, RT_NULL);
rt_hw_interrupt_install(IRQ_TCU0, rt_hw_timer_handler, RT_NULL, "tick");
rt_hw_interrupt_umask (IRQ_TCU0);
}
......
......@@ -18,6 +18,7 @@
/* Thread Debug */
#define RT_DEBUG
#define RT_USING_OVERFLOW_CHECK
#define RT_USING_INTERRUPT_INFO
/* Using Hook */
#define RT_USING_HOOK
......
......@@ -10,7 +10,7 @@
/*@{*/
#if defined(RT_USING_UART) && defined(RT_USING_DEVICE)
#define UART_BAUDRATE 115200
#define UART_BAUDRATE 57600
#define DEV_CLK 12000000
/*
......@@ -129,10 +129,10 @@ struct rt_uart_jz
rt_uint8_t rx_buffer[RT_UART_RX_BUFFER_SIZE];
}uart_device;
static void rt_uart_irqhandler(int irqno)
static void rt_uart_irqhandler(int vector, void* param)
{
rt_ubase_t level, isr;
struct rt_uart_jz* uart = &uart_device;
struct rt_uart_jz* uart = param;
/* read interrupt status and clear it */
isr = UART_ISR(uart->hw_base);
......@@ -212,7 +212,7 @@ static rt_err_t rt_uart_open(rt_device_t dev, rt_uint16_t oflag)
UART_IER(uart->hw_base) |= (UARTIER_RIE | UARTIER_RTIE);
/* install interrupt */
rt_hw_interrupt_install(uart->irq, rt_uart_irqhandler, RT_NULL);
rt_hw_interrupt_install(uart->irq, rt_uart_irqhandler, uart, "uart");
rt_hw_interrupt_umask(uart->irq);
}
return RT_EOK;
......
......@@ -9,6 +9,16 @@
//*** <<< Use Configuration Wizard in Context Menu >>> ***
*/
.syntax unified
.cpu cortex-m3
.fpu softvfp
.thumb
.word _sidata
.word _sdata
.word _edata
.word _sbss
.word _ebss
/*
// <h> Stack Configuration
......@@ -16,8 +26,8 @@
// </h>
*/
.equ Stack_Size, 0x00000100
.section ".stack", "w"
.equ Stack_Size, 0x00000200
.section .stack, "w"
.align 3
.globl __cs3_stack_mem
.globl __cs3_stack_size
......@@ -28,35 +38,15 @@ __cs3_stack_mem:
.size __cs3_stack_mem, . - __cs3_stack_mem
.set __cs3_stack_size, . - __cs3_stack_mem
/*
// <h> Heap Configuration
// <o> Heap Size (in Bytes) <0x0-0xFFFFFFFF:8>
// </h>
*/
.equ Heap_Size, 0x00001000
.section ".heap", "w"
.align 3
.globl __cs3_heap_start
.globl __cs3_heap_end
__cs3_heap_start:
.if Heap_Size
.space Heap_Size
.endif
__cs3_heap_end:
/* Vector Table */
.section ".cs3.interrupt_vector"
.section .interrupt_vector
.globl __cs3_interrupt_vector_cortex_m
.type __cs3_interrupt_vector_cortex_m, %object
__cs3_interrupt_vector_cortex_m:
.long __cs3_stack /* Top of Stack */
.long __cs3_reset /* Reset Handler */
.long _estack /* Top of Stack */
.long Reset_Handler /* Reset Handler */
.long NMI_Handler /* NMI Handler */
.long HardFault_Handler /* Hard Fault Handler */
.long MemManage_Handler /* MPU Fault Handler */
......@@ -86,7 +76,7 @@ __cs3_interrupt_vector_cortex_m:
.long I2C0_IRQHandler /* 26: I2C0 */
.long I2C1_IRQHandler /* 27: I2C1 */
.long I2C2_IRQHandler /* 28: I2C2 */
.long SPIFI_IRQHandler /* 29: SPIFI */
.long SPIFI_IRQHandler /* 29: SPIFI */
.long SSP0_IRQHandler /* 30: SSP0 */
.long SSP1_IRQHandler /* 31: SSP1 */
.long PLL0_IRQHandler /* 32: PLL0 Lock (Main PLL) */
......@@ -102,61 +92,65 @@ __cs3_interrupt_vector_cortex_m:
.long DMA_IRQHandler /* 42: General Purpose DMA */
.long I2S_IRQHandler /* 43: I2S */
.long ENET_IRQHandler /* 44: Ethernet */
.long MCI_IRQHandler /* 45: SD/MMC Card */
.long MCI_IRQHandler /* 45: SD/MMC Card */
.long MCPWM_IRQHandler /* 46: Motor Control PWM */
.long QEI_IRQHandler /* 47: Quadrature Encoder Interface */
.long PLL1_IRQHandler /* 48: PLL1 Lock (USB PLL) */
.long USBActivity_IRQHandler /* 49: USB Activity */
.long CANActivity_IRQHandler /* 50: CAN Activity */
.long UART4_IRQHandler /* 51: UART4 */
.long SSP2_IRQHandler /* 52: SSP2 */
.long LCD_IRQHandler /* 53: LCD */
.long GPIO_IRQHandler /* 54: GPIO */
.long PWM0_IRQHandler /* 55: PWM0 */
.long EEPROM_IRQHandler /* 56: EEPROM */
.long USBActivity_IRQHandler /* 49: USB Activity */
.long CANActivity_IRQHandler /* 50: CAN Activity */
.long UART4_IRQHandler /* 51: UART4 */
.long SSP2_IRQHandler /* 52: SSP2 */
.long LCD_IRQHandler /* 53: LCD */
.long GPIO_IRQHandler /* 54: GPIO */
.long PWM0_IRQHandler /* 55: PWM0 */
.long EEPROM_IRQHandler /* 56: EEPROM */
.size __cs3_interrupt_vector_cortex_m, . - __cs3_interrupt_vector_cortex_m
.thumb
/* Reset Handler */
.section .cs3.reset,"x",%progbits
.thumb_func
.globl __cs3_reset_cortex_m
.type __cs3_reset_cortex_m, %function
__cs3_reset_cortex_m:
.section .text.Reset_Handler
.weak Reset_Handler
.type Reset_Handler, %function
Reset_Handler:
.fnstart
#if (RAM_MODE)
/* Clear .bss section (Zero init) */
MOV R0, #0
LDR R1, =__bss_start__
LDR R2, =__bss_end__
CMP R1,R2
BEQ BSSIsEmpty
LoopZI:
CMP R1, R2
BHS BSSIsEmpty
STR R0, [R1]
ADD R1, #4
BLO LoopZI
BSSIsEmpty:
LDR R0, =SystemInit
BLX R0
LDR R0,=main
BX R0
#else
LDR R0, =SystemInit
BLX R0
LDR R0,=_start
BX R0
#endif
/* Copy the data segment initializers from flash to SRAM */
movs r1, #0
b LoopCopyDataInit
CopyDataInit:
ldr r3, =_sidata
ldr r3, [r3, r1]
str r3, [r0, r1]
add r1, r1, #4
LoopCopyDataInit:
ldr r0, =_sdata
ldr r3, =_edata
add r2, r0, r1
cmp r2, r3
bcc CopyDataInit
ldr r2, =_sbss
b LoopFillZerobss
/* Zero fill the bss segment. */
FillZerobss:
movs r3, #0
str r3, [r2], #4
LoopFillZerobss:
ldr r3, = _ebss
cmp r2, r3
bcc FillZerobss
/* Call the clock system intitialization function.*/
bl SystemInit
/* Call the application's entry point.*/
bl main
bx lr
.pool
.cantunwind
.fnend
.size __cs3_reset_cortex_m,.-__cs3_reset_cortex_m
.size Reset_Handler,.-Reset_Handler
.section ".text"
......@@ -243,7 +237,7 @@ Default_Handler:
IRQ I2C0_IRQHandler
IRQ I2C1_IRQHandler
IRQ I2C2_IRQHandler
IRQ SPIFI_IRQHandler
IRQ SPIFI_IRQHandler
IRQ SSP0_IRQHandler
IRQ SSP1_IRQHandler
IRQ PLL0_IRQHandler
......@@ -263,13 +257,13 @@ Default_Handler:
IRQ MCPWM_IRQHandler
IRQ QEI_IRQHandler
IRQ PLL1_IRQHandler
IRQ USBActivity_IRQHandler
IRQ CANActivity_IRQHandler
IRQ UART4_IRQHandler
IRQ SSP2_IRQHandler
IRQ LCD_IRQHandler
IRQ GPIO_IRQHandler
IRQ PWM0_IRQHandler
IRQ EEPROM_IRQHandler
IRQ USBActivity_IRQHandler
IRQ CANActivity_IRQHandler
IRQ UART4_IRQHandler
IRQ SSP2_IRQHandler
IRQ LCD_IRQHandler
IRQ GPIO_IRQHandler
IRQ PWM0_IRQHandler
IRQ EEPROM_IRQHandler
.end
/*
* linker script for LPC1788 (512kB Flash, 48kB + 48kB SRAM ) with GNU ld
* yiyue.fang 2012-04-14
*/
/* Program Entry, set to mark it as "used" and avoid gc */
MEMORY
{
CODE (rx) : ORIGIN = 0x00000000, LENGTH = 0x00080000
DATA (rw) : ORIGIN = 0x10000000, LENGTH = 0x00010000
}
ENTRY(Reset_Handler)
_system_stack_size = 0x200;
SECTIONS
{
.text :
{
. = ALIGN(4);
KEEP(*(.interrupt_vector)) /* Startup code */
. = ALIGN(4);
*(.text) /* remaining code */
*(.text.*) /* remaining code */
*(.rodata) /* read-only data (constants) */
*(.rodata*)
*(.glue_7)
*(.glue_7t)
*(.gnu.linkonce.t*)
/* section information for finsh shell */
. = ALIGN(4);
__fsymtab_start = .;
KEEP(*(FSymTab))
__fsymtab_end = .;
. = ALIGN(4);
__vsymtab_start = .;
KEEP(*(VSymTab))
__vsymtab_end = .;
. = ALIGN(4);
. = ALIGN(4);
_etext = .;
} > CODE = 0
/* .ARM.exidx is sorted, so has to go in its own output section. */
__exidx_start = .;
.ARM.exidx :
{
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
/* This is used by the startup in order to initialize the .data secion */
_sidata = .;
} > CODE
__exidx_end = .;
/* .data section which is used for initialized data */
.data : AT (_sidata)
{
. = ALIGN(4);
/* This is used by the startup in order to initialize the .data secion */
_sdata = . ;
*(.data)
*(.data.*)
*(.gnu.linkonce.d*)
. = ALIGN(4);
/* This is used by the startup in order to initialize the .data secion */
_edata = . ;
} >DATA
.stack :
{
. = . + _system_stack_size;
. = ALIGN(4);
_estack = .;
} >DATA
__bss_start = .;
.bss :
{
. = ALIGN(4);
/* This is used by the startup in order to initialize the .bss secion */
_sbss = .;
*(.bss)
*(.bss.*)
*(COMMON)
. = ALIGN(4);
/* This is used by the startup in order to initialize the .bss secion */
_ebss = . ;
*(.bss.init)
} > DATA
__bss_end = .;
_end = .;
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
/* DWARF debug sections.
* Symbols in the DWARF debugging sections are relative to the beginning
* of the section so we begin them at 0. */
/* DWARF 1 */
.debug 0 : { *(.debug) }
.line 0 : { *(.line) }
/* GNU DWARF 1 extensions */
.debug_srcinfo 0 : { *(.debug_srcinfo) }
.debug_sfnames 0 : { *(.debug_sfnames) }
/* DWARF 1.1 and DWARF 2 */
.debug_aranges 0 : { *(.debug_aranges) }
.debug_pubnames 0 : { *(.debug_pubnames) }
/* DWARF 2 */
.debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_line 0 : { *(.debug_line) }
.debug_frame 0 : { *(.debug_frame) }
.debug_str 0 : { *(.debug_str) }
.debug_loc 0 : { *(.debug_loc) }
.debug_macinfo 0 : { *(.debug_macinfo) }
/* SGI/MIPS DWARF 2 extensions */
.debug_weaknames 0 : { *(.debug_weaknames) }
.debug_funcnames 0 : { *(.debug_funcnames) }
.debug_typenames 0 : { *(.debug_typenames) }
.debug_varnames 0 : { *(.debug_varnames) }
}
; *************************************************************
; *** Scatter-Loading Description File generated by uVision ***
; *************************************************************
LR_IROM1 0x00000000 0x00080000 { ; load region size_region
ER_IROM1 0x00000000 0x00080000 { ; load address = execution address
*.o (RESET, +First)
*(InRoot$$Sections)
.ANY (+RO)
}
RW_IRAM1 0x10000000 0x00010000 { ; RW data
.ANY (+RW +ZI)
}
}
......@@ -70,12 +70,12 @@ SECTIONS
_edata = . ;
} >DATA
.stack :
{
. = . + _system_stack_size;
. = ALIGN(4);
_estack = .;
} >DATA
.stack :
{
. = . + _system_stack_size;
. = ALIGN(4);
_estack = .;
} >DATA
__bss_start = .;
.bss :
......
......@@ -27,7 +27,7 @@
* This is the timer interrupt service routine.
* @param vector the irq number for timer
*/
void rt_hw_timer_handler(int vector)
void rt_hw_timer_handler(int vector, void *param)
{
rt_tick_increase();
......@@ -53,10 +53,10 @@ void rt_hw_console_output(const char* str)
while (!(U0LSR & 0x20));
U0THR = '\r';
}
while (!(U0LSR & 0x20));
U0THR = *str;
str ++;
}
}
......@@ -82,11 +82,11 @@ void rt_hw_console_init()
/**
* This function will initial sam7x256 board.
*/
void rt_hw_board_init()
void rt_hw_board_init(void)
{
/* console init */
rt_hw_console_init();
/* prescaler = 0*/
T0PR = 0;
T0PC = 0;
......@@ -94,12 +94,12 @@ void rt_hw_board_init()
/* reset and enable MR0 interrupt */
T0MCR = 0x3;
T0MR0 = PCLK / RT_TICK_PER_SECOND;
/* enable timer 0 */
T0TCR = 1;
/* install timer handler */
rt_hw_interrupt_install(TIMER0_INT, rt_hw_timer_handler, RT_NULL);
rt_hw_interrupt_install(TIMER0_INT, rt_hw_timer_handler, RT_NULL, "TIMER0");
rt_hw_interrupt_umask(TIMER0_INT);
}
......
......@@ -69,7 +69,7 @@ void rt_hw_uart_isr(struct rt_lpcserial* lpc_serial)
UNUSED rt_uint32_t iir;
RT_ASSERT(lpc_serial != RT_NULL)
if (UART_LSR(lpc_serial->hw_base) & 0x01)
{
rt_base_t level;
......@@ -80,12 +80,12 @@ void rt_hw_uart_isr(struct rt_lpcserial* lpc_serial)
level = rt_hw_interrupt_disable();
/* read character */
lpc_serial->rx_buffer[lpc_serial->save_index] =
lpc_serial->rx_buffer[lpc_serial->save_index] =
UART_RBR(lpc_serial->hw_base);
lpc_serial->save_index ++;
if (lpc_serial->save_index >= RT_UART_RX_BUFFER_SIZE)
lpc_serial->save_index = 0;
/* if the next position is read index, discard this 'read char' */
if (lpc_serial->save_index == lpc_serial->read_index)
{
......@@ -113,7 +113,7 @@ void rt_hw_uart_isr(struct rt_lpcserial* lpc_serial)
}
#ifdef RT_USING_UART1
void rt_hw_uart_isr_1(int irqno)
void rt_hw_uart_isr_1(int irqno, void *param)
{
/* get lpc serial device */
rt_hw_uart_isr(&serial1);
......@@ -121,7 +121,7 @@ void rt_hw_uart_isr_1(int irqno)
#endif
#ifdef RT_USING_UART2
void rt_hw_uart_isr_2(int irqno)
void rt_hw_uart_isr_2(int irqno, void *param)
{
/* get lpc serial device */
rt_hw_uart_isr(&serial2);
......@@ -153,13 +153,15 @@ static rt_err_t rt_serial_open(rt_device_t dev, rt_uint16_t oflag)
if (lpc_serial->irqno == UART0_INT)
{
#ifdef RT_USING_UART1
rt_hw_interrupt_install(lpc_serial->irqno, rt_hw_uart_isr_1, RT_NULL);
rt_hw_interrupt_install(lpc_serial->irqno,
rt_hw_uart_isr_1, &serial1, "UART1");
#endif
}
else
{
#ifdef RT_USING_UART2
rt_hw_interrupt_install(lpc_serial->irqno, rt_hw_uart_isr_2, RT_NULL);
rt_hw_interrupt_install(lpc_serial->irqno,
rt_hw_uart_isr_2, &serial2, "UART2");
#endif
}
......@@ -173,7 +175,7 @@ static rt_err_t rt_serial_close(rt_device_t dev)
{
struct rt_lpcserial* lpc_serial;
lpc_serial = (struct rt_lpcserial*) dev;
RT_ASSERT(lpc_serial != RT_NULL);
if (dev->flag & RT_DEVICE_FLAG_INT_RX)
......@@ -244,7 +246,7 @@ static rt_size_t rt_serial_read(rt_device_t dev, rt_off_t pos, void* buffer, rt_
{
/* Read Character */
*ptr = UART_RBR(lpc_serial->hw_base);
ptr ++;
size --;
}
......@@ -271,7 +273,7 @@ static rt_size_t rt_serial_write(rt_device_t dev, rt_off_t pos, const void* buff
/* polling write */
ptr = (char *)buffer;
if (dev->flag & RT_DEVICE_FLAG_STREAM)
{
/* stream mode */
......@@ -285,7 +287,7 @@ static rt_size_t rt_serial_write(rt_device_t dev, rt_off_t pos, const void* buff
while (!(UART_LSR(lpc_serial->hw_base) & 0x20));
UART_THR(lpc_serial->hw_base) = *ptr;
ptr ++;
size --;
}
......@@ -296,37 +298,37 @@ static rt_size_t rt_serial_write(rt_device_t dev, rt_off_t pos, const void* buff
{
while (!(UART_LSR(lpc_serial->hw_base) & 0x20));
UART_THR(lpc_serial->hw_base) = *ptr;
ptr ++;
size --;
}
}
return (rt_size_t) ptr - (rt_size_t) buffer;
}
void rt_hw_serial_init(void)
{
struct rt_lpcserial* lpc_serial;
#ifdef RT_USING_UART1
lpc_serial = &serial1;
lpc_serial->parent.type = RT_Device_Class_Char;
lpc_serial->hw_base = 0xE000C000;
lpc_serial->baudrate = 115200;
lpc_serial->irqno = UART0_INT;
rt_memset(lpc_serial->rx_buffer, 0, sizeof(lpc_serial->rx_buffer));
lpc_serial->read_index = lpc_serial->save_index = 0;
/* Enable UART0 RxD and TxD pins */
PINSEL0 |= 0x05;
PINSEL0 |= 0x05;
/* 8 bits, no Parity, 1 Stop bit */
UART_LCR(lpc_serial->hw_base) = 0x83;
/* Setup Baudrate */
UART_DLL(lpc_serial->hw_base) = (PCLK/16/lpc_serial->baudrate) & 0xFF;
UART_DLM(lpc_serial->hw_base) = ((PCLK/16/lpc_serial->baudrate) >> 8) & 0xFF;
......@@ -334,6 +336,7 @@ void rt_hw_serial_init(void)
/* DLAB = 0 */
UART_LCR(lpc_serial->hw_base) = 0x03;
lpc_serial->parent.type = RT_Device_Class_Char;
lpc_serial->parent.init = rt_serial_init;
lpc_serial->parent.open = rt_serial_open;
lpc_serial->parent.close = rt_serial_close;
......@@ -342,13 +345,13 @@ void rt_hw_serial_init(void)
lpc_serial->parent.control = rt_serial_control;
lpc_serial->parent.user_data = RT_NULL;
rt_device_register(&lpc_serial->parent,
rt_device_register(&lpc_serial->parent,
"uart1", RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX);
#endif
#ifdef RT_USING_UART2
lpc_serial = &serial2;
lpc_serial->parent.type = RT_Device_Class_Char;
lpc_serial->hw_base = 0xE0010000;
......@@ -363,7 +366,7 @@ void rt_hw_serial_init(void)
/* 8 bits, no Parity, 1 Stop bit */
UART_LCR(lpc_serial->hw_base) = 0x83;
/* Setup Baudrate */
UART_DLL(lpc_serial->hw_base) = (PCLK/16/lpc_serial->baudrate) & 0xFF;
UART_DLM(lpc_serial->hw_base) = ((PCLK/16/lpc_serial->baudrate) >> 8) & 0xFF;
......@@ -371,6 +374,7 @@ void rt_hw_serial_init(void)
/* DLAB = 0 */
UART_LCR(lpc_serial->hw_base) = 0x03;
lpc_serial->parent.type = RT_Device_Class_Char;
lpc_serial->parent.init = rt_serial_init;
lpc_serial->parent.open = rt_serial_open;
lpc_serial->parent.close = rt_serial_close;
......@@ -379,7 +383,7 @@ void rt_hw_serial_init(void)
lpc_serial->parent.control = rt_serial_control;
lpc_serial->parent.user_data = RT_NULL;
rt_device_register(&lpc_serial->parent,
rt_device_register(&lpc_serial->parent,
"uart2", RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX);
#endif
}
......
......@@ -27,7 +27,7 @@ extern void rt_hw_serial_init(void);
*/
/*@{*/
void rt_timer_handler(int vector)
void rt_timer_handler(int vector, void* param)
{
T0IR |= 0x01; /* clear interrupt flag */
rt_tick_increase();
......@@ -37,7 +37,7 @@ void rt_timer_handler(int vector)
/**
* This function will init LPC2478 board
*/
void rt_hw_board_init()
void rt_hw_board_init(void)
{
#if defined(RT_USING_DEVICE) && defined(RT_USING_UART1)
rt_hw_serial_init();
......@@ -49,7 +49,7 @@ void rt_hw_board_init()
T0MCR = 0x03;
T0MR0 = (DATA_COUNT);
rt_hw_interrupt_install(TIMER0_INT, rt_timer_handler, RT_NULL);
rt_hw_interrupt_install(TIMER0_INT, rt_timer_handler, RT_NULL, "tick");
rt_hw_interrupt_umask(TIMER0_INT);
T0TCR = 0x01; //enable timer0 counter
......
......@@ -64,9 +64,10 @@ void rt_hw_serial_init(void);
#define U0PINS 0x00000005
void rt_hw_uart_isr(struct rt_lpcserial* lpc_serial)
void rt_hw_uart_isr(int irqno, void *param)
{
UNUSED rt_uint32_t iir;
struct rt_lpcserial* lpc_serial = (struct rt_lpcserial*)param;
RT_ASSERT(lpc_serial != RT_NULL)
......@@ -112,21 +113,6 @@ void rt_hw_uart_isr(struct rt_lpcserial* lpc_serial)
VICVectAddr = 0;
}
#ifdef RT_USING_UART1
void rt_hw_uart_isr_1(int irqno)
{
/* get lpc serial device */
rt_hw_uart_isr(&serial1);
}
#endif
#ifdef RT_USING_UART2
void rt_hw_uart_isr_2(int irqno)
{
/* get lpc serial device */
rt_hw_uart_isr(&serial2);
}
#endif
/**
* @addtogroup LPC214x
......@@ -150,19 +136,8 @@ static rt_err_t rt_serial_open(rt_device_t dev, rt_uint16_t oflag)
UART_IER(lpc_serial->hw_base) = 0x01;
/* install ISR */
if (lpc_serial->irqno == UART0_INT)
{
#ifdef RT_USING_UART1
rt_hw_interrupt_install(lpc_serial->irqno, rt_hw_uart_isr_1, RT_NULL);
#endif
}
else
{
#ifdef RT_USING_UART2
rt_hw_interrupt_install(lpc_serial->irqno, rt_hw_uart_isr_2, RT_NULL);
#endif
}
rt_hw_interrupt_install(lpc_serial->irqno,
rt_hw_uart_isr, lpc_serial, RT_NULL);
rt_hw_interrupt_umask(lpc_serial->irqno);
}
......
......@@ -37,7 +37,7 @@ struct rt_uart_ls1b
rt_uint8_t rx_buffer[RT_UART_RX_BUFFER_SIZE];
}uart_device;
static void rt_uart_irqhandler(int irqno)
static void rt_uart_irqhandler(int irqno, void *param)
{
rt_ubase_t level;
rt_uint8_t isr;
......@@ -121,7 +121,7 @@ static rt_err_t rt_uart_open(rt_device_t dev, rt_uint16_t oflag)
UART_IER(uart->hw_base) |= UARTIER_IRXE;
/* install interrupt */
rt_hw_interrupt_install(uart->irq, rt_uart_irqhandler, RT_NULL);
rt_hw_interrupt_install(uart->irq, rt_uart_irqhandler, RT_NULL, "UART");
rt_hw_interrupt_umask(uart->irq);
}
return RT_EOK;
......
......@@ -21,6 +21,8 @@
// #define RT_THREAD_DEBUG
// <bool name="RT_USING_OVERFLOW_CHECK" description="Thread stack over flow detect" default="true" />
#define RT_USING_OVERFLOW_CHECK
// <bool name="RT_USING_INTERRUPT_INFO" description="Show more interrupt description" default="true" />
#define RT_USING_INTERRUPT_INFO
// </section>
// <bool name="RT_USING_HOOK" description="Using hook functions" default="true" />
......
......@@ -58,7 +58,7 @@ struct rt_device uart2_device;
/**
* This function will handle rtos timer
*/
static void rt_timer_handler(int vector)
static void rt_timer_handler(int vector, void *param)
{
rt_tick_increase();
}
......@@ -66,7 +66,7 @@ static void rt_timer_handler(int vector)
/**
* This function will handle serial
*/
static void rt_serial0_handler(int vector)
static void rt_serial0_handler(int vector, void *param)
{
INTSUBMSK |= (BIT_SUB_RXD0);
......@@ -81,7 +81,7 @@ static void rt_serial0_handler(int vector)
/**
* This function will handle serial
*/
static void rt_serial2_handler(int vector)
static void rt_serial2_handler(int vector, void *param)
{
INTSUBMSK |= (BIT_SUB_RXD2);
......@@ -133,7 +133,7 @@ static void rt_hw_uart_init(void)
uart2.uart_device->ucon = 0x245;
/* Set uart0 bps */
uart2.uart_device->ubrd = (rt_int32_t)(PCLK / (BPS * 16)) - 1;
for (i = 0; i < 100; i++);
/* install uart0 isr */
......@@ -141,18 +141,18 @@ static void rt_hw_uart_init(void)
/* install uart2 isr */
INTSUBMSK &= ~(BIT_SUB_RXD2);
rt_hw_interrupt_install(INTUART0, rt_serial0_handler, RT_NULL);
rt_hw_interrupt_install(INTUART0, rt_serial0_handler, RT_NULL, "UART0");
rt_hw_interrupt_umask(INTUART0);
rt_hw_interrupt_install(INTUART2, rt_serial2_handler, RT_NULL);
rt_hw_interrupt_umask(INTUART2);
rt_hw_interrupt_install(INTUART2, rt_serial2_handler, RT_NULL, "UART2");
rt_hw_interrupt_umask(INTUART2);
}
/**
* This function will init timer4 for system ticks
*/
static void rt_hw_timer_init()
static void rt_hw_timer_init(void)
{
/* timer4, pre = 15+1 */
TCFG0 &= 0xffff00ff;
......@@ -165,7 +165,7 @@ static void rt_hw_timer_init()
/* manual update */
TCON = TCON & (~(0x0f<<20)) | (0x02<<20);
/* install interrupt handler */
rt_hw_interrupt_install(INTTIMER4, rt_timer_handler, RT_NULL);
rt_hw_interrupt_install(INTTIMER4, rt_timer_handler, RT_NULL, "tick");
rt_hw_interrupt_umask(INTTIMER4);
/* start timer4, reload */
......@@ -175,7 +175,7 @@ static void rt_hw_timer_init()
/**
* This function will init s3ceb2410 board
*/
void rt_hw_board_init()
void rt_hw_board_init(void)
{
/* initialize the system clock */
rt_hw_clock_init();
......
......@@ -572,7 +572,7 @@ __error_retry:
#define B4_Tacp 0x0
#define B4_PMC 0x0
void INTEINT4_7_handler(int irqno)
void INTEINT4_7_handler(int irqno, void *param)
{
rt_uint32_t eint_pend;
......@@ -637,7 +637,7 @@ void rt_hw_dm9000_init()
eth_device_init(&(dm9000_device.parent), "e0");
/* instal interrupt */
rt_hw_interrupt_install(INTEINT4_7, INTEINT4_7_handler, RT_NULL);
rt_hw_interrupt_install(INTEINT4_7, INTEINT4_7_handler, RT_NULL, "EINT4_7");
rt_hw_interrupt_umask(INTEINT4_7);
}
......
......@@ -22,6 +22,8 @@
// #define RT_THREAD_DEBUG
// <bool name="RT_USING_OVERFLOW_CHECK" description="Thread stack over flow detect" default="true" />
#define RT_USING_OVERFLOW_CHECK
// <bool name="RT_USING_INTERRUPT_INFO" description="Show more interrupt description" default="true" />
#define RT_USING_INTERRUPT_INFO
// </section>
// <bool name="RT_USING_HOOK" description="Using hook functions" default="true" />
......
......@@ -34,7 +34,7 @@ struct serial_device uart0 =
/**
* This function will handle rtos timer
*/
void rt_timer_handler(int vector)
void rt_timer_handler(int vector, void *param)
{
rt_uint32_t clear_int;
rt_tick_increase();
......@@ -47,7 +47,7 @@ void rt_timer_handler(int vector)
/**
* This function will handle serial
*/
void rt_serial_handler(int vector)
void rt_serial_handler(int vector, void *param)
{
//rt_kprintf("in rt_serial_handler\n");
rt_int32_t stat = *(RP)UART0_IIR ;
......@@ -78,16 +78,17 @@ static void rt_hw_board_led_init(void)
*(RP)GPIO_PORTE_DATA &= ~0x38; /* low */
}
/**
* This function will init timer4 for system ticks
*/
void rt_hw_timer_init(void)
void rt_hw_timer_init(void)
{
/*Set timer1*/
*(RP)TIMER_T1LCR = 880000;
*(RP)TIMER_T1CR = 0x06;
rt_hw_interrupt_install(INTSRC_TIMER1, rt_timer_handler, RT_NULL);
rt_hw_interrupt_install(INTSRC_TIMER1, rt_timer_handler, RT_NULL, "tick");
rt_hw_interrupt_umask(INTSRC_TIMER1);
/*Enable timer1*/
......@@ -119,7 +120,7 @@ void rt_hw_uart_init(void)
/*Disable tx interrupt*/
*(RP)(UART0_IER) &= ~(0x1<<1);
rt_hw_interrupt_install(INTSRC_UART0, rt_serial_handler, RT_NULL);
rt_hw_interrupt_install(INTSRC_UART0, rt_serial_handler, RT_NULL, "UART0");
rt_hw_interrupt_umask(INTSRC_UART0);
/* register uart0 */
rt_hw_serial_register(&uart0_device, "uart0",
......
......@@ -81,7 +81,7 @@ struct rt_dm9161_eth
static struct rt_dm9161_eth dm9161_device;
static struct rt_semaphore sem_ack, sem_lock;
void rt_dm9161_isr(int irqno);
void rt_dm9161_isr(int irqno, void *param);
static void udelay(unsigned long ns)
{
......@@ -201,7 +201,7 @@ static void read_phy(unsigned char phy_addr, unsigned char address, unsigned int
}
/* interrupt service routine */
void rt_dm9161_isr(int irqno)
void rt_dm9161_isr(int irqno, void *param)
{
unsigned long intstatus;
rt_uint32_t address;
......@@ -469,7 +469,7 @@ static rt_err_t rt_dm9161_open(rt_device_t dev, rt_uint16_t oflag)
*(volatile unsigned long*)GPIO_PORTA_INTRCLR |= 0x0080; //清除中断
*(volatile unsigned long*)GPIO_PORTA_INTRCLR = 0x0000; //清除中断
rt_hw_interrupt_install(INTSRC_MAC, rt_dm9161_isr, RT_NULL);
rt_hw_interrupt_install(INTSRC_MAC, rt_dm9161_isr, RT_NULL, "EMAC");
enable_irq(INTSRC_EXINT7);
......
......@@ -20,6 +20,7 @@
/* #define RT_THREAD_DEBUG */
#define RT_USING_OVERFLOW_CHECK
#define RT_USING_INTERRUPT_INFO
/* Using Hook */
#define RT_USING_HOOK
......
......@@ -31,14 +31,14 @@ Options 1,0,0 // Target 'RT-Thread_Mini4020'
EnvReg ()
OrgReg ()
TgStat=16
OutDir (.\)
OutDir (.\build\)
OutName (rtthread-mini4020)
GenApp=1
GenLib=0
GenHex=0
Debug=1
Browse=0
LstDir (.\)
LstDir (.\build\)
HexSel=1
MG32K=0
TGMORE=0
......
......@@ -97,7 +97,7 @@ void rtthread_startup(void)
#elif __ICCARM__
rt_system_heap_init(__segment_end("HEAP"), (void*)0x00210000);
#else
rt_system_heap_init(&__bss_end, 0x00210000);
rt_system_heap_init(&__bss_end, (void*)0x00210000);
#endif
#endif
......
......@@ -33,7 +33,7 @@ static void rt_hw_board_led_init(void);
* This is the timer interrupt service routine.
* @param vector the irq number for timer
*/
void rt_hw_timer_handler(int vector)
void rt_hw_timer_handler(int vector, void* param)
{
if (AT91C_BASE_PITC->PITC_PISR & 0x01)
{
......@@ -154,7 +154,7 @@ static void rt_hw_console_init()
/**
* This function will initial sam7x board.
*/
void rt_hw_board_init()
void rt_hw_board_init(void)
{
extern void rt_serial_init(void);
......@@ -168,7 +168,7 @@ void rt_hw_board_init()
AT91C_BASE_PITC->PITC_PIMR = (1 << 25) | (1 << 24) | PIV;
/* install timer handler */
rt_hw_interrupt_install(AT91C_ID_SYS, rt_hw_timer_handler, RT_NULL);
rt_hw_interrupt_install(AT91C_ID_SYS, rt_hw_timer_handler, RT_NULL, "tick");
AT91C_BASE_AIC->AIC_SMR[AT91C_ID_SYS] = 0;
rt_hw_interrupt_umask(AT91C_ID_SYS);
}
......
......@@ -120,7 +120,7 @@ rt_inline void sam7xether_reset_tx_desc(void)
/* interrupt service routing */
static void sam7xether_isr(int irq)
static void sam7xether_isr(int irq, void* param)
{
/* Variable definitions can be made now. */
volatile rt_uint32_t isr, rsr;
......@@ -377,7 +377,7 @@ rt_err_t sam7xether_init(rt_device_t dev)
AT91C_BASE_EMAC->EMAC_IER = AT91C_EMAC_RCOMP | AT91C_EMAC_TCOMP;
/* setup interrupt */
rt_hw_interrupt_install(AT91C_ID_EMAC, sam7xether_isr, RT_NULL);
rt_hw_interrupt_install(AT91C_ID_EMAC, sam7xether_isr, RT_NULL, "emac");
*(volatile unsigned int*)(0xFFFFF000 + AT91C_ID_EMAC * 4) = AT91C_AIC_SRCTYPE_INT_HIGH_LEVEL | 5;
// AT91C_AIC_SMR(AT91C_ID_EMAC) = AT91C_AIC_SRCTYPE_INT_HIGH_LEVEL | 5;
rt_hw_interrupt_umask(AT91C_ID_EMAC);
......
......@@ -76,27 +76,12 @@ struct rt_at91serial serial1;
struct rt_at91serial serial2;
#endif
static void rt_hw_serial_isr(int irqno)
static void rt_hw_serial_isr(int irqno, void* param)
{
rt_base_t level;
struct rt_device* device;
struct rt_at91serial* serial = RT_NULL;
struct rt_at91serial* serial = (struct rt_at91serial*)param;
#ifdef RT_USING_UART1
if (irqno == AT91C_ID_US0)
{
/* serial 1 */
serial = &serial1;
}
#endif
#ifdef RT_USING_UART2
if (irqno == AT91C_ID_US1)
{
/* serial 2 */
serial = &serial2;
}
#endif
RT_ASSERT(serial != RT_NULL);
/* get generic device object */
......@@ -202,7 +187,7 @@ static rt_err_t rt_serial_open(rt_device_t dev, rt_uint16_t oflag)
//serial->hw_base->US_IMR |= 1 << 0; /* umask RxReady interrupt */
/* install UART handler */
rt_hw_interrupt_install(serial->peripheral_id, rt_hw_serial_isr, RT_NULL);
rt_hw_interrupt_install(serial->peripheral_id, rt_hw_serial_isr, serial, "uart");
// SAM7X Datasheet 30.5.3:
// It is notrecommended to use the USART interrupt line in edge sensitive mode
//AT91C_AIC_SMR(serial->peripheral_id) = 5 | (0x01 << 5);
......
......@@ -184,7 +184,6 @@ static void *sdl_loop(void *lpParam)
switch (event.type)
{
case SDL_MOUSEMOTION:
#if 0
{
struct rtgui_event_mouse emouse;
emouse.parent.type = RTGUI_EVENT_MOUSE_MOTION;
......@@ -200,7 +199,6 @@ static void *sdl_loop(void *lpParam)
/* send event to server */
rtgui_server_post_event(&emouse.parent, sizeof(struct rtgui_event_mouse));
}
#endif
break;
case SDL_MOUSEBUTTONDOWN:
......
......@@ -304,6 +304,9 @@ char *dfs_normalize_path(const char *directory, const char *filename)
{
fullpath = rt_malloc(strlen(directory) + strlen(filename) + 2);
if (fullpath == RT_NULL)
return RT_NULL;
/* join path and file name */
rt_snprintf(fullpath, strlen(directory) + strlen(filename) + 2,
"%s/%s", directory, filename);
......@@ -311,6 +314,9 @@ char *dfs_normalize_path(const char *directory, const char *filename)
else
{
fullpath = rt_strdup(filename); /* copy string */
if (fullpath == RT_NULL)
return RT_NULL;
}
src = fullpath;
......
/*
* File : cmd.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006, RT-Thread Development Team
* RT-Thread finsh shell commands
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......@@ -604,6 +619,9 @@ long list(void)
index < _syscall_table_end;
FINSH_NEXT_SYSCALL(index))
{
/* skip the internal command */
if (strncpy((char*)index->name, "__", 2) == 0) continue;
#ifdef FINSH_USING_DESCRIPTION
rt_kprintf("%-16s -- %s\n", index->name, index->desc);
#else
......@@ -693,6 +711,9 @@ void list_prefix(char *prefix)
index < _syscall_table_end;
FINSH_NEXT_SYSCALL(index))
{
/* skip internal command */
if (str_is_prefix("__", index->name) == 0) continue;
if (str_is_prefix(prefix, index->name) == 0)
{
if (func_cnt == 0)
......
/*
* File : finsh_compiler.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, RT-Thread Development Team
* RT-Thread finsh shell compiler
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
/*
* File : finsh_error.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, RT-Thread Development Team
* error number for finsh shell.
*
* 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
* COPYRIGHT (C) 2013, Shanghai Real-Thread Technology Co., Ltd
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
/*
* File : finsh_error.h
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, RT-Thread Development Team
* error number for finsh shell.
*
* 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
* COPYRIGHT (C) 2013, Shanghai Real-Thread Technology Co., Ltd
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
/*
* File : finsh_heap.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, RT-Thread Development Team
* heap management in finsh shell.
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
/*
* File : finsh_heap.h
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, RT-Thread Development Team
* heap management in finsh shell.
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
/*
* File : finsh_init.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, RT-Thread Development Team
* Initialization procedure for finsh shell.
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
/*
* File : finsh_node.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, RT-Thread Development Team
* node routines for finsh shell.
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
/*
* File : finsh_node.h
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, RT-Thread Development Team
* node routines for finsh shell.
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
/*
* File : finsh_ops.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, RT-Thread Development Team
* operations for finsh shell.
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
/*
* File : finsh_ops.h
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, RT-Thread Development Team
* operations for finsh shell.
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
/*
* File : finsh_parser.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, RT-Thread Development Team
* script parser for finsh shell.
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
/*
* File : finsh_parser.h
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, RT-Thread Development Team
* script parser for finsh shell.
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
/*
* File : finsh_token.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, RT-Thread Development Team
* token lex for finsh shell.
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
/*
* File : finsh_token.h
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, RT-Thread Development Team
* token lex for finsh shell.
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
/*
* File : finsh_var.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, RT-Thread Development Team
* Variable implementation in finsh shell.
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
/*
* File : finsh_var.h
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, RT-Thread Development Team
* Variable implementation in finsh shell.
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
/*
* File : finsh_vm.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, RT-Thread Development Team
* Virtual machine finsh shell.
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
/*
* File : finsh_vm.h
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, RT-Thread Development Team
* Virtual machine finsh shell.
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
/*
* RT-Thread module shell implementation.
*
* COPYRIGHT (C) 2013, Shanghai Real-Thread Technology Co., Ltd
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
* 2013-03-30 Bernard the first verion for FinSH
*/
#include "msh.h"
#include <finsh.h>
#include <shell.h>
#define RT_FINSH_ARG_MAX 10
typedef int (*cmd_function_t)(int argc, char** argv);
#ifdef FINSH_USING_MSH
#ifdef FINSH_USING_MSH_DEFAULT
static rt_bool_t __msh_state = RT_TRUE;
#else
static rt_bool_t __msh_state = RT_FALSE;
#endif
rt_bool_t msh_is_used(void)
{
return __msh_state;
}
static int msh_exit(int argc, char** argv)
{
/* return to finsh shell mode */
__msh_state = RT_FALSE;
return 0;
}
FINSH_FUNCTION_EXPORT_ALIAS(msh_exit, __cmd_exit, return to RT-Thread shell mode.);
static int msh_enter(void)
{
/* enter module shell mode */
__msh_state = RT_TRUE;
return 0;
}
FINSH_FUNCTION_EXPORT_ALIAS(msh_enter, msh, use module shell);
int msh_help(int argc, char** argv)
{
rt_kprintf("RT-Thread shell commands:\n");
{
struct finsh_syscall *index;
for (index = _syscall_table_begin;
index < _syscall_table_end;
FINSH_NEXT_SYSCALL(index))
{
if (strncmp(index->name, "__cmd_", 6) != 0) continue;
rt_kprintf("%s ", &index->name[6]);
}
}
rt_kprintf("\n");
return 0;
}
FINSH_FUNCTION_EXPORT_ALIAS(msh_help, __cmd_help, "RT-Thread shell help.");
static int msh_split(char* cmd, rt_size_t length, char* argv[RT_FINSH_ARG_MAX])
{
char *ptr;
rt_size_t position;
rt_size_t argc;
ptr = cmd;
position = 0; argc = 0;
while (position < length)
{
/* strip bank and tab */
while ((*ptr == ' ' || *ptr == '\t') && position < length)
{
*ptr = '\0';
ptr ++; position ++;
}
if (position >= length) break;
/* handle string */
if (*ptr == '"')
{
ptr ++; position ++;
argv[argc] = ptr; argc ++;
/* skip this string */
while (*ptr != '"' && position < length)
{
if (*ptr == '\\')
{
if (*(ptr + 1) == '"')
{
ptr ++; position ++;
}
}
ptr ++; position ++;
}
if (position >= length) break;
/* skip '"' */
*ptr = '\0'; ptr ++; position ++;
}
else
{
argv[argc] = ptr;
argc ++;
while ((*ptr != ' ' && *ptr != '\t') && position < length)
{
ptr ++; position ++;
}
if (position >= length) break;
}
}
return argc;
}
static cmd_function_t msh_get_cmd(char *cmd)
{
struct finsh_syscall *index;
cmd_function_t cmd_func = RT_NULL;
for (index = _syscall_table_begin;
index < _syscall_table_end;
FINSH_NEXT_SYSCALL(index))
{
if (strncmp(index->name, "__cmd_", 6) != 0) continue;
if (strcmp(&index->name[6], cmd) == 0)
{
cmd_func = (cmd_function_t)index->func;
break;
}
}
return cmd_func;
}
int msh_exec(char* cmd, rt_size_t length)
{
int argc;
char *argv[RT_FINSH_ARG_MAX];
cmd_function_t cmd_func;
memset(argv, 0x00, sizeof(argv));
argc = msh_split(cmd, length, argv);
if (argc == 0) return -1;
/* get command in internal commands */
cmd_func = msh_get_cmd(argv[0]);
if (cmd_func == RT_NULL)
{
rt_kprintf("%s: command not found\n", argv[0]);
return -1;
}
/* exec this command */
return cmd_func(argc, argv);
}
static int str_common(const char *str1, const char *str2)
{
const char *str = str1;
while ((*str != 0) && (*str2 != 0) && (*str == *str2))
{
str ++;
str2 ++;
}
return (str - str1);
}
void msh_auto_complete(char *prefix)
{
rt_uint16_t func_cnt;
int length, min_length;
const char *name_ptr, *cmd_name;
struct finsh_syscall *index;
func_cnt = 0;
min_length = 0;
name_ptr = RT_NULL;
if (*prefix == '\0')
{
msh_help(0, RT_NULL);
return;
}
/* checks in internal command */
{
for (index = _syscall_table_begin; index < _syscall_table_end; FINSH_NEXT_SYSCALL(index))
{
/* skip finsh shell function */
if (strncmp(index->name, "__cmd_", 6) != 0) continue;
cmd_name = (const char*) &index->name[6];
if (strncmp(prefix, cmd_name, strlen(prefix)) == 0)
{
if (func_cnt == 0)
{
/* set name_ptr */
name_ptr = cmd_name;
/* set initial length */
min_length = strlen(name_ptr);
}
func_cnt ++;
length = str_common(name_ptr, cmd_name);
if (length < min_length)
min_length = length;
rt_kprintf("%s\n", cmd_name);
}
}
}
/* auto complete string */
if (name_ptr != NULL)
{
rt_strncpy(prefix, name_ptr, min_length);
}
return ;
}
#endif
/*
* RT-Thread module shell implementation.
*
* COPYRIGHT (C) 2013, Shanghai Real-Thread Technology Co., Ltd
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
* 2013-03-30 Bernard the first verion for FinSH
*/
#ifndef __M_SHELL__
#define __M_SHELL__
#include <rtthread.h>
rt_bool_t msh_is_used(void);
int msh_exec(char* cmd, rt_size_t length);
void msh_auto_complete(char *prefix);
#endif
/*
* internal commands for RT-Thread module shell
*
* COPYRIGHT (C) 2013, Shanghai Real-Thread Technology Co., Ltd
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
* 2013-03-30 Bernard the first verion for FinSH
*/
#include <rtthread.h>
#include <finsh.h>
#include "msh.h"
#ifdef FINSH_USING_MSH
#ifdef RT_USING_DFS
#include <dfs_posix.h>
#ifdef DFS_USING_WORKDIR
extern char working_directory[];
#endif
int cmd_ps(int argc, char** argv)
{
extern long list_thread(void);
list_thread();
return 0;
}
FINSH_FUNCTION_EXPORT_ALIAS(cmd_ps, __cmd_ps, "list threads in the system");
int cmd_i(int argc, char** argv)
{
return cmd_ps(argc, argv);
}
FINSH_FUNCTION_EXPORT_ALIAS(cmd_i, __cmd_i, "list threads in the system");
int cmd_time(int argc, char** argv)
{
return 0;
}
FINSH_FUNCTION_EXPORT_ALIAS(cmd_time, __cmd_time, "exec command with time");
int cmd_free(int argc, char** argv)
{
extern void list_mem(void);
list_mem();
return 0;
}
FINSH_FUNCTION_EXPORT_ALIAS(cmd_free, __cmd_free, "show the memory usage in the system");
int cmd_ls(int argc, char** argv)
{
extern void ls(const char *pathname);
if (argc == 1)
{
#ifdef DFS_USING_WORKDIR
ls(working_directory);
#else
ls("/");
#endif
}
else
{
ls(argv[1]);
}
return 0;
}
FINSH_FUNCTION_EXPORT_ALIAS(cmd_ls, __cmd_ls, "List information about the FILEs.");
int cmd_cp(int argc, char** argv)
{
void copy(const char *src, const char *dst);
if (argc != 3)
{
rt_kprintf("Usage: cp SOURCE DEST\n");
rt_kprintf("Copy SOURCE to DEST.\n");
}
else
{
copy(argv[1], argv[2]);
}
return 0;
}
FINSH_FUNCTION_EXPORT_ALIAS(cmd_cp, __cmd_cp, "Copy SOURCE to DEST.");
int cmd_mv(int argc, char** argv)
{
if (argc != 3)
{
rt_kprintf("Usage: mv SOURCE DEST\n");
rt_kprintf("Rename SOURCE to DEST, or move SOURCE(s) to DIRECTORY.\n");
}
else
{
rt_kprintf("%s => %s\n", argv[1], argv[2]);
}
return 0;
}
FINSH_FUNCTION_EXPORT_ALIAS(cmd_mv, __cmd_mv, "Rename SOURCE to DEST.");
int cmd_cat(int argc, char** argv)
{
int index;
extern void cat(const char* filename);
if (argc == 1)
{
rt_kprintf("Usage: cat [FILE]...\n");
rt_kprintf("Concatenate FILE(s)\n");
return 0;
}
for (index = 1; index < argc; index ++)
{
cat(argv[index]);
}
return 0;
}
FINSH_FUNCTION_EXPORT_ALIAS(cmd_cat, __cmd_cat, "Concatenate FILE(s)");
int cmd_rm(int argc, char** argv)
{
int index;
if (argc == 1)
{
rt_kprintf("Usage: rm FILE...\n");
rt_kprintf("Remove (unlink) the FILE(s).\n");
return 0;
}
for (index = 1; index < argc; index ++)
{
unlink(argv[index]);
}
return 0;
}
FINSH_FUNCTION_EXPORT_ALIAS(cmd_rm, __cmd_rm, "Remove (unlink) the FILE(s).");
int cmd_cd(int argc, char** argv)
{
if (argc == 1)
{
rt_kprintf("%s\n", working_directory);
}
else if (argc == 2)
{
chdir(argv[1]);
}
return 0;
}
FINSH_FUNCTION_EXPORT_ALIAS(cmd_cd, __cmd_cd, Change the shell working directory.);
int cmd_pwd(int argc, char** argv)
{
rt_kprintf("%s\n", working_directory);
return 0;
}
FINSH_FUNCTION_EXPORT_ALIAS(cmd_pwd, __cmd_pwd, Print the name of the current working directory.);
int cmd_mkdir(int argc, char** argv)
{
if (argc == 1)
{
rt_kprintf("Usage: mkdir [OPTION] DIRECTORY\n");
rt_kprintf("Create the DIRECTORY, if they do not already exist.\n");
}
else
{
mkdir(argv[1], 0);
}
return 0;
}
FINSH_FUNCTION_EXPORT_ALIAS(cmd_mkdir, __cmd_mkdir, Create the DIRECTORY.);
#endif
#endif
/*
* File : shell.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006, RT-Thread Development Team
* shell implementation for finsh shell.
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
* 2006-04-30 Bernard the first verion for FinSH
* 2006-04-30 Bernard the first version for FinSH
* 2006-05-08 Bernard change finsh thread stack to 2048
* 2006-06-03 Bernard add support for skyeye
* 2006-09-24 Bernard remove the code related with hardware
......@@ -26,6 +41,10 @@
#include "finsh.h"
#include "shell.h"
#ifdef FINSH_USING_MSH
#include "msh.h"
#endif
#ifdef _WIN32
#include <stdio.h> /* for putchar */
#endif
......@@ -192,7 +211,17 @@ void finsh_auto_complete(char* prefix)
extern void list_prefix(char* prefix);
rt_kprintf("\n");
list_prefix(prefix);
#ifdef FINSH_USING_MSH
if (msh_is_used() == RT_TRUE)
{
msh_auto_complete(prefix);
}
else
#endif
{
list_prefix(prefix);
}
rt_kprintf("%s%s", FINSH_PROMPT, prefix);
}
......@@ -420,15 +449,28 @@ void finsh_thread_entry(void* parameter)
/* handle end of line, break */
if (ch == '\r' || ch == '\n')
{
/* change to ';' and break */
shell->line[shell->line_position] = ';';
#ifdef FINSH_USING_MSH
if (msh_is_used() == RT_TRUE && shell->line_position != 0)
{
rt_kprintf("\n");
msh_exec(shell->line, shell->line_position);
#ifdef FINSH_USING_HISTORY
finsh_push_history(shell);
#endif
}
else
#endif
{
/* add ';' and run the command line */
shell->line[shell->line_position] = ';';
#ifdef FINSH_USING_HISTORY
finsh_push_history(shell);
#endif
#ifdef FINSH_USING_HISTORY
finsh_push_history(shell);
#endif
if (shell->line_position != 0) finsh_run_line(&shell->parser, shell->line);
else rt_kprintf("\n");
if (shell->line_position != 0) finsh_run_line(&shell->parser, shell->line);
else rt_kprintf("\n");
}
rt_kprintf(FINSH_PROMPT);
memset(shell->line, 0, sizeof(shell->line));
......
/*
* File : shell.h
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2011, RT-Thread Development Team
* shell implementation for finsh shell.
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
/*
* File : symbol.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, RT-Thread Development Team
* symbols in finsh shell.
*
* 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
* COPYRIGHT (C) 2006 - 2013, RT-Thread Development Team
*
* This file is part of RT-Thread (http://www.rt-thread.org)
* Maintainer: bernard.xiong <bernard.xiong at gmail.com>
*
* All rights reserved.
*
* This program is free software; you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation; either version 2 of the License, or
* (at your option) any later version.
*
* This program 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 General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program; if not, write to the Free Software Foundation, Inc.,
* 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
*
* Change Logs:
* Date Author Notes
......
......@@ -8,14 +8,14 @@ if GetDepend('RT_USING_NEWLIB') and rtconfig.CROSS_TOOL != 'gcc':
exit(0)
cwd = GetCurrentDir()
src = Glob('*.c')
src = Glob('*.c')
CPPPATH = [cwd]
# link with libm in default.
# link with libc and libm:
# libm is a frequently used lib. Newlib is compiled with -ffunction-sections in
# recent GCC tool chains. The linker would just link in the functions that have
# been referenced. So setting this won't result in bigger text size.
LIBS = ['m']
LIBS = ['c', 'm']
group = DefineGroup('newlib', src, depend = ['RT_USING_NEWLIB'],
CPPPATH = CPPPATH, LIBS = LIBS)
......
# for network related component
import os
Import('RTT_ROOT')
from building import *
objs = []
list = os.listdir(os.path.join(RTT_ROOT, 'components', 'net'))
# the default version of LWIP is 1.4.0
if not GetDepend('RT_USING_LWIP132') and not GetDepend('RT_USING_LWIP141'):
AddDepend('RT_USING_LWIP140')
for d in list:
path = os.path.join(RTT_ROOT, 'components', 'net', d)
if os.path.isfile(os.path.join(path, 'SConscript')):
......
Import('RTT_ROOT')
from building import *
src = Split("""
src/api/api_lib.c
src/api/api_msg.c
src/api/err.c
src/api/netbuf.c
src/api/netdb.c
src/api/netifapi.c
src/api/sockets.c
src/api/tcpip.c
src/arch/sys_arch.c
src/core/def.c
src/core/dhcp.c
src/core/dns.c
src/core/init.c
src/core/memp.c
src/core/netif.c
src/core/pbuf.c
src/core/raw.c
src/core/stats.c
src/core/sys.c
src/core/tcp.c
src/core/tcp_in.c
src/core/tcp_out.c
src/core/timers.c
src/core/udp.c
src/core/ipv4/autoip.c
src/core/ipv4/icmp.c
src/core/ipv4/igmp.c
src/core/ipv4/inet.c
src/core/ipv4/inet_chksum.c
src/core/ipv4/ip.c
src/core/ipv4/ip_addr.c
src/core/ipv4/ip_frag.c
src/netif/etharp.c
src/netif/ethernetif.c
src/netif/slipif.c
""")
snmp_src = Split("""
src/core/snmp/asn1_dec.c
src/core/snmp/asn1_enc.c
src/core/snmp/mib2.c
src/core/snmp/mib_structs.c
src/core/snmp/msg_in.c
src/core/snmp/msg_out.c
""")
ppp_src = Split("""
src/netif/ppp/auth.c
src/netif/ppp/chap.c
src/netif/ppp/chpms.c
src/netif/ppp/fsm.c
src/netif/ppp/ipcp.c
src/netif/ppp/lcp.c
src/netif/ppp/magic.c
src/netif/ppp/md5.c
src/netif/ppp/pap.c
src/netif/ppp/ppp.c
src/netif/ppp/ppp_oe.c
src/netif/ppp/randm.c
src/netif/ppp/vj.c
""")
# The set of source files associated with this SConscript file.
path = [GetCurrentDir() + '/src',
GetCurrentDir() + '/src/include',
GetCurrentDir() + '/src/include/ipv4',
GetCurrentDir() + '/src/arch/include',
GetCurrentDir() + '/src/include/netif']
if GetDepend(['RT_LWIP_SNMP']):
src += snmp_src
if GetDepend(['RT_LWIP_PPP']):
src += ppp_src
path += [GetCurrentDir() + '/src/netif/ppp']
# For testing apps
if GetDepend(['RT_USING_NETUTILS']):
src += Glob('./apps/*.c')
group = DefineGroup('LwIP', src, depend = ['RT_USING_LWIP', 'RT_USING_LWIP141'], CPPPATH = path)
Return('group')
/*
* Copyright (c) 2001-2003 Swedish Institute of Computer Science.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. The name of the author may not be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT
* SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
* EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
* OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING
* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
* OF SUCH DAMAGE.
*
* This file is part of the lwIP TCP/IP stack.
*
* Author: Adam Dunkels <adam@sics.se>
*
*/
#if defined(__ICCARM__)
#pragma pack(1)
#endif
/*
* Copyright (c) 2001, Swedish Institute of Computer Science.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the Institute nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE.
*
* This file is part of the lwIP TCP/IP stack.
*
* Author: Adam Dunkels <adam@sics.se>
*
* $Id: cc.h,v 1.1.1.1 2004/12/16 14:17:13 bear Exp $
*/
#ifndef __ARCH_CC_H__
#define __ARCH_CC_H__
#include <rthw.h>
#include <rtthread.h>
typedef rt_uint8_t u8_t;
typedef rt_int8_t s8_t;
typedef rt_uint16_t u16_t;
typedef rt_int16_t s16_t;
typedef rt_uint32_t u32_t;
typedef rt_int32_t s32_t;
typedef rt_uint32_t mem_ptr_t;
#define U16_F "hu"
#define S16_F "hd"
#define X16_F "hx"
#define U32_F "lu"
#define S32_F "ld"
#define X32_F "lx"
#ifdef RT_USING_NEWLIB
#include <errno.h>
/* some errno not defined in newlib */
#define ENSRNOTFOUND 163 /* Domain name not found */
/* WARNING: ESHUTDOWN also not defined in newlib. We chose
180 here because the number "108" which is used
in arch.h has been assigned to another error code. */
#define ESHUTDOWN 180
#elif RT_USING_MINILIBC
#include <errno.h>
#define EADDRNOTAVAIL 99 /* Cannot assign requested address */
#else
#define LWIP_PROVIDE_ERRNO
#endif
#ifdef RT_USING_MINILIBC
#include <time.h>
#define LWIP_TIMEVAL_PRIVATE 0
#endif
#if defined(__CC_ARM) /* ARMCC compiler */
#define PACK_STRUCT_FIELD(x) x
#define PACK_STRUCT_STRUCT __attribute__ ((__packed__))
#define PACK_STRUCT_BEGIN
#define PACK_STRUCT_END
#elif defined(__IAR_SYSTEMS_ICC__) /* IAR Compiler */
#define PACK_STRUCT_BEGIN
#define PACK_STRUCT_STRUCT
#define PACK_STRUCT_END
#define PACK_STRUCT_FIELD(x) x
#define PACK_STRUCT_USE_INCLUDES
#elif defined(__GNUC__) /* GNU GCC Compiler */
#define PACK_STRUCT_FIELD(x) x
#define PACK_STRUCT_STRUCT __attribute__((packed))
#define PACK_STRUCT_BEGIN
#define PACK_STRUCT_END
#elif defined(_MSC_VER)
#define PACK_STRUCT_FIELD(x) x
#define PACK_STRUCT_STRUCT
#define PACK_STRUCT_BEGIN
#define PACK_STRUCT_END
#endif
void sys_arch_assert(const char* file, int line);
#define LWIP_PLATFORM_DIAG(x) do {rt_kprintf x;} while(0)
#define LWIP_PLATFORM_ASSERT(x) do {rt_kprintf(x); sys_arch_assert(__FILE__, __LINE__);}while(0)
#include "string.h"
#endif /* __ARCH_CC_H__ */
/*
* Copyright (c) 2001-2003 Swedish Institute of Computer Science.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. The name of the author may not be used to endorse or promote products
* derived from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED
* WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
* MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT
* SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
* EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
* OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING
* IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY
* OF SUCH DAMAGE.
*
* This file is part of the lwIP TCP/IP stack.
*
* Author: Adam Dunkels <adam@sics.se>
*
*/
#if defined(__ICCARM__)
#pragma pack()
#endif
/*
* Copyright (c) 2001, Swedish Institute of Computer Science.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the Institute nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE.
*
* This file is part of the lwIP TCP/IP stack.
*
* Author: Adam Dunkels <adam@sics.se>
*
* $Id: perf.h,v 1.1.1.1 2004/12/16 14:17:13 bear Exp $
*/
#ifndef __ARCH_PERF_H__
#define __ARCH_PERF_H__
//#include <sys/times.h>
#define PERF_START /* null definition */
#define PERF_STOP(x) /* null definition */
/*
void perf_print(unsigned long c1l, unsigned long c1h,
unsigned long c2l, unsigned long c2h,
char *key);
void perf_print_times(struct tms *start, struct tms *end, char *key);
void perf_init(char *fname);
*/
#endif /* __ARCH_PERF_H__ */
/*
* Copyright (c) 2001, Swedish Institute of Computer Science.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* 3. Neither the name of the Institute nor the names of its contributors
* may be used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE INSTITUTE AND CONTRIBUTORS ``AS IS'' AND
* ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE INSTITUTE OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
* OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
* OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
* SUCH DAMAGE.
*
* This file is part of the lwIP TCP/IP stack.
*
* Author: Adam Dunkels <adam@sics.se>
*
* $Id: sys_arch.h,v 1.3 2005/03/13 16:03:23 bear Exp $
*/
#ifndef __ARCH_SYS_ARCH_H__
#define __ARCH_SYS_ARCH_H__
#include "arch/cc.h"
#include <rtthread.h>
#ifndef BYTE_ORDER
#define BYTE_ORDER LITTLE_ENDIAN
#endif
#define SYS_MBOX_NULL RT_NULL
#define SYS_SEM_NULL RT_NULL
typedef u32_t sys_prot_t;
#define SYS_MBOX_SIZE 10
#define SYS_LWIP_TIMER_NAME "timer"
#define SYS_LWIP_MBOX_NAME "mbox"
#define SYS_LWIP_SEM_NAME "sem"
#define SYS_LWIP_MUTEX_NAME "mu"
typedef rt_sem_t sys_sem_t;
typedef rt_mutex_t sys_mutex_t;
typedef rt_mailbox_t sys_mbox_t;
typedef rt_thread_t sys_thread_t;
#endif /* __ARCH_SYS_ARCH_H__ */
/*
* File : sys_arch.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2012, 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
* 2012-12-8 Bernard add file header
* export bsd socket symbol for RT-Thread Application Module
*/
#include <rtthread.h>
#include "lwip/sys.h"
#include "lwip/opt.h"
#include "lwip/stats.h"
#include "lwip/err.h"
#include "arch/sys_arch.h"
#include "lwip/debug.h"
#include "lwip/netif.h"
#include "lwip/tcpip.h"
#include "netif/ethernetif.h"
#include "lwip/sio.h"
#include <string.h>
static err_t netif_device_init(struct netif *netif)
{
struct eth_device *ethif;
ethif = (struct eth_device *)netif->state;
if (ethif != RT_NULL)
{
rt_device_t device;
/* get device object */
device = (rt_device_t) ethif;
if (rt_device_init(device) != RT_EOK)
{
return ERR_IF;
}
/* copy device flags to netif flags */
netif->flags = ethif->flags;
return ERR_OK;
}
return ERR_IF;
}
static void tcpip_init_done_callback(void *arg)
{
rt_device_t device;
struct eth_device *ethif;
struct ip_addr ipaddr, netmask, gw;
struct rt_list_node* node;
struct rt_object* object;
struct rt_object_information *information;
extern struct rt_object_information rt_object_container[];
LWIP_ASSERT("invalid arg.\n",arg);
IP4_ADDR(&gw, 0,0,0,0);
IP4_ADDR(&ipaddr, 0,0,0,0);
IP4_ADDR(&netmask, 0,0,0,0);
/* enter critical */
rt_enter_critical();
/* for each network interfaces */
information = &rt_object_container[RT_Object_Class_Device];
for (node = information->object_list.next;
node != &(information->object_list);
node = node->next)
{
object = rt_list_entry(node, struct rt_object, list);
device = (rt_device_t)object;
if (device->type == RT_Device_Class_NetIf)
{
ethif = (struct eth_device *)device;
/* leave critical */
rt_exit_critical();
netif_add(ethif->netif, &ipaddr, &netmask, &gw,
ethif, netif_device_init, tcpip_input);
if (netif_default == RT_NULL)
netif_set_default(ethif->netif);
#if LWIP_DHCP
if (ethif->flags & NETIF_FLAG_DHCP)
{
/* if this interface uses DHCP, start the DHCP client */
dhcp_start(ethif->netif);
}
else
#endif
{
/* set interface up */
netif_set_up(ethif->netif);
}
#ifdef LWIP_NETIF_LINK_CALLBACK
netif_set_link_up(ethif->netif);
#endif
/* enter critical */
rt_enter_critical();
}
}
/* leave critical */
rt_exit_critical();
rt_sem_release((rt_sem_t)arg);
}
/**
* LwIP system initialization
*/
void lwip_system_init(void)
{
rt_err_t rc;
struct rt_semaphore done_sem;
/* set default netif to NULL */
netif_default = RT_NULL;
rc = rt_sem_init(&done_sem, "done", 0, RT_IPC_FLAG_FIFO);
if (rc != RT_EOK)
{
LWIP_ASSERT("Failed to create semaphore", 0);
return;
}
tcpip_init(tcpip_init_done_callback, (void *)&done_sem);
/* waiting for initialization done */
if (rt_sem_take(&done_sem, RT_WAITING_FOREVER) != RT_EOK)
{
rt_sem_detach(&done_sem);
return;
}
rt_sem_detach(&done_sem);
/* set default ip address */
#if !LWIP_DHCP
if (netif_default != RT_NULL)
{
struct ip_addr ipaddr, netmask, gw;
IP4_ADDR(&ipaddr, RT_LWIP_IPADDR0, RT_LWIP_IPADDR1, RT_LWIP_IPADDR2, RT_LWIP_IPADDR3);
IP4_ADDR(&gw, RT_LWIP_GWADDR0, RT_LWIP_GWADDR1, RT_LWIP_GWADDR2, RT_LWIP_GWADDR3);
IP4_ADDR(&netmask, RT_LWIP_MSKADDR0, RT_LWIP_MSKADDR1, RT_LWIP_MSKADDR2, RT_LWIP_MSKADDR3);
netifapi_netif_set_addr(netif_default, &ipaddr, &netmask, &gw);
}
#endif
}
void sys_init(void)
{
/* nothing on RT-Thread porting */
}
void lwip_sys_init(void)
{
lwip_system_init();
}
err_t sys_sem_new(sys_sem_t *sem, u8_t count)
{
static unsigned short counter = 0;
char tname[RT_NAME_MAX];
sys_sem_t tmpsem;
RT_DEBUG_NOT_IN_INTERRUPT;
rt_snprintf(tname, RT_NAME_MAX, "%s%d", SYS_LWIP_SEM_NAME, counter);
counter ++;
tmpsem = rt_sem_create(tname, count, RT_IPC_FLAG_FIFO);
if (tmpsem == RT_NULL)
return ERR_MEM;
else
{
*sem = tmpsem;
return ERR_OK;
}
}
void sys_sem_free(sys_sem_t *sem)
{
RT_DEBUG_NOT_IN_INTERRUPT;
rt_sem_delete(*sem);
}
void sys_sem_signal(sys_sem_t *sem)
{
rt_sem_release(*sem);
}
u32_t sys_arch_sem_wait(sys_sem_t *sem, u32_t timeout)
{
rt_err_t ret;
s32_t t;
u32_t tick;
RT_DEBUG_NOT_IN_INTERRUPT;
/* get the begin tick */
tick = rt_tick_get();
if (timeout == 0)
t = RT_WAITING_FOREVER;
else
{
/* convert msecond to os tick */
if (timeout < (1000/RT_TICK_PER_SECOND))
t = 1;
else
t = timeout / (1000/RT_TICK_PER_SECOND);
}
ret = rt_sem_take(*sem, t);
if (ret == -RT_ETIMEOUT)
return SYS_ARCH_TIMEOUT;
else
{
if (ret == RT_EOK)
ret = 1;
}
/* get elapse msecond */
tick = rt_tick_get() - tick;
/* convert tick to msecond */
tick = tick * (1000 / RT_TICK_PER_SECOND);
if (tick == 0)
tick = 1;
return tick;
}
#ifndef sys_sem_valid
/** Check if a semaphore is valid/allocated:
* return 1 for valid, 0 for invalid
*/
int sys_sem_valid(sys_sem_t *sem)
{
return (int)(*sem);
}
#endif
#ifndef sys_sem_set_invalid
/** Set a semaphore invalid so that sys_sem_valid returns 0
*/
void sys_sem_set_invalid(sys_sem_t *sem)
{
*sem = RT_NULL;
}
#endif
/* ====================== Mutex ====================== */
/** Create a new mutex
* @param mutex pointer to the mutex to create
* @return a new mutex
*/
err_t sys_mutex_new(sys_mutex_t *mutex)
{
static unsigned short counter = 0;
char tname[RT_NAME_MAX];
sys_mutex_t tmpmutex;
RT_DEBUG_NOT_IN_INTERRUPT;
rt_snprintf(tname, RT_NAME_MAX, "%s%d", SYS_LWIP_MUTEX_NAME, counter);
counter ++;
tmpmutex = rt_mutex_create(tname, RT_IPC_FLAG_FIFO);
if (tmpmutex == RT_NULL)
return ERR_MEM;
else
{
*mutex = tmpmutex;
return ERR_OK;
}
}
/** Lock a mutex
* @param mutex the mutex to lock
*/
void sys_mutex_lock(sys_mutex_t *mutex)
{
RT_DEBUG_NOT_IN_INTERRUPT;
rt_mutex_take(*mutex, RT_WAITING_FOREVER);
return;
}
/** Unlock a mutex
* @param mutex the mutex to unlock
*/
void sys_mutex_unlock(sys_mutex_t *mutex)
{
rt_mutex_release(*mutex);
}
/** Delete a semaphore
* @param mutex the mutex to delete
*/
void sys_mutex_free(sys_mutex_t *mutex)
{
RT_DEBUG_NOT_IN_INTERRUPT;
rt_mutex_delete(*mutex);
}
#ifndef sys_mutex_valid
/** Check if a mutex is valid/allocated:
* return 1 for valid, 0 for invalid
*/
int sys_mutex_valid(sys_mutex_t *mutex)
{
return (int)(*mutex);
}
#endif
#ifndef sys_mutex_set_invalid
/** Set a mutex invalid so that sys_mutex_valid returns 0
*/
void sys_mutex_set_invalid(sys_mutex_t *mutex)
{
*mutex = RT_NULL;
}
#endif
/* ====================== Mailbox ====================== */
err_t sys_mbox_new(sys_mbox_t *mbox, int size)
{
static unsigned short counter = 0;
char tname[RT_NAME_MAX];
sys_mbox_t tmpmbox;
RT_DEBUG_NOT_IN_INTERRUPT;
rt_snprintf(tname, RT_NAME_MAX, "%s%d", SYS_LWIP_MBOX_NAME, counter);
counter ++;
tmpmbox = rt_mb_create(tname, size, RT_IPC_FLAG_FIFO);
if (tmpmbox != RT_NULL)
{
*mbox = tmpmbox;
return ERR_OK;
}
return ERR_MEM;
}
void sys_mbox_free(sys_mbox_t *mbox)
{
RT_DEBUG_NOT_IN_INTERRUPT;
rt_mb_delete(*mbox);
return;
}
/** Post a message to an mbox - may not fail
* -> blocks if full, only used from tasks not from ISR
* @param mbox mbox to posts the message
* @param msg message to post (ATTENTION: can be NULL)
*/
void sys_mbox_post(sys_mbox_t *mbox, void *msg)
{
RT_DEBUG_NOT_IN_INTERRUPT;
rt_mb_send_wait(*mbox, (rt_uint32_t)msg, RT_WAITING_FOREVER);
return;
}
err_t sys_mbox_trypost(sys_mbox_t *mbox, void *msg)
{
if (rt_mb_send(*mbox, (rt_uint32_t)msg) == RT_EOK)
return ERR_OK;
return ERR_MEM;
}
/** Wait for a new message to arrive in the mbox
* @param mbox mbox to get a message from
* @param msg pointer where the message is stored
* @param timeout maximum time (in milliseconds) to wait for a message
* @return time (in milliseconds) waited for a message, may be 0 if not waited
or SYS_ARCH_TIMEOUT on timeout
* The returned time has to be accurate to prevent timer jitter!
*/
u32_t sys_arch_mbox_fetch(sys_mbox_t *mbox, void **msg, u32_t timeout)
{
rt_err_t ret;
s32_t t;
u32_t tick;
RT_DEBUG_NOT_IN_INTERRUPT;
/* get the begin tick */
tick = rt_tick_get();
if(timeout == 0)
t = RT_WAITING_FOREVER;
else
{
/* convirt msecond to os tick */
if (timeout < (1000/RT_TICK_PER_SECOND))
t = 1;
else
t = timeout / (1000/RT_TICK_PER_SECOND);
}
ret = rt_mb_recv(*mbox, (rt_uint32_t *)msg, t);
if(ret == -RT_ETIMEOUT)
return SYS_ARCH_TIMEOUT;
else
{
LWIP_ASSERT("rt_mb_recv returned with error!", ret == RT_EOK);
}
/* get elapse msecond */
tick = rt_tick_get() - tick;
/* convert tick to msecond */
tick = tick * (1000 / RT_TICK_PER_SECOND);
if (tick == 0)
tick = 1;
return tick;
}
/** Wait for a new message to arrive in the mbox
* @param mbox mbox to get a message from
* @param msg pointer where the message is stored
* @param timeout maximum time (in milliseconds) to wait for a message
* @return 0 (milliseconds) if a message has been received
* or SYS_MBOX_EMPTY if the mailbox is empty
*/
u32_t sys_arch_mbox_tryfetch(sys_mbox_t *mbox, void **msg)
{
int ret;
ret = rt_mb_recv(*mbox, (rt_uint32_t *)msg, 0);
if(ret == -RT_ETIMEOUT)
return SYS_ARCH_TIMEOUT;
else
{
if (ret == RT_EOK)
ret = 1;
}
return ret;
}
#ifndef sys_mbox_valid
/** Check if an mbox is valid/allocated:
* return 1 for valid, 0 for invalid
*/
int sys_mbox_valid(sys_mbox_t *mbox)
{
return (int)(*mbox);
}
#endif
#ifndef sys_mbox_set_invalid
/** Set an mbox invalid so that sys_mbox_valid returns 0
*/
void sys_mbox_set_invalid(sys_mbox_t *mbox)
{
*mbox = RT_NULL;
}
#endif
/* ====================== System ====================== */
sys_thread_t sys_thread_new(const char *name,
lwip_thread_fn thread,
void *arg,
int stacksize,
int prio)
{
rt_thread_t t;
RT_DEBUG_NOT_IN_INTERRUPT;
/* create thread */
t = rt_thread_create(name, thread, arg, stacksize, prio, 20);
RT_ASSERT(t != RT_NULL);
/* startup thread */
rt_thread_startup(t);
return t;
}
sys_prot_t sys_arch_protect(void)
{
rt_base_t level;
/* disable interrupt */
level = rt_hw_interrupt_disable();
return level;
}
void sys_arch_unprotect(sys_prot_t pval)
{
/* enable interrupt */
rt_hw_interrupt_enable(pval);
return;
}
void sys_arch_assert(const char *file, int line)
{
rt_kprintf("\nAssertion: %d in %s, thread %s\n",
line, file, rt_thread_self()->name);
RT_ASSERT(0);
}
u32_t sys_jiffies(void)
{
return rt_tick_get();
}
#ifdef RT_LWIP_PPP
u32_t sio_read(sio_fd_t fd, u8_t *buf, u32_t size)
{
u32_t len;
RT_ASSERT(fd != RT_NULL);
len = rt_device_read((rt_device_t)fd, 0, buf, size);
if (len <= 0)
return 0;
return len;
}
u32_t sio_write(sio_fd_t fd, u8_t *buf, u32_t size)
{
RT_ASSERT(fd != RT_NULL);
return rt_device_write((rt_device_t)fd, 0, buf, size);
}
void sio_read_abort(sio_fd_t fd)
{
rt_kprintf("read_abort\n");
}
void ppp_trace(int level, const char *format, ...)
{
va_list args;
rt_size_t length;
static char rt_log_buf[RT_CONSOLEBUF_SIZE];
va_start(args, format);
length = rt_vsprintf(rt_log_buf, format, args);
rt_device_write((rt_device_t)rt_console_get_device(), 0, rt_log_buf, length);
va_end(args);
}
#endif
/*
* export bsd socket symbol for RT-Thread Application Module
*/
#if LWIP_SOCKET
#include <lwip/sockets.h>
RTM_EXPORT(lwip_accept);
RTM_EXPORT(lwip_bind);
RTM_EXPORT(lwip_shutdown);
RTM_EXPORT(lwip_getpeername);
RTM_EXPORT(lwip_getsockname);
RTM_EXPORT(lwip_getsockopt);
RTM_EXPORT(lwip_setsockopt);
RTM_EXPORT(lwip_close);
RTM_EXPORT(lwip_connect);
RTM_EXPORT(lwip_listen);
RTM_EXPORT(lwip_recv);
RTM_EXPORT(lwip_read);
RTM_EXPORT(lwip_recvfrom);
RTM_EXPORT(lwip_send);
RTM_EXPORT(lwip_sendto);
RTM_EXPORT(lwip_socket);
RTM_EXPORT(lwip_write);
RTM_EXPORT(lwip_select);
RTM_EXPORT(lwip_ioctl);
RTM_EXPORT(lwip_fcntl);
#if LWIP_DNS
#include <lwip/netdb.h>
RTM_EXPORT(lwip_gethostbyname);
RTM_EXPORT(lwip_gethostbyname_r);
RTM_EXPORT(lwip_freeaddrinfo);
RTM_EXPORT(lwip_getaddrinfo);
#endif
#endif
#if LWIP_DHCP
#include <lwip/dhcp.h>
RTM_EXPORT(dhcp_start);
RTM_EXPORT(dhcp_renew);
RTM_EXPORT(dhcp_stop);
#endif
#if LWIP_NETIF_API
#include <lwip/netifapi.h>
RTM_EXPORT(netifapi_netif_set_addr);
#endif
#ifndef __NETIF_ETHERNETIF_H__
#define __NETIF_ETHERNETIF_H__
#include "lwip/netif.h"
#include <rtthread.h>
#define NIOCTL_GADDR 0x01
#define ETHERNET_MTU 1500
struct eth_device
{
/* inherit from rt_device */
struct rt_device parent;
/* network interface for lwip */
struct netif *netif;
struct rt_semaphore tx_ack;
rt_uint8_t flags;
rt_uint8_t link_changed;
rt_uint16_t link_status;
/* eth device interface */
struct pbuf* (*eth_rx)(rt_device_t dev);
rt_err_t (*eth_tx)(rt_device_t dev, struct pbuf* p);
};
rt_err_t eth_device_ready(struct eth_device* dev);
rt_err_t eth_device_init(struct eth_device * dev, char *name);
rt_err_t eth_device_init_with_flag(struct eth_device *dev, char *name, rt_uint8_t flag);
rt_err_t eth_device_linkchange(struct eth_device* dev, rt_bool_t up);
void eth_system_device_init(void);
#endif /* __NETIF_ETHERNETIF_H__ */
#ifndef __LWIPOPTS_H__
#define __LWIPOPTS_H__
#include <rtconfig.h>
#define ERRNO 1
#define NO_SYS 0
#define LWIP_SOCKET 1
#define LWIP_NETCONN 1
#ifdef RT_LWIP_IGMP
#define LWIP_IGMP 1
#else
#define LWIP_IGMP 0
#endif
#ifdef RT_LWIP_ICMP
#define LWIP_ICMP 1
#else
#define LWIP_ICMP 0
#endif
#ifdef RT_LWIP_SNMP
#define LWIP_SNMP 1
#else
#define LWIP_SNMP 0
#endif
#ifdef RT_LWIP_DNS
#define LWIP_DNS 1
#else
#define LWIP_DNS 0
#endif
#define LWIP_HAVE_LOOPIF 0
#define LWIP_PLATFORM_BYTESWAP 0
#define BYTE_ORDER LITTLE_ENDIAN
/* Enable SO_RCVTIMEO processing. */
#define LWIP_SO_RCVTIMEO 1
/* #define RT_LWIP_DEBUG */
#ifdef RT_LWIP_DEBUG
#define LWIP_DEBUG
#endif
/* ---------- Debug options ---------- */
#ifdef LWIP_DEBUG
#define SYS_DEBUG LWIP_DBG_OFF
#define ETHARP_DEBUG LWIP_DBG_OFF
#define PPP_DEBUG LWIP_DBG_OFF
#define MEM_DEBUG LWIP_DBG_OFF
#define MEMP_DEBUG LWIP_DBG_OFF
#define PBUF_DEBUG LWIP_DBG_OFF
#define API_LIB_DEBUG LWIP_DBG_OFF
#define API_MSG_DEBUG LWIP_DBG_OFF
#define TCPIP_DEBUG LWIP_DBG_OFF
#define NETIF_DEBUG LWIP_DBG_OFF
#define SOCKETS_DEBUG LWIP_DBG_OFF
#define DNS_DEBUG LWIP_DBG_OFF
#define AUTOIP_DEBUG LWIP_DBG_OFF
#define DHCP_DEBUG LWIP_DBG_OFF
#define IP_DEBUG LWIP_DBG_OFF
#define IP_REASS_DEBUG LWIP_DBG_OFF
#define ICMP_DEBUG LWIP_DBG_OFF
#define IGMP_DEBUG LWIP_DBG_OFF
#define UDP_DEBUG LWIP_DBG_OFF
#define TCP_DEBUG LWIP_DBG_OFF
#define TCP_INPUT_DEBUG LWIP_DBG_OFF
#define TCP_OUTPUT_DEBUG LWIP_DBG_OFF
#define TCP_RTO_DEBUG LWIP_DBG_OFF
#define TCP_CWND_DEBUG LWIP_DBG_OFF
#define TCP_WND_DEBUG LWIP_DBG_OFF
#define TCP_FR_DEBUG LWIP_DBG_OFF
#define TCP_QLEN_DEBUG LWIP_DBG_OFF
#define TCP_RST_DEBUG LWIP_DBG_OFF
#endif
#define LWIP_DBG_TYPES_ON (LWIP_DBG_ON|LWIP_DBG_TRACE|LWIP_DBG_STATE|LWIP_DBG_FRESH|LWIP_DBG_HALT)
/* ---------- Memory options ---------- */
#ifdef RT_LWIP_ALIGN_SIZE
#define MEM_ALIGNMENT RT_LWIP_ALIGN_SIZE
#else
#define MEM_ALIGNMENT 4
#endif
#define MEM_LIBC_MALLOC 1
#define mem_malloc rt_malloc
#define mem_free rt_free
#define mem_calloc rt_calloc
#ifdef RT_LWIP_USING_RT_MEM
#define MEMP_MEM_MALLOC 1
#else
#define MEMP_MEM_MALLOC 0
#endif
/* MEMP_NUM_PBUF: the number of memp struct pbufs. If the application
sends a lot of data out of ROM (or other static memory), this
should be set high. */
#define MEMP_NUM_PBUF 16
/* the number of UDP protocol control blocks. One per active RAW "connection". */
#ifdef RT_LWIP_RAW_PCB_NUM
#define MEMP_NUM_RAW_PCB RT_LWIP_RAW_PCB_NUM
#endif
/* the number of UDP protocol control blocks. One per active UDP "connection". */
#ifdef RT_LWIP_UDP_PCB_NUM
#define MEMP_NUM_UDP_PCB RT_LWIP_UDP_PCB_NUM
#endif
/* the number of simulatenously active TCP connections. */
#ifdef RT_LWIP_TCP_PCB_NUM
#define MEMP_NUM_TCP_PCB RT_LWIP_TCP_PCB_NUM
#endif
/* the number of simultaneously queued TCP */
#ifdef RT_LWIP_TCP_SEG_NUM
#define MEMP_NUM_TCP_SEG TCP_SND_QUEUELEN
#endif
/* The following four are used only with the sequential API and can be
set to 0 if the application only will use the raw API. */
/* MEMP_NUM_NETBUF: the number of struct netbufs. */
#define MEMP_NUM_NETBUF 2
/* MEMP_NUM_NETCONN: the number of struct netconns. */
#define MEMP_NUM_NETCONN 4
/* MEMP_NUM_TCPIP_MSG_*: the number of struct tcpip_msg, which is used
for sequential API communication and incoming packets. Used in
src/api/tcpip.c. */
#define MEMP_NUM_TCPIP_MSG_API 16
#define MEMP_NUM_TCPIP_MSG_INPKT 16
/* ---------- Pbuf options ---------- */
/* PBUF_POOL_SIZE: the number of buffers in the pbuf pool. */
#ifdef RT_LWIP_PBUF_NUM
#define PBUF_POOL_SIZE RT_LWIP_PBUF_NUM
#endif
/* PBUF_POOL_BUFSIZE: the size of each pbuf in the pbuf pool. */
#ifdef RT_LWIP_PBUF_POOL_BUFSIZE
#define PBUF_POOL_BUFSIZE RT_LWIP_PBUF_POOL_BUFSIZE
#endif
/* PBUF_LINK_HLEN: the number of bytes that should be allocated for a
link level header. */
#define PBUF_LINK_HLEN 16
#ifdef RT_LWIP_ETH_PAD_SIZE
#define ETH_PAD_SIZE RT_LWIP_ETH_PAD_SIZE
#endif
/** SYS_LIGHTWEIGHT_PROT
* define SYS_LIGHTWEIGHT_PROT in lwipopts.h if you want inter-task protection
* for certain critical regions during buffer allocation, deallocation and memory
* allocation and deallocation.
*/
#define SYS_LIGHTWEIGHT_PROT (NO_SYS==0)
/* ---------- TCP options ---------- */
#ifdef RT_LWIP_TCP
#define LWIP_TCP 1
#else
#define LWIP_TCP 0
#endif
#define TCP_TTL 255
/* Controls if TCP should queue segments that arrive out of
order. Define to 0 if your device is low on memory. */
#define TCP_QUEUE_OOSEQ 1
/* TCP Maximum segment size. */
#define TCP_MSS 1460
/* TCP sender buffer space (bytes). */
#define TCP_SND_BUF (TCP_MSS * 2)
/* TCP sender buffer space (pbufs). This must be at least = 2 *
TCP_SND_BUF/TCP_MSS for things to work. */
#define TCP_SND_QUEUELEN (4 * TCP_SND_BUF/TCP_MSS)
/* TCP writable space (bytes). This must be less than or equal
to TCP_SND_BUF. It is the amount of space which must be
available in the tcp snd_buf for select to return writable */
#define TCP_SNDLOWAT (TCP_SND_BUF/2)
#define TCP_SNDQUEUELOWAT TCP_SND_QUEUELEN/2
/* TCP receive window. */
#ifdef RT_LWIP_TCP_WND
#define TCP_WND RT_LWIP_TCP_WND
#else
#define TCP_WND (TCP_MSS * 2)
#endif
/* Maximum number of retransmissions of data segments. */
#define TCP_MAXRTX 12
/* Maximum number of retransmissions of SYN segments. */
#define TCP_SYNMAXRTX 4
/* tcpip thread options */
#ifdef RT_LWIP_TCPTHREAD_PRIORITY
#define TCPIP_MBOX_SIZE RT_LWIP_TCPTHREAD_MBOX_SIZE
#define TCPIP_THREAD_PRIO RT_LWIP_TCPTHREAD_PRIORITY
#define TCPIP_THREAD_STACKSIZE RT_LWIP_TCPTHREAD_STACKSIZE
#else
#define TCPIP_MBOX_SIZE 8
#define TCPIP_THREAD_PRIO 128
#define TCPIP_THREAD_STACKSIZE 4096
#endif
#define TCPIP_THREAD_NAME "tcpip"
#define DEFAULT_TCP_RECVMBOX_SIZE 10
/* ---------- ARP options ---------- */
#define LWIP_ARP 1
#define ARP_TABLE_SIZE 10
#define ARP_QUEUEING 1
/* ---------- IP options ---------- */
/* Define IP_FORWARD to 1 if you wish to have the ability to forward
IP packets across network interfaces. If you are going to run lwIP
on a device with only one network interface, define this to 0. */
#define IP_FORWARD 0
/* IP reassembly and segmentation.These are orthogonal even
* if they both deal with IP fragments */
#define IP_REASSEMBLY 0
#define IP_REASS_MAX_PBUFS 10
#define MEMP_NUM_REASSDATA 10
#define IP_FRAG 0
/* ---------- ICMP options ---------- */
#define ICMP_TTL 255
/* ---------- DHCP options ---------- */
/* Define LWIP_DHCP to 1 if you want DHCP configuration of
interfaces. */
#ifdef RT_LWIP_DHCP
#define LWIP_DHCP 1
#else
#define LWIP_DHCP 0
#endif
/* 1 if you want to do an ARP check on the offered address
(recommended). */
#define DHCP_DOES_ARP_CHECK (LWIP_DHCP)
/* ---------- AUTOIP options ------- */
#define LWIP_AUTOIP 0
#define LWIP_DHCP_AUTOIP_COOP (LWIP_DHCP && LWIP_AUTOIP)
/* ---------- UDP options ---------- */
#ifdef RT_LWIP_UDP
#define LWIP_UDP 1
#else
#define LWIP_UDP 0
#endif
#define LWIP_UDPLITE 0
#define UDP_TTL 255
#define DEFAULT_UDP_RECVMBOX_SIZE 1
/* ---------- RAW options ---------- */
#define DEFAULT_RAW_RECVMBOX_SIZE 1
#define DEFAULT_ACCEPTMBOX_SIZE 10
/* ---------- Statistics options ---------- */
#ifdef RT_LWIP_STATS
#define LWIP_STATS 1
#define LWIP_STATS_DISPLAY 1
#else
#define LWIP_STATS 0
#endif
#if LWIP_STATS
#define LINK_STATS 1
#define IP_STATS 1
#define ICMP_STATS 1
#define IGMP_STATS 1
#define IPFRAG_STATS 1
#define UDP_STATS 1
#define TCP_STATS 1
#define MEM_STATS 1
#define MEMP_STATS 1
#define PBUF_STATS 1
#define SYS_STATS 1
#endif /* LWIP_STATS */
/* ---------- PPP options ---------- */
#ifdef RT_LWIP_PPP
#define PPP_SUPPORT 1 /* Set > 0 for PPP */
#else
#define PPP_SUPPORT 0 /* Set > 0 for PPP */
#endif
#if PPP_SUPPORT
#define NUM_PPP 1 /* Max PPP sessions. */
/* Select modules to enable. Ideally these would be set in the makefile but
* we're limited by the command line length so you need to modify the settings
* in this file.
*/
#define PPPOE_SUPPORT 0
#define PPPOS_SUPPORT 1
#define PAP_SUPPORT 1 /* Set > 0 for PAP. */
#define CHAP_SUPPORT 1 /* Set > 0 for CHAP. */
#define MSCHAP_SUPPORT 0 /* Set > 0 for MSCHAP (NOT FUNCTIONAL!) */
#define CBCP_SUPPORT 0 /* Set > 0 for CBCP (NOT FUNCTIONAL!) */
#define CCP_SUPPORT 0 /* Set > 0 for CCP (NOT FUNCTIONAL!) */
#define VJ_SUPPORT 1 /* Set > 0 for VJ header compression. */
#define MD5_SUPPORT 1 /* Set > 0 for MD5 (see also CHAP) */
#endif /* PPP_SUPPORT */
/* no read/write/close for socket */
#define LWIP_POSIX_SOCKETS_IO_NAMES 0
#define LWIP_NETIF_API 1
/* MEMP_NUM_SYS_TIMEOUT: the number of simulateously active timeouts. */
#define MEMP_NUM_SYS_TIMEOUT (LWIP_TCP + IP_REASSEMBLY + LWIP_ARP + (2*LWIP_DHCP) + LWIP_AUTOIP + LWIP_IGMP + LWIP_DNS + PPP_SUPPORT)
#ifdef LWIP_IGMP
#include <stdlib.h>
#define LWIP_RAND rand
#endif
#endif /* __LWIPOPTS_H__ */
......@@ -82,6 +82,6 @@ if GetDepend(['RT_LWIP_PPP']):
if GetDepend(['RT_USING_NETUTILS']):
src += Glob('./apps/*.c')
group = DefineGroup('LwIP', src, depend = ['RT_USING_LWIP'], CPPPATH = path)
group = DefineGroup('LwIP', src, depend = ['RT_USING_LWIP', 'RT_USING_LWIP140'], CPPPATH = path)
Return('group')
......@@ -104,9 +104,9 @@ struct pthread_rwlock
pthread_cond_t rw_condreaders; /* for reader threads waiting */
pthread_cond_t rw_condwriters; /* for writer threads waiting */
int rw_nwaitreaders; /* the number waiting */
int rw_nwaitwriters; /* the number waiting */
int rw_refcount;
int rw_nwaitreaders; /* the number of reader threads waiting */
int rw_nwaitwriters; /* the number of writer threads waiting */
int rw_refcount; /* 0: unlocked, -1: locked by writer, > 0 locked by n readers */
};
typedef struct pthread_rwlock pthread_rwlock_t;
......
此差异已折叠。
此差异已折叠。
......@@ -425,7 +425,6 @@ void rt_module_unload_sethook(void (*hook)(rt_module_t module));
/*
* interrupt service
*/
typedef void (*rt_isr_handler_t)(int vector);
/*
* rt_interrupt_enter and rt_interrupt_leave only can be called by BSP
......
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
......@@ -126,17 +126,20 @@ void rt_hw_trap_resv(struct rt_hw_register *regs)
}
extern rt_isr_handler_t isr_table[];
void rt_hw_trap_irq()
void rt_hw_trap_irq(void)
{
rt_isr_handler_t isr_func;
isr_func = (rt_isr_handler_t) VICVectAddr;
int irqno;
struct rt_irq_desc* irq;
extern struct rt_irq_desc irq_desc[];
/* fixme, how to get interrupt number */
isr_func(0);
irq = (struct rt_irq_desc*) VICVectAddr;
irqno = ((rt_uint32_t) irq - (rt_uint32_t) &irq_desc[0])/sizeof(struct rt_irq_desc);
/* invoke isr */
irq->handler(irqno, irq->param);
}
void rt_hw_trap_fiq()
void rt_hw_trap_fiq(void)
{
rt_kprintf("fast interrupt request\n");
}
......
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
此差异已折叠。
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册