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

This commit is contained in:
Rogerz Zhang 2013-04-01 19:06:22 +08:00
commit 489b3822f0
96 changed files with 4077 additions and 1367 deletions

1
.gitignore vendored
View File

@ -10,3 +10,4 @@
*.idb
*.ilk
build
*~

View File

@ -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);

View File

@ -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);
}

View File

@ -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",

View File

@ -22,6 +22,8 @@
#define RT_USING_OVERFLOW_CHECK
#define RT_USING_INTERRUPT_INFO
/* Using Hook */
#define RT_USING_HOOK

View File

@ -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

View File

@ -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;

View File

@ -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);
}

View File

@ -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

View File

@ -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;

View File

@ -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

View File

@ -1,133 +0,0 @@
/*
* 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) }
}

View File

@ -1,15 +0,0 @@
; *************************************************************
; *** 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)
}
}

View File

@ -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 :

View File

@ -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);
}

View File

@ -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
}

View File

@ -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

View File

@ -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);
}

View File

@ -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;

View File

@ -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" />

View File

@ -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();

View File

@ -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);
}

View File

@ -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" />

View File

@ -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",

View File

@ -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);

View File

@ -20,6 +20,7 @@
/* #define RT_THREAD_DEBUG */
#define RT_USING_OVERFLOW_CHECK
#define RT_USING_INTERRUPT_INFO
/* Using Hook */
#define RT_USING_HOOK

View File

@ -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

View File

@ -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

View File

@ -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);
}

View File

@ -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);

View File

@ -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);

View File

@ -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:

View File

@ -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;

View File

@ -1,11 +1,26 @@
/*
* 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)

View File

@ -1,11 +1,26 @@
/*
* 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

View File

@ -1,11 +1,26 @@
/*
* 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

View File

@ -1,11 +1,26 @@
/*
* 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

View File

@ -1,11 +1,26 @@
/*
* 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

View File

@ -1,11 +1,26 @@
/*
* 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

View File

@ -1,11 +1,26 @@
/*
* 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

View File

@ -1,11 +1,26 @@
/*
* 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

View File

@ -1,11 +1,26 @@
/*
* 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

View File

@ -1,11 +1,26 @@
/*
* 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

View File

@ -1,11 +1,26 @@
/*
* 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

View File

@ -1,11 +1,26 @@
/*
* 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

View File

@ -1,11 +1,26 @@
/*
* 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

View File

@ -1,11 +1,26 @@
/*
* 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

View File

@ -1,11 +1,26 @@
/*
* 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

View File

@ -1,11 +1,26 @@
/*
* 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

View File

@ -1,11 +1,26 @@
/*
* 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

View File

@ -1,11 +1,26 @@
/*
* 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

View File

@ -1,11 +1,26 @@
/*
* 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

255
components/finsh/msh.c Normal file
View File

@ -0,0 +1,255 @@
/*
* 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

39
components/finsh/msh.h Normal file
View File

@ -0,0 +1,39 @@
/*
* 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

208
components/finsh/msh_cmd.c Normal file
View File

@ -0,0 +1,208 @@
/*
* 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

View File

@ -1,15 +1,30 @@
/*
* 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));

View File

@ -1,11 +1,26 @@
/*
* 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

View File

@ -1,11 +1,26 @@
/*
* 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

View File

@ -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)

View File

@ -1,10 +1,15 @@
# 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')):

View File

@ -0,0 +1,87 @@
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')

View File

@ -0,0 +1,35 @@
/*
* 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

View File

@ -0,0 +1,107 @@
/*
* 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__ */

View File

@ -0,0 +1,35 @@
/*
* 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

View File

@ -0,0 +1,52 @@
/*
* 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__ */

View File

@ -0,0 +1,63 @@
/*
* 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__ */

View File

@ -0,0 +1,635 @@
/*
* 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

View File

@ -0,0 +1,35 @@
#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__ */

View File

@ -0,0 +1,333 @@
#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__ */

View File

@ -1,14 +1,27 @@
/**
* @file
* Ethernet Interface Skeleton
/*
* File : ethernetif.c
* This file is part of RT-Thread RTOS
* COPYRIGHT (C) 2006 - 2010, 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
* 2010-07-07 Bernard fix send mail to mailbox issue.
* 2011-07-30 mbbill port lwIP 1.4.0 to RT-Thread
* 2012-04-10 Bernard add more compatible with RT-Thread.
* 2012-11-12 Bernard The network interface can be initialized
* after lwIP initialization.
* 2013-02-28 aozima fixed list_tcps bug: ipaddr_ntoa isn't reentrant.
*/
/*
* Copyright (c) 2001-2004 Swedish Institute of Computer Science.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without modification,
* 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,
@ -17,301 +30,538 @@
* 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.
* 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
* 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>
*
*/
/*
* This file is a skeleton for developing Ethernet network interface
* drivers for lwIP. Add code to the low_level functions and do a
* search-and-replace for the word "ethernetif" to replace it with
* something that better describes your network interface.
*/
#include <rtthread.h>
#include "lwip/opt.h"
#if 0 /* don't build, this is only a skeleton, see previous comment */
#include "lwip/debug.h"
#include "lwip/def.h"
#include "lwip/mem.h"
#include "lwip/pbuf.h"
#include <lwip/stats.h>
#include <lwip/snmp.h>
#include "netif/etharp.h"
#include "netif/ppp_oe.h"
#include "lwip/sys.h"
#include "lwip/netif.h"
#include "lwip/stats.h"
#include "lwip/tcpip.h"
/* Define those to better describe your network interface. */
#define IFNAME0 'e'
#define IFNAME1 'n'
#include "netif/etharp.h"
#include "netif/ethernetif.h"
#define netifapi_netif_set_link_up(n) netifapi_netif_common(n, netif_set_link_up, NULL)
#define netifapi_netif_set_link_down(n) netifapi_netif_common(n, netif_set_link_down, NULL)
/**
* Helper struct to hold private data used to operate your ethernet interface.
* Keeping the ethernet address of the MAC in this struct is not necessary
* as it is already kept in the struct netif.
* But this is only an example, anyway...
* Tx message structure for Ethernet interface
*/
struct ethernetif {
struct eth_addr *ethaddr;
/* Add whatever per-interface state that is needed here. */
struct eth_tx_msg
{
struct netif *netif;
struct pbuf *buf;
};
/* Forward declarations. */
static void ethernetif_input(struct netif *netif);
static struct rt_mailbox eth_tx_thread_mb;
static struct rt_thread eth_tx_thread;
#ifndef RT_LWIP_ETHTHREAD_PRIORITY
static char eth_tx_thread_mb_pool[32 * 4];
static char eth_tx_thread_stack[512];
#else
static char eth_tx_thread_mb_pool[RT_LWIP_ETHTHREAD_MBOX_SIZE * 4];
static char eth_tx_thread_stack[RT_LWIP_ETHTHREAD_STACKSIZE];
#endif
/**
* In this function, the hardware should be initialized.
* Called from ethernetif_init().
*
* @param netif the already initialized lwip network interface structure
* for this ethernetif
*/
static void
low_level_init(struct netif *netif)
static struct rt_mailbox eth_rx_thread_mb;
static struct rt_thread eth_rx_thread;
#ifndef RT_LWIP_ETHTHREAD_PRIORITY
#define RT_ETHERNETIF_THREAD_PREORITY 0x90
static char eth_rx_thread_mb_pool[48 * 4];
static char eth_rx_thread_stack[1024];
#else
#define RT_ETHERNETIF_THREAD_PREORITY RT_LWIP_ETHTHREAD_PRIORITY
static char eth_rx_thread_mb_pool[RT_LWIP_ETHTHREAD_MBOX_SIZE * 4];
static char eth_rx_thread_stack[RT_LWIP_ETHTHREAD_STACKSIZE];
#endif
static err_t ethernetif_linkoutput(struct netif *netif, struct pbuf *p)
{
struct ethernetif *ethernetif = netif->state;
/* set MAC hardware address length */
netif->hwaddr_len = ETHARP_HWADDR_LEN;
struct eth_tx_msg msg;
struct eth_device* enetif;
/* set MAC hardware address */
netif->hwaddr[0] = ;
...
netif->hwaddr[5] = ;
enetif = (struct eth_device*)netif->state;
/* maximum transfer unit */
netif->mtu = 1500;
/* device capabilities */
/* don't set NETIF_FLAG_ETHARP if this device is not an ethernet one */
netif->flags = NETIF_FLAG_BROADCAST | NETIF_FLAG_ETHARP | NETIF_FLAG_LINK_UP;
/* Do whatever else is needed to initialize interface. */
}
/**
* This function should do the actual transmission of the packet. The packet is
* contained in the pbuf that is passed to the function. This pbuf
* might be chained.
*
* @param netif the lwip network interface structure for this ethernetif
* @param p the MAC packet to send (e.g. IP packet including MAC addresses and type)
* @return ERR_OK if the packet could be sent
* an err_t value if the packet couldn't be sent
*
* @note Returning ERR_MEM here if a DMA queue of your MAC is full can lead to
* strange results. You might consider waiting for space in the DMA queue
* to become availale since the stack doesn't retry to send a packet
* dropped because of memory failure (except for the TCP timers).
*/
static err_t
low_level_output(struct netif *netif, struct pbuf *p)
{
struct ethernetif *ethernetif = netif->state;
struct pbuf *q;
initiate transfer();
#if ETH_PAD_SIZE
pbuf_header(p, -ETH_PAD_SIZE); /* drop the padding word */
#endif
for(q = p; q != NULL; q = q->next) {
/* Send the data from the pbuf to the interface, one pbuf at a
time. The size of the data in each pbuf is kept in the ->len
variable. */
send data from(q->payload, q->len);
}
signal that packet should be sent();
#if ETH_PAD_SIZE
pbuf_header(p, ETH_PAD_SIZE); /* reclaim the padding word */
#endif
LINK_STATS_INC(link.xmit);
return ERR_OK;
}
/**
* Should allocate a pbuf and transfer the bytes of the incoming
* packet from the interface into the pbuf.
*
* @param netif the lwip network interface structure for this ethernetif
* @return a pbuf filled with the received packet (including MAC header)
* NULL on memory error
*/
static struct pbuf *
low_level_input(struct netif *netif)
{
struct ethernetif *ethernetif = netif->state;
struct pbuf *p, *q;
u16_t len;
/* Obtain the size of the packet and put it into the "len"
variable. */
len = ;
#if ETH_PAD_SIZE
len += ETH_PAD_SIZE; /* allow room for Ethernet padding */
#endif
/* We allocate a pbuf chain of pbufs from the pool. */
p = pbuf_alloc(PBUF_RAW, len, PBUF_POOL);
if (p != NULL) {
#if ETH_PAD_SIZE
pbuf_header(p, -ETH_PAD_SIZE); /* drop the padding word */
#endif
/* We iterate over the pbuf chain until we have read the entire
* packet into the pbuf. */
for(q = p; q != NULL; q = q->next) {
/* Read enough bytes to fill this pbuf in the chain. The
* available data in the pbuf is given by the q->len
* variable.
* This does not necessarily have to be a memcpy, you can also preallocate
* pbufs for a DMA-enabled MAC and after receiving truncate it to the
* actually received size. In this case, ensure the tot_len member of the
* pbuf is the sum of the chained pbuf len members.
*/
read data into(q->payload, q->len);
/* send a message to eth tx thread */
msg.netif = netif;
msg.buf = p;
if (rt_mb_send(&eth_tx_thread_mb, (rt_uint32_t) &msg) == RT_EOK)
{
/* waiting for ack */
rt_sem_take(&(enetif->tx_ack), RT_WAITING_FOREVER);
}
acknowledge that packet has been read();
#if ETH_PAD_SIZE
pbuf_header(p, ETH_PAD_SIZE); /* reclaim the padding word */
return ERR_OK;
}
static err_t eth_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;
/* set default netif */
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
LINK_STATS_INC(link.recv);
} else {
drop packet();
LINK_STATS_INC(link.memerr);
LINK_STATS_INC(link.drop);
}
return ERR_OK;
}
return p;
return ERR_IF;
}
/**
* This function should be called when a packet is ready to be read
* from the interface. It uses the function low_level_input() that
* should handle the actual reception of bytes from the network
* interface. Then the type of the received packet is determined and
* the appropriate input function is called.
*
* @param netif the lwip network interface structure for this ethernetif
*/
static void
ethernetif_input(struct netif *netif)
/* Keep old drivers compatible in RT-Thread */
rt_err_t eth_device_init_with_flag(struct eth_device *dev, char *name, rt_uint8_t flags)
{
struct ethernetif *ethernetif;
struct eth_hdr *ethhdr;
struct pbuf *p;
struct netif* netif;
ethernetif = netif->state;
netif = (struct netif*) rt_malloc (sizeof(struct netif));
if (netif == RT_NULL)
{
rt_kprintf("malloc netif failed\n");
return -RT_ERROR;
}
rt_memset(netif, 0, sizeof(struct netif));
/* move received packet into a new pbuf */
p = low_level_input(netif);
/* no packet could be read, silently ignore this */
if (p == NULL) return;
/* points to packet payload, which starts with an Ethernet header */
ethhdr = p->payload;
/* set netif */
dev->netif = netif;
/* device flags, which will be set to netif flags when initializing */
dev->flags = flags;
/* link changed status of device */
dev->link_changed = 0x00;
dev->parent.type = RT_Device_Class_NetIf;
/* register to RT-Thread device manager */
rt_device_register(&(dev->parent), name, RT_DEVICE_FLAG_RDWR);
rt_sem_init(&(dev->tx_ack), name, 0, RT_IPC_FLAG_FIFO);
switch (htons(ethhdr->type)) {
/* IP or ARP packet? */
case ETHTYPE_IP:
case ETHTYPE_ARP:
#if PPPOE_SUPPORT
/* PPPoE packet? */
case ETHTYPE_PPPOEDISC:
case ETHTYPE_PPPOE:
#endif /* PPPOE_SUPPORT */
/* full packet send to tcpip_thread to process */
if (netif->input(p, netif)!=ERR_OK)
{ LWIP_DEBUGF(NETIF_DEBUG, ("ethernetif_input: IP input error\n"));
pbuf_free(p);
p = NULL;
}
break;
/* set name */
netif->name[0] = name[0];
netif->name[1] = name[1];
default:
pbuf_free(p);
p = NULL;
break;
}
/* set hw address to 6 */
netif->hwaddr_len = 6;
/* maximum transfer unit */
netif->mtu = ETHERNET_MTU;
/* get hardware MAC address */
rt_device_control(&(dev->parent), NIOCTL_GADDR, netif->hwaddr);
/* set output */
netif->output = etharp_output;
netif->linkoutput = ethernetif_linkoutput;
/* if tcp thread has been started up, we add this netif to the system */
if (rt_thread_find("tcpip") != RT_NULL)
{
struct ip_addr ipaddr, netmask, gw;
#if !LWIP_DHCP
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);
#else
IP4_ADDR(&ipaddr, 0, 0, 0, 0);
IP4_ADDR(&gw, 0, 0, 0, 0);
IP4_ADDR(&netmask, 0, 0, 0, 0);
#endif
netifapi_netif_add(netif, &ipaddr, &netmask, &gw, dev, eth_netif_device_init, tcpip_input);
}
return RT_EOK;
}
/**
* Should be called at the beginning of the program to set up the
* network interface. It calls the function low_level_init() to do the
* actual setup of the hardware.
*
* This function should be passed as a parameter to netif_add().
*
* @param netif the lwip network interface structure for this ethernetif
* @return ERR_OK if the loopif is initialized
* ERR_MEM if private data couldn't be allocated
* any other err_t on error
*/
err_t
ethernetif_init(struct netif *netif)
rt_err_t eth_device_init(struct eth_device * dev, char *name)
{
struct ethernetif *ethernetif;
rt_uint8_t flags = NETIF_FLAG_BROADCAST | NETIF_FLAG_ETHARP;
LWIP_ASSERT("netif != NULL", (netif != NULL));
ethernetif = mem_malloc(sizeof(struct ethernetif));
if (ethernetif == NULL) {
LWIP_DEBUGF(NETIF_DEBUG, ("ethernetif_init: out of memory\n"));
return ERR_MEM;
}
#if LWIP_DHCP
/* DHCP support */
flags |= NETIF_FLAG_DHCP;
#endif
#if LWIP_NETIF_HOSTNAME
/* Initialize interface hostname */
netif->hostname = "lwip";
#endif /* LWIP_NETIF_HOSTNAME */
#if LWIP_IGMP
/* IGMP support */
flags |= NETIF_FLAG_IGMP;
#endif
/*
* Initialize the snmp variables and counters inside the struct netif.
* The last argument should be replaced with your link speed, in units
* of bits per second.
*/
NETIF_INIT_SNMP(netif, snmp_ifType_ethernet_csmacd, LINK_SPEED_OF_YOUR_NETIF_IN_BPS);
netif->state = ethernetif;
netif->name[0] = IFNAME0;
netif->name[1] = IFNAME1;
/* We directly use etharp_output() here to save a function call.
* You can instead declare your own function an call etharp_output()
* from it if you have to do some checks before sending (e.g. if link
* is available...) */
netif->output = etharp_output;
netif->linkoutput = low_level_output;
ethernetif->ethaddr = (struct eth_addr *)&(netif->hwaddr[0]);
/* initialize the hardware */
low_level_init(netif);
return ERR_OK;
return eth_device_init_with_flag(dev, name, flags);
}
#endif /* 0 */
rt_err_t eth_device_ready(struct eth_device* dev)
{
if (dev->netif)
/* post message to Ethernet thread */
return rt_mb_send(&eth_rx_thread_mb, (rt_uint32_t)dev);
else
return ERR_OK; /* netif is not initialized yet, just return. */
}
rt_err_t eth_device_linkchange(struct eth_device* dev, rt_bool_t up)
{
rt_uint32_t level;
RT_ASSERT(dev != RT_NULL);
level = rt_hw_interrupt_disable();
dev->link_changed = 0x01;
if (up == RT_TRUE)
dev->link_status = 0x01;
else
dev->link_status = 0x00;
rt_hw_interrupt_enable(level);
/* post message to ethernet thread */
return rt_mb_send(&eth_rx_thread_mb, (rt_uint32_t)dev);
}
/* Ethernet Tx Thread */
static void eth_tx_thread_entry(void* parameter)
{
struct eth_tx_msg* msg;
while (1)
{
if (rt_mb_recv(&eth_tx_thread_mb, (rt_uint32_t*)&msg, RT_WAITING_FOREVER) == RT_EOK)
{
struct eth_device* enetif;
RT_ASSERT(msg->netif != RT_NULL);
RT_ASSERT(msg->buf != RT_NULL);
enetif = (struct eth_device*)msg->netif->state;
if (enetif != RT_NULL)
{
/* call driver's interface */
if (enetif->eth_tx(&(enetif->parent), msg->buf) != RT_EOK)
{
rt_kprintf("transmit eth packet failed\n");
}
}
/* send ACK */
rt_sem_release(&(enetif->tx_ack));
}
}
}
/* Ethernet Rx Thread */
static void eth_rx_thread_entry(void* parameter)
{
struct eth_device* device;
while (1)
{
if (rt_mb_recv(&eth_rx_thread_mb, (rt_uint32_t*)&device, RT_WAITING_FOREVER) == RT_EOK)
{
struct pbuf *p;
/* check link status */
if (device->link_changed)
{
int status;
rt_uint32_t level;
level = rt_hw_interrupt_disable();
status = device->link_status;
device->link_changed = 0x00;
rt_hw_interrupt_enable(level);
if (status)
netifapi_netif_set_link_up(device->netif);
else
netifapi_netif_set_link_down(device->netif);
}
/* receive all of buffer */
while (1)
{
p = device->eth_rx(&(device->parent));
if (p != RT_NULL)
{
/* notify to upper layer */
if( device->netif->input(p, device->netif) != ERR_OK )
{
LWIP_DEBUGF(NETIF_DEBUG, ("ethernetif_input: Input error\n"));
pbuf_free(p);
p = NULL;
}
}
else break;
}
}
else
{
LWIP_ASSERT("Should not happen!\n",0);
}
}
}
void eth_system_device_init()
{
rt_err_t result = RT_EOK;
/* initialize Rx thread.
* initialize mailbox and create Ethernet Rx thread */
result = rt_mb_init(&eth_rx_thread_mb, "erxmb",
&eth_rx_thread_mb_pool[0], sizeof(eth_rx_thread_mb_pool)/4,
RT_IPC_FLAG_FIFO);
RT_ASSERT(result == RT_EOK);
result = rt_thread_init(&eth_rx_thread, "erx", eth_rx_thread_entry, RT_NULL,
&eth_rx_thread_stack[0], sizeof(eth_rx_thread_stack),
RT_LWIP_ETHTHREAD_PRIORITY, 16);
RT_ASSERT(result == RT_EOK);
result = rt_thread_startup(&eth_rx_thread);
RT_ASSERT(result == RT_EOK);
/* initialize Tx thread */
/* initialize mailbox and create Ethernet Tx thread */
result = rt_mb_init(&eth_tx_thread_mb, "etxmb",
&eth_tx_thread_mb_pool[0], sizeof(eth_tx_thread_mb_pool)/4,
RT_IPC_FLAG_FIFO);
RT_ASSERT(result == RT_EOK);
result = rt_thread_init(&eth_tx_thread, "etx", eth_tx_thread_entry, RT_NULL,
&eth_tx_thread_stack[0], sizeof(eth_tx_thread_stack),
RT_ETHERNETIF_THREAD_PREORITY, 16);
RT_ASSERT(result == RT_EOK);
result = rt_thread_startup(&eth_tx_thread);
RT_ASSERT(result == RT_EOK);
}
#ifdef RT_USING_FINSH
#include <finsh.h>
void set_if(char* netif_name, char* ip_addr, char* gw_addr, char* nm_addr)
{
struct ip_addr *ip;
struct ip_addr addr;
struct netif * netif = netif_list;
if(strlen(netif_name) > sizeof(netif->name))
{
rt_kprintf("network interface name too long!\r\n");
return;
}
while(netif != RT_NULL)
{
if(strncmp(netif_name, netif->name, sizeof(netif->name)) == 0)
break;
netif = netif->next;
if( netif == RT_NULL )
{
rt_kprintf("network interface: %s not found!\r\n", netif_name);
return;
}
}
ip = (struct ip_addr *)&addr;
/* set ip address */
if ((ip_addr != RT_NULL) && ipaddr_aton(ip_addr, &addr))
{
netif_set_ipaddr(netif, ip);
}
/* set gateway address */
if ((gw_addr != RT_NULL) && ipaddr_aton(gw_addr, &addr))
{
netif_set_gw(netif, ip);
}
/* set netmask address */
if ((nm_addr != RT_NULL) && ipaddr_aton(nm_addr, &addr))
{
netif_set_netmask(netif, ip);
}
}
FINSH_FUNCTION_EXPORT(set_if, set network interface address);
#if LWIP_DNS
#include <lwip/dns.h>
void set_dns(char* dns_server)
{
struct ip_addr addr;
if ((dns_server != RT_NULL) && ipaddr_aton(dns_server, &addr))
{
dns_setserver(0, &addr);
}
}
FINSH_FUNCTION_EXPORT(set_dns, set DNS server address);
#endif
void list_if(void)
{
rt_ubase_t index;
struct netif * netif;
rt_enter_critical();
netif = netif_list;
while( netif != RT_NULL )
{
rt_kprintf("network interface: %c%c%s\n",
netif->name[0],
netif->name[1],
(netif == netif_default)?" (Default)":"");
rt_kprintf("MTU: %d\n", netif->mtu);
rt_kprintf("MAC: ");
for (index = 0; index < netif->hwaddr_len; index ++)
rt_kprintf("%02x ", netif->hwaddr[index]);
rt_kprintf("\nFLAGS:");
if (netif->flags & NETIF_FLAG_UP) rt_kprintf(" UP");
else rt_kprintf(" DOWN");
if (netif->flags & NETIF_FLAG_LINK_UP) rt_kprintf(" LINK_UP");
else rt_kprintf(" LINK_DOWN");
if (netif->flags & NETIF_FLAG_DHCP) rt_kprintf(" DHCP");
if (netif->flags & NETIF_FLAG_POINTTOPOINT) rt_kprintf(" PPP");
if (netif->flags & NETIF_FLAG_ETHARP) rt_kprintf(" ETHARP");
if (netif->flags & NETIF_FLAG_IGMP) rt_kprintf(" IGMP");
rt_kprintf("\n");
rt_kprintf("ip address: %s\n", ipaddr_ntoa(&(netif->ip_addr)));
rt_kprintf("gw address: %s\n", ipaddr_ntoa(&(netif->gw)));
rt_kprintf("net mask : %s\n", ipaddr_ntoa(&(netif->netmask)));
rt_kprintf("\r\n");
netif = netif->next;
}
#if LWIP_DNS
{
struct ip_addr ip_addr;
for(index=0; index<DNS_MAX_SERVERS; index++)
{
ip_addr = dns_getserver(index);
rt_kprintf("dns server #%d: %s\n", index, ipaddr_ntoa(&(ip_addr)));
}
}
#endif /**< #if LWIP_DNS */
rt_exit_critical();
}
FINSH_FUNCTION_EXPORT(list_if, list network interface information);
#if LWIP_TCP
#include <lwip/tcp.h>
#include <lwip/tcp_impl.h>
void list_tcps(void)
{
rt_uint32_t num = 0;
struct tcp_pcb *pcb;
char local_ip_str[16];
char remote_ip_str[16];
extern struct tcp_pcb *tcp_active_pcbs;
extern union tcp_listen_pcbs_t tcp_listen_pcbs;
extern struct tcp_pcb *tcp_tw_pcbs;
extern const char *tcp_state_str[];
rt_enter_critical();
rt_kprintf("Active PCB states:\n");
for(pcb = tcp_active_pcbs; pcb != NULL; pcb = pcb->next)
{
strcpy(local_ip_str, ipaddr_ntoa(&(pcb->local_ip)));
strcpy(remote_ip_str, ipaddr_ntoa(&(pcb->remote_ip)));
rt_kprintf("#%d %s:%d <==> %s:%d snd_nxt 0x%08X rcv_nxt 0x%08X ",
num++,
local_ip_str,
pcb->local_port,
remote_ip_str,
pcb->remote_port,
pcb->snd_nxt,
pcb->rcv_nxt);
rt_kprintf("state: %s\n", tcp_state_str[pcb->state]);
}
rt_kprintf("Listen PCB states:\n");
num = 0;
for(pcb = (struct tcp_pcb *)tcp_listen_pcbs.pcbs; pcb != NULL; pcb = pcb->next)
{
rt_kprintf("#%d local port %d ", num++, pcb->local_port);
rt_kprintf("state: %s\n", tcp_state_str[pcb->state]);
}
rt_kprintf("TIME-WAIT PCB states:\n");
num = 0;
for(pcb = tcp_tw_pcbs; pcb != NULL; pcb = pcb->next)
{
strcpy(local_ip_str, ipaddr_ntoa(&(pcb->local_ip)));
strcpy(remote_ip_str, ipaddr_ntoa(&(pcb->remote_ip)));
rt_kprintf("#%d %s:%d <==> %s:%d snd_nxt 0x%08X rcv_nxt 0x%08X ",
num++,
local_ip_str,
pcb->local_port,
remote_ip_str,
pcb->remote_port,
pcb->snd_nxt,
pcb->rcv_nxt);
rt_kprintf("state: %s\n", tcp_state_str[pcb->state]);
}
rt_exit_critical();
}
FINSH_FUNCTION_EXPORT(list_tcps, list all of tcp connections);
#endif
#endif

View File

@ -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')

View File

@ -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;

View File

@ -112,9 +112,11 @@ int pthread_rwlock_rdlock (pthread_rwlock_t *rwlock)
while (rwlock->rw_refcount < 0 || rwlock->rw_nwaitwriters > 0)
{
rwlock->rw_nwaitreaders++;
/* rw_mutex will be released when waiting for rw_condreaders */
result = pthread_cond_wait(&rwlock->rw_condreaders, &rwlock->rw_mutex);
/* rw_mutex should have been taken again when returned from waiting */
rwlock->rw_nwaitreaders--;
if (result != 0)
if (result != 0) /* wait error */
break;
}
@ -160,7 +162,9 @@ int pthread_rwlock_timedrdlock (pthread_rwlock_t * rwlock, const struct timespec
while (rwlock->rw_refcount < 0 || rwlock->rw_nwaitwriters > 0)
{
rwlock->rw_nwaitreaders++;
/* rw_mutex will be released when waiting for rw_condreaders */
result = pthread_cond_timedwait(&rwlock->rw_condreaders, &rwlock->rw_mutex, abstime);
/* rw_mutex should have been taken again when returned from waiting */
rwlock->rw_nwaitreaders--;
if (result != 0)
break;
@ -187,7 +191,9 @@ int pthread_rwlock_timedwrlock (pthread_rwlock_t *rwlock, const struct timespec
while (rwlock->rw_refcount != 0)
{
rwlock->rw_nwaitwriters++;
/* rw_mutex will be released when waiting for rw_condwriters */
result = pthread_cond_timedwait(&rwlock->rw_condwriters, &rwlock->rw_mutex, abstime);
/* rw_mutex should have been taken again when returned from waiting */
rwlock->rw_nwaitwriters--;
if (result != 0) break;
@ -233,7 +239,7 @@ int pthread_rwlock_unlock (pthread_rwlock_t *rwlock)
if (rwlock->rw_refcount > 0)
rwlock->rw_refcount--; /* releasing a reader */
else if (rwlock->rw_refcount == -1)
rwlock->rw_refcount = 0; /* releasing a reader */
rwlock->rw_refcount = 0; /* releasing a writer */
/* give preference to waiting writers over waiting readers */
if (rwlock->rw_nwaitwriters > 0)
@ -264,7 +270,9 @@ int pthread_rwlock_wrlock (pthread_rwlock_t *rwlock)
while (rwlock->rw_refcount != 0)
{
rwlock->rw_nwaitwriters++;
/* rw_mutex will be released when waiting for rw_condwriters */
result = pthread_cond_wait(&rwlock->rw_condwriters, &rwlock->rw_mutex);
/* rw_mutex should have been taken again when returned from waiting */
rwlock->rw_nwaitwriters--;
if (result != 0) break;

View File

@ -0,0 +1,45 @@
# Roadmap for RT-Thread 1.2.0 #
The document is the mainly task of RT-Thread 1.2.0. In this series, there will be a full manual document for RT-Thread 1.x series. The format of document is markdown document[0] on github.com and some hardware environment is used in document (RT-Thread Real-Touch[1]).
The document will be wroten in Chinese firstly. At least when RT-Thread 1.2.0 has officially released, the Chinese edition of manual is ready. The manual includes:
1. RT-Thread Kernel (The basic facilities in RTOS)
2. How to port RT-Thread in a new architecture.
3. RT-Thread components.
4. How to debug in RT-Thread.
## Other codes changes in planning ##
### Improvement on bsp porting ###
- LPC18xx & LPC43xx
* USB host and device driver;
- Other BSP.
* welcome contributions.
### New features on Components ###
- device IPC
* implement the work queue[2].
* implement the rwlock[3].
* The APIs are like *BSD, but implement in RT-Thread
- finsh shell
* implement a UNIX style shell, and this shell can execute application module.
- device file system
* implement select[4] API for device object in RT-Thread.
- lwIP TCP/IP stack
* enable IPv6 feature[5].
- gdb server or stub
[0] RT-Thread manual: https://github.com/RT-Thread/manual-doc
[1] RT-Thread Real-Touch: https://github.com/RT-Thread/realtouch-stm32f4
[2] work queue: http://fxr.watson.org/fxr/source/sys/workqueue.h?v=NETBSD
[3] rwlock: http://fxr.watson.org/fxr/source/sys/rwlock.h?v=NETBSD
[4] select API: http://pubs.opengroup.org/onlinepubs/7908799/xsh/select.html
[5] dual IPv4/v6 stack: http://lwip.wikia.com/wiki/LwIP_IPv4/IPv6_stacks

View File

@ -24,6 +24,9 @@
extern "C" {
#endif
/*
* CPU interfaces
*/
void rt_hw_cpu_icache_enable(void);
void rt_hw_cpu_icache_disable(void);
rt_base_t rt_hw_cpu_icache_status(void);
@ -38,16 +41,38 @@ rt_uint8_t *rt_hw_stack_init(void *entry,
rt_uint8_t *stack_addr,
void *exit);
/*
* Interrupt handler definition
*/
typedef void (*rt_isr_handler_t)(int vector, void *param);
struct rt_irq_desc {
rt_isr_handler_t handler;
void *param;
#ifdef RT_USING_INTERRUPT_INFO
char name[RT_NAME_MAX];
rt_uint32_t counter;
#endif
};
/*
* Interrupt interfaces
*/
void rt_hw_interrupt_init(void);
void rt_hw_interrupt_mask(int vector);
void rt_hw_interrupt_umask(int vector);
void rt_hw_interrupt_install(int vector,
rt_isr_handler_t new_handler,
rt_isr_handler_t *old_handler);
void rt_hw_interrupt_handle(int vector);
rt_isr_handler_t rt_hw_interrupt_install(int vector,
rt_isr_handler_t handler,
void *param,
char *name);
rt_base_t rt_hw_interrupt_disable(void);
void rt_hw_interrupt_enable(rt_base_t level);
/*
* Context interfaces
*/
void rt_hw_context_switch(rt_uint32_t from, rt_uint32_t to);
void rt_hw_context_switch_to(rt_uint32_t to);
void rt_hw_context_switch_interrupt(rt_uint32_t from, rt_uint32_t to);
@ -58,7 +83,7 @@ void rt_hw_backtrace(rt_uint32_t *fp, rt_uint32_t thread_entry);
void rt_hw_show_memory(rt_uint32_t addr, rt_uint32_t size);
/*
* exception interfaces
* Exception interfaces
*/
void rt_hw_exception_install(rt_err_t (*exception_handle)(void* context));

View File

@ -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

View File

@ -10,13 +10,18 @@
* Change Logs:
* Date Author Notes
* 2006-08-23 Bernard first version
* 2013-03-29 aozima Modify the interrupt interface implementations.
*/
#include <rtthread.h>
#include <rthw.h>
#include "AT91SAM7X256.h"
#define MAX_HANDLERS 32
/* exception and interrupt handler table */
struct rt_irq_desc irq_desc[MAX_HANDLERS];
extern rt_uint32_t rt_interrupt_nest;
rt_uint32_t rt_interrupt_from_thread, rt_interrupt_to_thread;
@ -27,7 +32,7 @@ rt_uint32_t rt_thread_switch_interrupt_flag;
*/
/*@{*/
void rt_hw_interrupt_handler(int vector)
static void rt_hw_interrupt_handler(int vector, void *param)
{
rt_kprintf("Unhandled interrupt %d occured!!!\n", vector);
}
@ -35,10 +40,17 @@ void rt_hw_interrupt_handler(int vector)
/**
* This function will initialize hardware interrupt
*/
void rt_hw_interrupt_init()
void rt_hw_interrupt_init(void)
{
rt_base_t index;
/* init exceptions table */
for(index=0; index < MAX_HANDLERS; index++)
{
irq_desc[index].handler = (rt_isr_handler_t)rt_hw_interrupt_handler;
irq_desc[index].param = RT_NULL;
}
for (index = 0; index < MAX_HANDLERS; index ++)
{
AT91C_BASE_AIC->AIC_SVR[index] = (rt_uint32_t)rt_hw_interrupt_handler;
@ -76,16 +88,27 @@ void rt_hw_interrupt_umask(int vector)
/**
* This function will install a interrupt service routine to a interrupt.
* @param vector the interrupt number
* @param new_handler the interrupt service routine to be installed
* @param old_handler the old interrupt service routine
* @param handler the interrupt service routine to be installed
* @param param the parameter for interrupt service routine
* @name unused.
*
* @return the old handler
*/
void rt_hw_interrupt_install(int vector, rt_isr_handler_t new_handler, rt_isr_handler_t *old_handler)
rt_isr_handler_t rt_hw_interrupt_install(int vector, rt_isr_handler_t handler,
void *param, char *name)
{
rt_isr_handler_t old_handler = RT_NULL;
if(vector >= 0 && vector < MAX_HANDLERS)
{
if (old_handler != RT_NULL) *old_handler = (rt_isr_handler_t)AT91C_BASE_AIC->AIC_SVR[vector];
if (new_handler != RT_NULL) AT91C_BASE_AIC->AIC_SVR[vector] = (rt_uint32_t)new_handler;
old_handler = irq_desc[vector].handler;
if (handler != RT_NULL)
{
irq_desc[vector].handler = (rt_isr_handler_t)handler;
irq_desc[vector].param = param;
}
}
return old_handler;
}
/*@}*/

View File

@ -22,23 +22,28 @@
*/
/*@{*/
void rt_hw_trap_irq()
void rt_hw_trap_irq(void)
{
rt_isr_handler_t hander = (rt_isr_handler_t)AT91C_BASE_AIC->AIC_IVR;
int irqno;
extern struct rt_irq_desc irq_desc[];
hander(AT91C_BASE_AIC->AIC_ISR);
/* get interrupt number */
irqno = AT91C_BASE_AIC->AIC_ISR;
/* invoke isr with parameters */
irq_desc[irqno].handler(irqno, irq_desc[irqno].param);
/* end of interrupt */
AT91C_BASE_AIC->AIC_EOICR = 0;
}
void rt_hw_trap_fiq()
void rt_hw_trap_fiq(void)
{
rt_kprintf("fast interrupt request\n");
}
extern struct rt_thread* rt_current_thread;
void rt_hw_trap_abort()
void rt_hw_trap_abort(void)
{
rt_kprintf("Abort occured!!! Thread [%s] suspended.\n",rt_current_thread->name);
rt_thread_suspend(rt_current_thread);

View File

@ -190,4 +190,60 @@ void rt_hw_cpu_shutdown()
}
}
#ifdef RT_USING_CPU_FFS
/**
* This function finds the first bit set (beginning with the least significant bit)
* in value and return the index of that bit.
*
* Bits are numbered starting at 1 (the least significant bit). A return value of
* zero from any of these functions means that the argument was zero.
*
* @return return the index of the first bit set. If value is 0, then this function
* shall return 0.
*/
#if defined(__CC_ARM)
int __rt_ffs(int value)
{
register rt_uint32_t x;
if (value == 0)
return value;
__asm
{
rsb x, value, #0
and x, x, value
clz x, x
rsb x, x, #32
}
return x;
}
#elif defined(__IAR_SYSTEMS_ICC__)
int __rt_ffs(int value)
{
if (value == 0)
return value;
__ASM("RSB r4, r0, #0");
__ASM("AND r4, r4, r0");
__ASM("CLZ r4, r4");
__ASM("RSB r0, r4, #32");
}
#elif defined(__GNUC__)
int __rt_ffs(int value)
{
if (value == 0)
return value;
value &= (-value);
asm ("clz %0, %1": "=r"(value) :"r"(value));
return (32 - value);
}
#endif
#endif
/*@}*/

View File

@ -12,15 +12,16 @@
* 2011-01-13 weety first version
*/
#include <rtthread.h>
#include <rthw.h>
#include "at91sam926x.h"
#define MAX_HANDLERS (AIC_IRQS + PIN_IRQS)
#define MAX_HANDLERS (AIC_IRQS + PIN_IRQS)
extern rt_uint32_t rt_interrupt_nest;
/* exception and interrupt handler table */
rt_isr_handler_t isr_table[MAX_HANDLERS];
struct rt_irq_desc irq_desc[MAX_HANDLERS];
rt_uint32_t rt_interrupt_from_thread, rt_interrupt_to_thread;
rt_uint32_t rt_thread_switch_interrupt_flag;
@ -37,38 +38,38 @@ rt_uint32_t at91_extern_irq;
* The default interrupt priority levels (0 = lowest, 7 = highest).
*/
static rt_uint32_t at91sam9260_default_irq_priority[MAX_HANDLERS] = {
7, /* Advanced Interrupt Controller */
7, /* System Peripherals */
1, /* Parallel IO Controller A */
1, /* Parallel IO Controller B */
1, /* Parallel IO Controller C */
0, /* Analog-to-Digital Converter */
5, /* USART 0 */
5, /* USART 1 */
5, /* USART 2 */
0, /* Multimedia Card Interface */
2, /* USB Device Port */
6, /* Two-Wire Interface */
5, /* Serial Peripheral Interface 0 */
5, /* Serial Peripheral Interface 1 */
5, /* Serial Synchronous Controller */
0,
0,
0, /* Timer Counter 0 */
0, /* Timer Counter 1 */
0, /* Timer Counter 2 */
2, /* USB Host port */
3, /* Ethernet */
0, /* Image Sensor Interface */
5, /* USART 3 */
5, /* USART 4 */
5, /* USART 5 */
0, /* Timer Counter 3 */
0, /* Timer Counter 4 */
0, /* Timer Counter 5 */
0, /* Advanced Interrupt Controller */
0, /* Advanced Interrupt Controller */
0, /* Advanced Interrupt Controller */
7, /* Advanced Interrupt Controller */
7, /* System Peripherals */
1, /* Parallel IO Controller A */
1, /* Parallel IO Controller B */
1, /* Parallel IO Controller C */
0, /* Analog-to-Digital Converter */
5, /* USART 0 */
5, /* USART 1 */
5, /* USART 2 */
0, /* Multimedia Card Interface */
2, /* USB Device Port */
6, /* Two-Wire Interface */
5, /* Serial Peripheral Interface 0 */
5, /* Serial Peripheral Interface 1 */
5, /* Serial Synchronous Controller */
0,
0,
0, /* Timer Counter 0 */
0, /* Timer Counter 1 */
0, /* Timer Counter 2 */
2, /* USB Host port */
3, /* Ethernet */
0, /* Image Sensor Interface */
5, /* USART 3 */
5, /* USART 4 */
5, /* USART 5 */
0, /* Timer Counter 3 */
0, /* Timer Counter 4 */
0, /* Timer Counter 5 */
0, /* Advanced Interrupt Controller */
0, /* Advanced Interrupt Controller */
0, /* Advanced Interrupt Controller */
};
/**
@ -79,45 +80,47 @@ static rt_uint32_t at91sam9260_default_irq_priority[MAX_HANDLERS] = {
void rt_hw_interrupt_mask(int irq);
void rt_hw_interrupt_umask(int irq);
rt_isr_handler_t rt_hw_interrupt_handle(rt_uint32_t vector)
rt_isr_handler_t rt_hw_interrupt_handle(rt_uint32_t vector, void *param)
{
rt_kprintf("Unhandled interrupt %d occured!!!\n", vector);
return RT_NULL;
rt_kprintf("Unhandled interrupt %d occured!!!\n", vector);
return RT_NULL;
}
rt_isr_handler_t at91_gpio_irq_handle(rt_uint32_t vector)
rt_isr_handler_t at91_gpio_irq_handle(rt_uint32_t vector, void *param)
{
rt_uint32_t isr, pio, irq_n;
rt_uint32_t isr, pio, irq_n;
void *parameter;
if (vector == AT91SAM9260_ID_PIOA)
{
pio = AT91_PIOA;
irq_n = AIC_IRQS;
}
else if (vector == AT91SAM9260_ID_PIOB)
{
pio = AT91_PIOB;
irq_n = AIC_IRQS + 32;
}
else if (vector == AT91SAM9260_ID_PIOC)
{
pio = AT91_PIOC;
irq_n = AIC_IRQS + 32*2;
}
else
return RT_NULL;
isr = at91_sys_read(pio+PIO_ISR) & at91_sys_read(pio+PIO_IMR);
while (isr)
{
if (isr & 1)
{
isr_table[irq_n](irq_n);
}
isr >>= 1;
irq_n++;
}
if (vector == AT91SAM9260_ID_PIOA)
{
pio = AT91_PIOA;
irq_n = AIC_IRQS;
}
else if (vector == AT91SAM9260_ID_PIOB)
{
pio = AT91_PIOB;
irq_n = AIC_IRQS + 32;
}
else if (vector == AT91SAM9260_ID_PIOC)
{
pio = AT91_PIOC;
irq_n = AIC_IRQS + 32*2;
}
else
return RT_NULL;
isr = at91_sys_read(pio+PIO_ISR) & at91_sys_read(pio+PIO_IMR);
while (isr)
{
if (isr & 1)
{
parameter = irq_desc[irq_n].param;
irq_desc[irq_n].handler(irq_n, parameter);
}
isr >>= 1;
irq_n++;
}
return RT_NULL;
return RT_NULL;
}
/*
@ -125,52 +128,61 @@ rt_isr_handler_t at91_gpio_irq_handle(rt_uint32_t vector)
*/
void at91_aic_init(rt_uint32_t *priority)
{
rt_uint32_t i;
rt_uint32_t i;
/*
* The IVR is used by macro get_irqnr_and_base to read and verify.
* The irq number is NR_AIC_IRQS when a spurious interrupt has occurred.
*/
for (i = 0; i < AIC_IRQS; i++) {
/* Put irq number in Source Vector Register: */
at91_sys_write(AT91_AIC_SVR(i), i);
/* Active Low interrupt, with the specified priority */
at91_sys_write(AT91_AIC_SMR(i), AT91_AIC_SRCTYPE_LOW | priority[i]);
//AT91_AIC_SRCTYPE_FALLING
/*
* The IVR is used by macro get_irqnr_and_base to read and verify.
* The irq number is NR_AIC_IRQS when a spurious interrupt has occurred.
*/
for (i = 0; i < AIC_IRQS; i++) {
/* Put irq number in Source Vector Register: */
at91_sys_write(AT91_AIC_SVR(i), i);
/* Active Low interrupt, with the specified priority */
at91_sys_write(AT91_AIC_SMR(i), AT91_AIC_SRCTYPE_LOW | priority[i]);
//AT91_AIC_SRCTYPE_FALLING
/* Perform 8 End Of Interrupt Command to make sure AIC will not Lock out nIRQ */
if (i < 8)
at91_sys_write(AT91_AIC_EOICR, 0);
}
/* Perform 8 End Of Interrupt Command to make sure AIC will not Lock out nIRQ */
if (i < 8)
at91_sys_write(AT91_AIC_EOICR, 0);
}
/*
* Spurious Interrupt ID in Spurious Vector Register is NR_AIC_IRQS
* When there is no current interrupt, the IRQ Vector Register reads the value stored in AIC_SPU
*/
at91_sys_write(AT91_AIC_SPU, AIC_IRQS);
/*
* Spurious Interrupt ID in Spurious Vector Register is NR_AIC_IRQS
* When there is no current interrupt, the IRQ Vector Register reads the value stored in AIC_SPU
*/
at91_sys_write(AT91_AIC_SPU, AIC_IRQS);
/* No debugging in AIC: Debug (Protect) Control Register */
at91_sys_write(AT91_AIC_DCR, 0);
/* No debugging in AIC: Debug (Protect) Control Register */
at91_sys_write(AT91_AIC_DCR, 0);
/* Disable and clear all interrupts initially */
at91_sys_write(AT91_AIC_IDCR, 0xFFFFFFFF);
at91_sys_write(AT91_AIC_ICCR, 0xFFFFFFFF);
/* Disable and clear all interrupts initially */
at91_sys_write(AT91_AIC_IDCR, 0xFFFFFFFF);
at91_sys_write(AT91_AIC_ICCR, 0xFFFFFFFF);
}
static void at91_gpio_irq_init()
{
at91_sys_write(AT91_PIOA+PIO_IDR, 0xffffffff);
at91_sys_write(AT91_PIOB+PIO_IDR, 0xffffffff);
at91_sys_write(AT91_PIOC+PIO_IDR, 0xffffffff);
int i, idx;
char *name[] = {"PIOA", "PIOB", "PIOC"};
at91_sys_write(AT91_PIOA+PIO_IDR, 0xffffffff);
at91_sys_write(AT91_PIOB+PIO_IDR, 0xffffffff);
at91_sys_write(AT91_PIOC+PIO_IDR, 0xffffffff);
isr_table[AT91SAM9260_ID_PIOA] = (rt_isr_handler_t)at91_gpio_irq_handle;
isr_table[AT91SAM9260_ID_PIOB] = (rt_isr_handler_t)at91_gpio_irq_handle;
isr_table[AT91SAM9260_ID_PIOC] = (rt_isr_handler_t)at91_gpio_irq_handle;
idx = AT91SAM9260_ID_PIOA;
for (i = 0; i < 3; i++)
{
rt_snprintf(irq_desc[idx].name, RT_NAME_MAX - 1, name[i]);
irq_desc[idx].handler = (rt_isr_handler_t)at91_gpio_irq_handle;
irq_desc[idx].param = RT_NULL;
irq_desc[idx].counter = 0;
idx++;
}
rt_hw_interrupt_umask(AT91SAM9260_ID_PIOA);
rt_hw_interrupt_umask(AT91SAM9260_ID_PIOB);
rt_hw_interrupt_umask(AT91SAM9260_ID_PIOC);
rt_hw_interrupt_umask(AT91SAM9260_ID_PIOA);
rt_hw_interrupt_umask(AT91SAM9260_ID_PIOB);
rt_hw_interrupt_umask(AT91SAM9260_ID_PIOC);
}
@ -179,53 +191,56 @@ static void at91_gpio_irq_init()
*/
void rt_hw_interrupt_init(void)
{
rt_int32_t i;
register rt_uint32_t idx;
rt_uint32_t *priority = at91sam9260_default_irq_priority;
at91_extern_irq = (1 << AT91SAM9260_ID_IRQ0) | (1 << AT91SAM9260_ID_IRQ1)
| (1 << AT91SAM9260_ID_IRQ2);
rt_int32_t i;
register rt_uint32_t idx;
rt_uint32_t *priority = at91sam9260_default_irq_priority;
at91_extern_irq = (1 << AT91SAM9260_ID_IRQ0) | (1 << AT91SAM9260_ID_IRQ1)
| (1 << AT91SAM9260_ID_IRQ2);
/* Initialize the AIC interrupt controller */
at91_aic_init(priority);
/* Initialize the AIC interrupt controller */
at91_aic_init(priority);
/* init exceptions table */
for(idx=0; idx < MAX_HANDLERS; idx++)
{
isr_table[idx] = (rt_isr_handler_t)rt_hw_interrupt_handle;
}
/* init exceptions table */
for(idx=0; idx < MAX_HANDLERS; idx++)
{
rt_snprintf(irq_desc[idx].name, RT_NAME_MAX - 1, "default");
irq_desc[idx].handler = (rt_isr_handler_t)rt_hw_interrupt_handle;
irq_desc[idx].param = RT_NULL;
irq_desc[idx].counter = 0;
}
at91_gpio_irq_init();
at91_gpio_irq_init();
/* init interrupt nest, and context in thread sp */
rt_interrupt_nest = 0;
rt_interrupt_from_thread = 0;
rt_interrupt_to_thread = 0;
rt_thread_switch_interrupt_flag = 0;
/* init interrupt nest, and context in thread sp */
rt_interrupt_nest = 0;
rt_interrupt_from_thread = 0;
rt_interrupt_to_thread = 0;
rt_thread_switch_interrupt_flag = 0;
}
static void at91_gpio_irq_mask(int irq)
{
rt_uint32_t pin, pio, bank;
rt_uint32_t pin, pio, bank;
bank = (irq - AIC_IRQS)>>5;
bank = (irq - AIC_IRQS)>>5;
if (bank == 0)
{
pio = AT91_PIOA;
}
else if (bank == 1)
{
pio = AT91_PIOB;
}
else if (bank == 2)
{
pio = AT91_PIOC;
}
else
return;
pin = 1 << ((irq - AIC_IRQS) & 31);
at91_sys_write(pio+PIO_IDR, pin);
if (bank == 0)
{
pio = AT91_PIOA;
}
else if (bank == 1)
{
pio = AT91_PIOB;
}
else if (bank == 2)
{
pio = AT91_PIOC;
}
else
return;
pin = 1 << ((irq - AIC_IRQS) & 31);
at91_sys_write(pio+PIO_IDR, pin);
}
/**
@ -234,39 +249,39 @@ static void at91_gpio_irq_mask(int irq)
*/
void rt_hw_interrupt_mask(int irq)
{
if (irq >= AIC_IRQS)
{
at91_gpio_irq_mask(irq);
}
else
{
/* Disable interrupt on AIC */
at91_sys_write(AT91_AIC_IDCR, 1 << irq);
}
if (irq >= AIC_IRQS)
{
at91_gpio_irq_mask(irq);
}
else
{
/* Disable interrupt on AIC */
at91_sys_write(AT91_AIC_IDCR, 1 << irq);
}
}
static void at91_gpio_irq_umask(int irq)
{
rt_uint32_t pin, pio, bank;
rt_uint32_t pin, pio, bank;
bank = (irq - AIC_IRQS)>>5;
bank = (irq - AIC_IRQS)>>5;
if (bank == 0)
{
pio = AT91_PIOA;
}
else if (bank == 1)
{
pio = AT91_PIOB;
}
else if (bank == 2)
{
pio = AT91_PIOC;
}
else
return;
pin = 1 << ((irq - AIC_IRQS) & 31);
at91_sys_write(pio+PIO_IER, pin);
if (bank == 0)
{
pio = AT91_PIOA;
}
else if (bank == 1)
{
pio = AT91_PIOB;
}
else if (bank == 2)
{
pio = AT91_PIOC;
}
else
return;
pin = 1 << ((irq - AIC_IRQS) & 31);
at91_sys_write(pio+PIO_IER, pin);
}
/**
@ -275,30 +290,43 @@ static void at91_gpio_irq_umask(int irq)
*/
void rt_hw_interrupt_umask(int irq)
{
if (irq >= AIC_IRQS)
{
at91_gpio_irq_umask(irq);
}
else
{
/* Enable interrupt on AIC */
at91_sys_write(AT91_AIC_IECR, 1 << irq);
}
if (irq >= AIC_IRQS)
{
at91_gpio_irq_umask(irq);
}
else
{
/* Enable interrupt on AIC */
at91_sys_write(AT91_AIC_IECR, 1 << irq);
}
}
/**
* This function will install a interrupt service routine to a interrupt.
* @param vector the interrupt number
* @param new_handler the interrupt service routine to be installed
* @param old_handler the old interrupt service routine
* @param handler the interrupt service routine to be installed
* @param param the interrupt service function parameter
* @param name the interrupt name
* @return old handler
*/
void rt_hw_interrupt_install(int vector, rt_isr_handler_t new_handler, rt_isr_handler_t *old_handler)
rt_isr_handler_t rt_hw_interrupt_install(int vector, rt_isr_handler_t handler,
void *param, char *name)
{
if(vector < MAX_HANDLERS)
{
if (old_handler != RT_NULL) *old_handler = isr_table[vector];
if (new_handler != RT_NULL) isr_table[vector] = new_handler;
}
rt_isr_handler_t old_handler = RT_NULL;
if(vector < MAX_HANDLERS)
{
old_handler = irq_desc[vector].handler;
if (handler != RT_NULL)
{
rt_snprintf(irq_desc[vector].name, RT_NAME_MAX - 1, "%s", name);
irq_desc[vector].handler = (rt_isr_handler_t)handler;
irq_desc[vector].param = param;
irq_desc[vector].counter = 0;
}
}
return old_handler;
}
/*@}*/
@ -306,32 +334,54 @@ void rt_hw_interrupt_install(int vector, rt_isr_handler_t new_handler, rt_isr_ha
static int at91_aic_set_type(unsigned irq, unsigned type)
{
unsigned int smr, srctype;
unsigned int smr, srctype;
switch (type) {
case IRQ_TYPE_LEVEL_HIGH:
srctype = AT91_AIC_SRCTYPE_HIGH;
break;
case IRQ_TYPE_EDGE_RISING:
srctype = AT91_AIC_SRCTYPE_RISING;
break;
case IRQ_TYPE_LEVEL_LOW:
if ((irq == AT91_ID_FIQ) || is_extern_irq(irq)) /* only supported on external interrupts */
srctype = AT91_AIC_SRCTYPE_LOW;
else
return -1;
break;
case IRQ_TYPE_EDGE_FALLING:
if ((irq == AT91_ID_FIQ) || is_extern_irq(irq)) /* only supported on external interrupts */
srctype = AT91_AIC_SRCTYPE_FALLING;
else
return -1;
break;
default:
return -1;
}
switch (type) {
case IRQ_TYPE_LEVEL_HIGH:
srctype = AT91_AIC_SRCTYPE_HIGH;
break;
case IRQ_TYPE_EDGE_RISING:
srctype = AT91_AIC_SRCTYPE_RISING;
break;
case IRQ_TYPE_LEVEL_LOW:
if ((irq == AT91_ID_FIQ) || is_extern_irq(irq)) /* only supported on external interrupts */
srctype = AT91_AIC_SRCTYPE_LOW;
else
return -1;
break;
case IRQ_TYPE_EDGE_FALLING:
if ((irq == AT91_ID_FIQ) || is_extern_irq(irq)) /* only supported on external interrupts */
srctype = AT91_AIC_SRCTYPE_FALLING;
else
return -1;
break;
default:
return -1;
}
smr = at91_sys_read(AT91_AIC_SMR(irq)) & ~AT91_AIC_SRCTYPE;
at91_sys_write(AT91_AIC_SMR(irq), smr | srctype);
return 0;
smr = at91_sys_read(AT91_AIC_SMR(irq)) & ~AT91_AIC_SRCTYPE;
at91_sys_write(AT91_AIC_SMR(irq), smr | srctype);
return 0;
}
#ifdef RT_USING_FINSH
void list_irq(void)
{
int irq;
rt_kprintf("number\tcount\tname\n");
for (irq = 0; irq < MAX_HANDLERS; irq++)
{
if (rt_strncmp(irq_desc[irq].name, "default", sizeof("default")))
{
rt_kprintf("%02ld: %10ld %s\n", irq, irq_desc[irq].counter, irq_desc[irq].name);
}
}
}
#include <finsh.h>
FINSH_FUNCTION_EXPORT(list_irq, list system irq);
#endif

View File

@ -138,12 +138,13 @@ void rt_hw_trap_resv(struct rt_hw_register *regs)
rt_hw_cpu_shutdown();
}
extern rt_isr_handler_t isr_table[];
extern struct rt_irq_desc irq_desc[];
void rt_hw_trap_irq()
{
rt_isr_handler_t isr_func;
rt_uint32_t irqstat, irq, mask;
void *param;
//rt_kprintf("irq interrupt request\n");
/* get irq number */
irq = at91_sys_read(AT91_AIC_IVR);
@ -158,11 +159,13 @@ void rt_hw_trap_irq()
//at91_sys_write(AT91_AIC_EOICR, 0x55555555);
/* get interrupt service routine */
isr_func = isr_table[irq];
isr_func = irq_desc[irq].handler;
param = irq_desc[irq].param;
/* turn to interrupt service routine */
isr_func(irq);
isr_func(irq, param);
at91_sys_write(AT91_AIC_EOICR, 0x55555555); //EIOCR must be write any value after interrupt, or else can't response next interrupt
irq_desc[irq].counter ++;
}
void rt_hw_trap_fiq()

View File

@ -148,3 +148,43 @@ void rt_hw_cpu_shutdown(void)
RT_ASSERT(0);
}
#ifdef RT_USING_CPU_FFS
/**
* This function finds the first bit set (beginning with the least significant bit)
* in value and return the index of that bit.
*
* Bits are numbered starting at 1 (the least significant bit). A return value of
* zero from any of these functions means that the argument was zero.
*
* @return return the index of the first bit set. If value is 0, then this function
* shall return 0.
*/
#if defined(__CC_ARM)
__asm int __rt_ffs(int value)
{
CMP r0, #0x00
BEQ exit
RBIT r0, r0
CLZ r0, r0
ADDS r0, r0, #0x01
exit
BX lr
}
#elif defined(__IAR_SYSTEMS_ICC__)
int __rt_ffs(int value)
{
if (value == 0) return value;
__ASM("RBIT r0, r0");
__ASM("CLZ r0, r0");
__ASM("ADDS r0, r0, #0x01");
}
#elif defined(__GNUC__)
int __rt_ffs(int value)
{
return __builtin_ffs(value);
}
#endif
#endif

View File

@ -10,9 +10,11 @@
* Change Logs:
* Date Author Notes
* 2011-06-15 aozima the first version for lpc214x
* 2013-03-29 aozima Modify the interrupt interface implementations.
*/
#include <rtthread.h>
#include <rthw.h>
#include "lpc214x.h"
#define MAX_HANDLERS 32
@ -20,6 +22,9 @@
extern rt_uint32_t rt_interrupt_nest;
/* exception and interrupt handler table */
struct rt_irq_desc irq_desc[MAX_HANDLERS];
/**
* @addtogroup LPC214x
*/
@ -71,7 +76,7 @@ rt_uint8_t *rt_hw_stack_init(void *tentry, void *parameter,
rt_uint32_t rt_interrupt_from_thread, rt_interrupt_to_thread;
rt_uint32_t rt_thread_switch_interrupt_flag;
void rt_hw_interrupt_handler(int vector)
void rt_hw_interrupt_handler(int vector, void *param)
{
rt_kprintf("Unhandled interrupt %d occured!!!\n", vector);
}
@ -79,7 +84,7 @@ void rt_hw_interrupt_handler(int vector)
/**
* This function will initialize hardware interrupt
*/
void rt_hw_interrupt_init()
void rt_hw_interrupt_init(void)
{
rt_base_t index;
rt_uint32_t *vect_addr, *vect_ctl;
@ -90,12 +95,15 @@ void rt_hw_interrupt_init()
/* set all to IRQ */
VICIntSelect = 0;
rt_memset(irq_desc, 0x00, sizeof(irq_desc));
for (index = 0; index < MAX_HANDLERS; index ++)
{
irq_desc[index].handler = rt_hw_interrupt_handler;
vect_addr = (rt_uint32_t *)(VIC_BASE_ADDR + 0x100 + (index << 2));
vect_ctl = (rt_uint32_t *)(VIC_BASE_ADDR + 0x200 + (index << 2));
*vect_addr = (rt_uint32_t)rt_hw_interrupt_handler;
*vect_addr = (rt_uint32_t)&irq_desc[index];
*vect_ctl = 0xF;
}
@ -127,30 +135,39 @@ void rt_hw_interrupt_umask(int vector)
/**
* This function will install a interrupt service routine to a interrupt.
* @param vector the interrupt number
* @param new_handler the interrupt service routine to be installed
* @param old_handler the old interrupt service routine
* @param handler the interrupt service routine to be installed
* @param param the interrupt service function parameter
* @param name the interrupt name
* @return old handler
*/
void rt_hw_interrupt_install(int vector, rt_isr_handler_t new_handler, rt_isr_handler_t *old_handler)
rt_isr_handler_t rt_hw_interrupt_install(int vector, rt_isr_handler_t handler,
void *param, char *name)
{
if(vector >= 0 && vector < MAX_HANDLERS)
{
/* get VIC address */
rt_uint32_t* vect_addr = (rt_uint32_t *)(VIC_BASE_ADDR + 0x100 + (vector << 2));
rt_uint32_t* vect_ctl = (rt_uint32_t *)(VIC_BASE_ADDR + 0x200 + (vector << 2));
rt_isr_handler_t old_handler = RT_NULL;
/* assign IRQ slot and enable this slot */
*vect_ctl = 0x20 | (vector & 0x1F);
if(vector >= 0 && vector < MAX_HANDLERS)
{
rt_uint32_t* vect_ctl = (rt_uint32_t *)(VIC_BASE_ADDR + 0x200 + (vector << 2));
if (old_handler != RT_NULL) *old_handler = (rt_isr_handler_t) *vect_addr;
if (new_handler != RT_NULL) *vect_addr = (rt_uint32_t) new_handler;
}
/* assign IRQ slot and enable this slot */
*vect_ctl = 0x20 | (vector & 0x1F);
old_handler = irq_desc[vector].handler;
if (handler != RT_NULL)
{
irq_desc[vector].handler = handler;
irq_desc[vector].param = param;
}
}
return old_handler;
}
/**
* this function will reset CPU
*
*/
void rt_hw_cpu_reset()
void rt_hw_cpu_reset(void)
{
}
@ -165,18 +182,23 @@ void rt_hw_cpu_shutdown()
while (1);
}
void rt_hw_trap_irq()
void rt_hw_trap_irq(void)
{
rt_isr_handler_t isr_func;
int irqno;
struct rt_irq_desc* irq;
extern struct rt_irq_desc irq_desc[];
isr_func = (rt_isr_handler_t) VICVectAddr;
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);
/* acknowledge Interrupt */
// VICVectAddr = 0;
/* invoke isr */
irq->handler(irqno, irq->param);
/* acknowledge Interrupt */
// VICVectAddr = 0;
}
void rt_hw_trap_fiq()
void rt_hw_trap_fiq(void)
{
rt_kprintf("fast interrupt request\n");
}

View File

@ -10,31 +10,34 @@
* Change Logs:
* Date Author Notes
* 2008-12-11 XuXinming first version
* 2013-03-29 aozima Modify the interrupt interface implementations.
*/
#include <rtthread.h>
#include <rthw.h>
#include "LPC24xx.h"
#define MAX_HANDLERS 32
/* exception and interrupt handler table */
struct rt_irq_desc irq_desc[MAX_HANDLERS];
extern rt_uint32_t rt_interrupt_nest;
/* exception and interrupt handler table */
rt_uint32_t rt_interrupt_from_thread, rt_interrupt_to_thread;
rt_uint32_t rt_thread_switch_interrupt_flag;
/**
* @addtogroup LPC2478
*/
/*@{*/
void rt_hw_interrupt_handle(int vector)
void rt_hw_interrupt_handler(int vector, void *param)
{
rt_kprintf("Unhandled interrupt %d occured!!!\n", vector);
}
void rt_hw_interrupt_init()
void rt_hw_interrupt_init(void)
{
register int i;
@ -45,11 +48,15 @@ void rt_hw_interrupt_init()
VICVectAddr = 0;
VICIntSelect = 0;
for ( i = 0; i < 32; i++ )
/* init exceptions table */
rt_memset(irq_desc, 0x00, sizeof(irq_desc));
for(i=0; i < MAX_HANDLERS; i++)
{
vect_addr = (rt_uint32_t *)(VIC_BASE_ADDR + 0x100 + i*4);
vect_cntl = (rt_uint32_t *)(VIC_BASE_ADDR + 0x200 + i*4);
*vect_addr = 0x0;
irq_desc[i].handler = rt_hw_interrupt_handler;
vect_addr = (rt_uint32_t *)(VIC_BASE_ADDR + 0x100 + i*4);
vect_cntl = (rt_uint32_t *)(VIC_BASE_ADDR + 0x200 + i*4);
*vect_addr = (rt_uint32_t)&irq_desc[i];
*vect_cntl = 0xF;
}
@ -70,20 +77,31 @@ void rt_hw_interrupt_umask(int vector)
VICIntEnable = (1 << vector);
}
void rt_hw_interrupt_install(int vector, rt_isr_handler_t new_handler, rt_isr_handler_t *old_handler)
/**
* This function will install a interrupt service routine to a interrupt.
* @param vector the interrupt number
* @param handler the interrupt service routine to be installed
* @param param the parameter for interrupt service routine
* @name unused.
*
* @return the old handler
*/
rt_isr_handler_t rt_hw_interrupt_install(int vector, rt_isr_handler_t handler,
void *param, char *name)
{
rt_uint32_t *vect_addr;
if(vector < MAX_HANDLERS)
rt_isr_handler_t old_handler = RT_NULL;
if(vector >= 0 && vector < MAX_HANDLERS)
{
/* find first un-assigned VIC address for the handler */
vect_addr = (rt_uint32_t *)(VIC_BASE_ADDR + 0x100 + vector*4);
/* get old handler */
if (old_handler != RT_NULL) *old_handler = (rt_isr_handler_t)*vect_addr;
*vect_addr = (rt_uint32_t)new_handler; /* set interrupt vector */
old_handler = irq_desc[vector].handler;
if (handler != RT_NULL)
{
irq_desc[vector].handler = handler;
irq_desc[vector].param = param;
}
}
return old_handler;
}
/*@}*/

View File

@ -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");
}

View File

@ -10,9 +10,11 @@
* Change Logs:
* Date Author Notes
* 2006-03-13 Bernard first version
* 2013-03-29 aozima Modify the interrupt interface implementations.
*/
#include <rtthread.h>
#include <rthw.h>
#include "s3c24x0.h"
#define MAX_HANDLERS 32
@ -20,7 +22,7 @@
extern rt_uint32_t rt_interrupt_nest;
/* exception and interrupt handler table */
rt_isr_handler_t isr_table[MAX_HANDLERS];
struct rt_irq_desc isr_table[MAX_HANDLERS];
rt_uint32_t rt_interrupt_from_thread, rt_interrupt_to_thread;
rt_uint32_t rt_thread_switch_interrupt_flag;
@ -29,10 +31,9 @@ rt_uint32_t rt_thread_switch_interrupt_flag;
*/
/*@{*/
rt_isr_handler_t rt_hw_interrupt_handle(rt_uint32_t vector)
static void rt_hw_interrupt_handle(int vector, void *param)
{
rt_kprintf("Unhandled interrupt %d occured!!!\n", vector);
return RT_NULL;
}
/**
@ -40,37 +41,38 @@ rt_isr_handler_t rt_hw_interrupt_handle(rt_uint32_t vector)
*/
void rt_hw_interrupt_init(void)
{
register rt_uint32_t idx;
register rt_uint32_t idx;
/* all clear source pending */
SRCPND = 0x0;
/* all clear source pending */
SRCPND = 0x0;
/* all clear sub source pending */
SUBSRCPND = 0x0;
/* all clear sub source pending */
SUBSRCPND = 0x0;
/* all=IRQ mode */
INTMOD = 0x0;
/* all=IRQ mode */
INTMOD = 0x0;
/* all interrupt disabled include global bit */
INTMSK = BIT_ALLMSK;
/* all interrupt disabled include global bit */
INTMSK = BIT_ALLMSK;
/* all sub interrupt disable */
INTSUBMSK = BIT_SUB_ALLMSK;
/* all sub interrupt disable */
INTSUBMSK = BIT_SUB_ALLMSK;
/* all clear interrupt pending */
INTPND = BIT_ALLMSK;
/* all clear interrupt pending */
INTPND = BIT_ALLMSK;
/* init exceptions table */
for(idx=0; idx < MAX_HANDLERS; idx++)
{
isr_table[idx] = (rt_isr_handler_t)rt_hw_interrupt_handle;
}
/* init exceptions table */
rt_memset(isr_table, 0x00, sizeof(isr_table));
for(idx=0; idx < MAX_HANDLERS; idx++)
{
isr_table[idx].handler = rt_hw_interrupt_handle;
}
/* init interrupt nest, and context in thread sp */
rt_interrupt_nest = 0;
rt_interrupt_from_thread = 0;
rt_interrupt_to_thread = 0;
rt_thread_switch_interrupt_flag = 0;
/* init interrupt nest, and context in thread sp */
rt_interrupt_nest = 0;
rt_interrupt_from_thread = 0;
rt_interrupt_to_thread = 0;
rt_thread_switch_interrupt_flag = 0;
}
/**
@ -105,13 +107,26 @@ void rt_hw_interrupt_umask(int vector)
* @param new_handler the interrupt service routine to be installed
* @param old_handler the old interrupt service routine
*/
void rt_hw_interrupt_install(int vector, rt_isr_handler_t new_handler, rt_isr_handler_t *old_handler)
rt_isr_handler_t rt_hw_interrupt_install(int vector, rt_isr_handler_t handler,
void *param, char *name)
{
if(vector < MAX_HANDLERS)
{
if (old_handler != RT_NULL) *old_handler = isr_table[vector];
if (new_handler != RT_NULL) isr_table[vector] = new_handler;
}
rt_isr_handler_t old_handler = RT_NULL;
if(vector < MAX_HANDLERS)
{
old_handler = isr_table[vector].handler;
if (handler != RT_NULL)
{
#ifdef RT_USING_INTERRUPT_INFO
rt_strncpy(isr_table[vector].name, name, RT_NAME_MAX);
#endif /* RT_USING_INTERRUPT_INFO */
isr_table[vector].handler = handler;
isr_table[vector].param = param;
}
}
return old_handler;
}
/*@}*/

View File

@ -12,6 +12,7 @@
* 2006-03-13 Bernard first version
* 2006-05-27 Bernard add skyeye support
* 2007-11-19 Yi.Qiu fix rt_hw_trap_irq function
* 2013-03-29 aozima Modify the interrupt interface implementations.
*/
#include <rtthread.h>
@ -140,29 +141,35 @@ void rt_hw_trap_resv(struct rt_hw_register *regs)
rt_hw_cpu_shutdown();
}
extern rt_isr_handler_t isr_table[];
extern struct rt_irq_desc isr_table[];
void rt_hw_trap_irq()
void rt_hw_trap_irq(void)
{
unsigned long intstat;
rt_isr_handler_t isr_func;
unsigned long irq;
rt_isr_handler_t isr_func;
void *param;
intstat = INTOFFSET;
irq = INTOFFSET;
if (intstat == INTGLOBAL) return;
if (irq == INTGLOBAL) return;
/* get interrupt service routine */
isr_func = isr_table[intstat];
/* get interrupt service routine */
isr_func = isr_table[irq].handler;
param = isr_table[irq].param;
/* turn to interrupt service routine */
isr_func(intstat);
/* turn to interrupt service routine */
isr_func(irq, param);
/* clear pending register */
/* note: must be the last, if not, may repeat*/
ClearPending(1 << intstat);
/* clear pending register */
/* note: must be the last, if not, may repeat*/
ClearPending(1 << irq);
#ifdef RT_USING_INTERRUPT_INFO
isr_table[irq].counter++;
#endif /* RT_USING_INTERRUPT_INFO */
}
void rt_hw_trap_fiq()
void rt_hw_trap_fiq(void)
{
rt_kprintf("fast interrupt request\n");
}

View File

@ -10,9 +10,11 @@
* Change Logs:
* Date Author Notes
* 2006-03-13 Bernard first version
* 2013-03-29 aozima Modify the interrupt interface implementations.
*/
#include <rtthread.h>
#include <rthw.h>
#include <sep4020.h>
#define MAX_HANDLERS 32
@ -20,7 +22,7 @@
extern rt_uint32_t rt_interrupt_nest;
/* exception and interrupt handler table */
rt_isr_handler_t isr_table[MAX_HANDLERS];
struct rt_irq_desc isr_table[MAX_HANDLERS];
rt_uint32_t rt_interrupt_from_thread, rt_interrupt_to_thread;
rt_uint32_t rt_thread_switch_interrupt_flag;
@ -38,44 +40,45 @@ rt_isr_handler_t rt_hw_interrupt_handle(rt_uint32_t vector)
/**
* This function will initialize hardware interrupt
*/
void rt_hw_interrupt_init()
void rt_hw_interrupt_init(void)
{
register rt_uint32_t idx;
register rt_uint32_t idx;
/*Make sure all intc registers in proper state*/
/*Make sure all intc registers in proper state*/
/*mask all the irq*/
*(RP)(INTC_IMR) = 0xFFFFFFFF;
/*mask all the irq*/
*(RP)(INTC_IMR) = 0xFFFFFFFF;
/*enable all the irq*/
*(RP)(INTC_IER) = 0XFFFFFFFF;
/*enable all the irq*/
*(RP)(INTC_IER) = 0XFFFFFFFF;
/*Dont use any forced irq*/
*(RP)(INTC_IFR) = 0x0;
/*Dont use any forced irq*/
*(RP)(INTC_IFR) = 0x0;
/*Disable all the fiq*/
*(RP)(INTC_FIER) = 0x0;
/*Disable all the fiq*/
*(RP)(INTC_FIER) = 0x0;
/*Mask all the fiq*/
*(RP)(INTC_FIMR) = 0x0F;
/*Mask all the fiq*/
*(RP)(INTC_FIMR) = 0x0F;
/*Dont use forced fiq*/
*(RP)(INTC_FIFR) = 0x0;
/*Dont use forced fiq*/
*(RP)(INTC_FIFR) = 0x0;
/*Intrrupt priority register*/
*(RP)(INTC_IPLR) = 0x0;
/*Intrrupt priority register*/
*(RP)(INTC_IPLR) = 0x0;
/* init exceptions table */
for(idx=0; idx < MAX_HANDLERS; idx++)
{
isr_table[idx] = (rt_isr_handler_t)rt_hw_interrupt_handle;
}
/* init exceptions table */
rt_memset(isr_table, 0x00, sizeof(isr_table));
for(idx=0; idx < MAX_HANDLERS; idx++)
{
isr_table[idx].handler = rt_hw_interrupt_handle;
}
/* init interrupt nest, and context in thread sp */
rt_interrupt_nest = 0;
rt_interrupt_from_thread = 0;
rt_interrupt_to_thread = 0;
rt_thread_switch_interrupt_flag = 0;
/* init interrupt nest, and context in thread sp */
rt_interrupt_nest = 0;
rt_interrupt_from_thread = 0;
rt_interrupt_to_thread = 0;
rt_thread_switch_interrupt_flag = 0;
}
/**
@ -108,15 +111,26 @@ void rt_hw_interrupt_umask(rt_uint32_t vector)
* @param new_handler the interrupt service routine to be installed
* @param old_handler the old interrupt service routine
*/
void rt_hw_interrupt_install(rt_uint32_t vector, rt_isr_handler_t new_handler, rt_isr_handler_t *old_handler)
rt_isr_handler_t rt_hw_interrupt_install(int vector, rt_isr_handler_t handler,
void *param, char *name)
{
if(vector < MAX_HANDLERS)
{
if (*old_handler != RT_NULL)
*old_handler = isr_table[vector];
if (new_handler != RT_NULL)
isr_table[vector] = new_handler;
}
rt_isr_handler_t old_handler = RT_NULL;
if(vector < MAX_HANDLERS)
{
old_handler = isr_table[vector].handler;
if (handler != RT_NULL)
{
#ifdef RT_USING_INTERRUPT_INFO
rt_strncpy(isr_table[vector].name, name, RT_NAME_MAX);
#endif /* RT_USING_INTERRUPT_INFO */
isr_table[vector].handler = handler;
isr_table[vector].param = param;
}
}
return old_handler;
}
/*@}*/

View File

@ -12,6 +12,7 @@
* 2006-03-13 Bernard first version
* 2006-05-27 Bernard add skyeye support
* 2007-11-19 Yi.Qiu fix rt_hw_trap_irq function
* 2013-03-29 aozima Modify the interrupt interface implementations.
*/
#include <rtthread.h>
@ -131,31 +132,38 @@ void rt_hw_trap_resv(struct rt_hw_register *regs)
rt_hw_cpu_shutdown();
}
extern rt_isr_handler_t isr_table[];
extern struct rt_irq_desc isr_table[];
void rt_hw_trap_irq()
void rt_hw_trap_irq(void)
{
unsigned long intstat;
rt_uint32_t i = 0;
rt_isr_handler_t isr_func;
unsigned long intstat;
rt_uint32_t irq = 0;
rt_isr_handler_t isr_func;
void *param;
/*Get the final intrrupt source*/
intstat = *(RP)(INTC_IFSR);;
/*Get the final intrrupt source*/
intstat = *(RP)(INTC_IFSR);;
/*Shift to get the intrrupt number*/
while(intstat != 1)
{
intstat = intstat >> 1;
i++;
}
/* get interrupt service routine */
isr_func = isr_table[i];
/*Shift to get the intrrupt number*/
while(intstat != 1)
{
intstat = intstat >> 1;
irq++;
}
/* turn to interrupt service routine */
isr_func(i);
/* get interrupt service routine */
isr_func = isr_table[irq].isr_handle;
param = isr_table[irq].param;
/* turn to interrupt service routine */
isr_func(irq, param);
#ifdef RT_USING_INTERRUPT_INFO
isr_table[irq].counter++;
#endif /* RT_USING_INTERRUPT_INFO */
}
void rt_hw_trap_fiq()
void rt_hw_trap_fiq(void)
{
rt_kprintf("fast interrupt request\n");
}

View File

@ -11,7 +11,7 @@
* Date Author Notes
* 2010-07-09 Bernard first version
*/
#include <rtthread.h>
#include <rthw.h>
#include "jz47xx.h"
#define JZ47XX_MAX_INTR 32
@ -20,7 +20,7 @@ extern rt_uint32_t rt_interrupt_nest;
rt_uint32_t rt_interrupt_from_thread, rt_interrupt_to_thread;
rt_uint32_t rt_thread_switch_interrupt_flag;
static rt_isr_handler_t irq_handle_table[JZ47XX_MAX_INTR];
static struct rt_irq_desc irq_handle_table[JZ47XX_MAX_INTR];
/**
* @addtogroup Jz47xx
@ -39,9 +39,10 @@ void rt_hw_interrupt_init()
{
rt_int32_t index;
rt_memset(irq_handle_table, 0x00, sizeof(irq_handle_table));
for (index = 0; index < JZ47XX_MAX_INTR; index ++)
{
irq_handle_table[index] = (rt_isr_handler_t)rt_hw_interrupt_handler;
irq_handle_table[index].handler = (rt_isr_handler_t)rt_hw_interrupt_handler;
}
/* init interrupt nest, and context in thread sp */
@ -73,18 +74,30 @@ void rt_hw_interrupt_umask(int vector)
/**
* This function will install a interrupt service routine to a interrupt.
* @param vector the interrupt number
* @param new_handler the interrupt service routine to be installed
* @param old_handler the old interrupt service routine
* @param handler the interrupt service routine to be installed
* @param param the interrupt service function parameter
* @param name the interrupt name
* @return old handler
*/
void rt_hw_interrupt_install(int vector, rt_isr_handler_t new_handler, rt_isr_handler_t *old_handler)
rt_isr_handler_t rt_hw_interrupt_install(int vector,
rt_isr_handler_t handler,
void *param,
char *name)
{
rt_isr_handler_t old_handler = RT_NULL;
if (vector >= 0 && vector < JZ47XX_MAX_INTR)
{
if (old_handler != RT_NULL)
*old_handler = irq_handle_table[vector];
if (new_handler != RT_NULL)
irq_handle_table[vector] = (rt_isr_handler_t)new_handler;
old_handler = irq_handle_table[vector].handler;
#ifdef RT_USING_INTERRUPT_INFO
rt_strncpy(irq_handle_table[vector].name, name, RT_NAME_MAX);
#endif /* RT_USING_INTERRUPT_INFO */
irq_handle_table[vector].handler = handler;
irq_handle_table[vector].param = param;
}
return old_handler;
}
void rt_interrupt_dispatch(void *ptreg)
@ -102,10 +115,14 @@ void rt_interrupt_dispatch(void *ptreg)
if ((pending & (1<<i)))
{
pending &= ~(1<<i);
irq_func = irq_handle_table[i];
irq_func = irq_handle_table[i].handler;
/* do interrupt */
(*irq_func)(i);
(*irq_func)(i, irq_handle_table[i].param);
#ifdef RT_USING_INTERRUPT_INFO
irq_handle_table[i].counter++;
#endif /* RT_USING_INTERRUPT_INFO */
/* ack interrupt */
INTC_IPR = (1 << i);

View File

@ -10,8 +10,11 @@
* Change Logs:
* Date Author Notes
* 2010-10-15 Bernard first version
* 2013-03-29 aozima Modify the interrupt interface implementations.
*/
#include <rtthread.h>
#include <rthw.h>
#include "soc3210.h"
#define MAX_INTR 32
@ -20,17 +23,17 @@ extern rt_uint32_t rt_interrupt_nest;
rt_uint32_t rt_interrupt_from_thread, rt_interrupt_to_thread;
rt_uint32_t rt_thread_switch_interrupt_flag;
static rt_isr_handler_t irq_handle_table[MAX_INTR];
static struct rt_irq_desc irq_handle_table[MAX_INTR];
void rt_interrupt_dispatch(void *ptreg);
void rt_hw_timer_handler();
/**
* @addtogroup Loongson SoC3210
*/
/*@{*/
void rt_hw_interrupt_handler(int vector)
static void rt_hw_interrupt_handler(int vector, void *param)
{
rt_kprintf("Unhandled interrupt %d occured!!!\n", vector);
}
@ -40,11 +43,12 @@ void rt_hw_interrupt_handler(int vector)
*/
void rt_hw_interrupt_init(void)
{
rt_int32_t index;
rt_int32_t idx;
for (index = 0; index < MAX_INTR; index ++)
rt_memset(irq_handle_table, 0x00, sizeof(irq_handle_table));
for (idx = 0; idx < MAX_INTR; idx ++)
{
irq_handle_table[index] = (rt_isr_handler_t)rt_hw_interrupt_handler;
irq_handle_table[idx].handler = rt_hw_interrupt_handler;
}
/* init interrupt nest, and context in thread sp */
@ -79,52 +83,70 @@ void rt_hw_interrupt_umask(int vector)
* @param new_handler the interrupt service routine to be installed
* @param old_handler the old interrupt service routine
*/
void rt_hw_interrupt_install(int vector, rt_isr_handler_t new_handler, rt_isr_handler_t *old_handler)
rt_isr_handler_t rt_hw_interrupt_install(int vector, rt_isr_handler_t handler,
void *param, char *name)
{
if (vector >= 0 && vector < MAX_INTR)
{
if (old_handler != RT_NULL)
*old_handler = irq_handle_table[vector];
if (new_handler != RT_NULL)
irq_handle_table[vector] = (rt_isr_handler_t)new_handler;
}
rt_isr_handler_t old_handler = RT_NULL;
if(vector < MAX_INTR)
{
old_handler = irq_handle_table[vector].handler;
if (handler != RT_NULL)
{
#ifdef RT_USING_INTERRUPT_INFO
rt_strncpy(irq_handle_table[vector].name, name, RT_NAME_MAX);
#endif /* RT_USING_INTERRUPT_INFO */
irq_handle_table[vector].handler = handler;
irq_handle_table[vector].param = param;
}
}
return old_handler;
}
void rt_interrupt_dispatch(void *ptreg)
{
int i;
rt_isr_handler_t irq_func;
static rt_uint32_t status = 0;
rt_uint32_t c0_status;
int irq;
void *param;
rt_isr_handler_t irq_func;
static rt_uint32_t status = 0;
rt_uint32_t c0_status;
/* check os timer */
c0_status = read_c0_status();
if (c0_status & 0x8000)
{
rt_hw_timer_handler();
}
/* check os timer */
c0_status = read_c0_status();
if (c0_status & 0x8000)
{
rt_hw_timer_handler();
}
if (c0_status & 0x0400)
{
/* the hardware interrupt */
status |= INT_ISR;
if (!status) return;
if (c0_status & 0x0400)
{
/* the hardware interrupt */
status |= INT_ISR;
if (!status) return;
for (i = MAX_INTR; i > 0; --i)
{
if ((status & (1<<i)))
{
status &= ~(1<<i);
irq_func = irq_handle_table[i];
for (irq = MAX_INTR; irq > 0; --irq)
{
if ((status & (1 << irq)))
{
status &= ~(1 << irq);
/* do interrupt */
(*irq_func)(i);
irq_func = irq_handle_table[irq].handler;
param = irq_handle_table[irq].param;
/* ack interrupt */
INT_CLR = (1 << i);
}
}
}
/* do interrupt */
(*irq_func)(irq, param);
#ifdef RT_USING_INTERRUPT_INFO
irq_handle_table[irq].counter++;
#endif /* RT_USING_INTERRUPT_INFO */
/* ack interrupt */
INT_CLR = (1 << irq);
}
}
}
}
/*@}*/

View File

@ -11,9 +11,11 @@
* Date Author Notes
* 2010-10-15 Bernard first version
* 2010-10-15 lgnq modified for LS1B
* 2013-03-29 aozima Modify the interrupt interface implementations.
*/
#include <rtthread.h>
#include <rthw.h>
#include "ls1b.h"
#define MAX_INTR 32
@ -23,7 +25,7 @@ rt_uint32_t rt_interrupt_from_thread;
rt_uint32_t rt_interrupt_to_thread;
rt_uint32_t rt_thread_switch_interrupt_flag;
static rt_isr_handler_t irq_handle_table[MAX_INTR];
static struct rt_irq_desc irq_handle_table[MAX_INTR];
void rt_interrupt_dispatch(void *ptreg);
void rt_hw_timer_handler();
@ -36,7 +38,7 @@ static struct ls1b_intc_regs volatile *ls1b_hw0_icregs
/*@{*/
void rt_hw_interrupt_handler(int vector)
static void rt_hw_interrupt_handler(int vector, void *param)
{
rt_kprintf("Unhandled interrupt %d occured!!!\n", vector);
}
@ -46,7 +48,7 @@ void rt_hw_interrupt_handler(int vector)
*/
void rt_hw_interrupt_init(void)
{
rt_int32_t index;
rt_int32_t idx;
/* pci active low */
ls1b_hw0_icregs->int_pol = -1; //must be done here 20110802 lgnq
@ -55,9 +57,10 @@ void rt_hw_interrupt_init(void)
/* mask all interrupts */
(ls1b_hw0_icregs+0)->int_clr = 0xffffffff;
for (index = 0; index < MAX_INTR; index ++)
rt_memset(irq_handle_table, 0x00, sizeof(irq_handle_table));
for (idx = 0; idx < MAX_INTR; idx ++)
{
irq_handle_table[index] = (rt_isr_handler_t)rt_hw_interrupt_handler;
irq_handle_table[idx].handler = rt_hw_interrupt_handler;
}
/* init interrupt nest, and context in thread sp */
@ -92,20 +95,32 @@ void rt_hw_interrupt_umask(int vector)
* @param new_handler the interrupt service routine to be installed
* @param old_handler the old interrupt service routine
*/
void rt_hw_interrupt_install(int vector, rt_isr_handler_t new_handler, rt_isr_handler_t *old_handler)
rt_isr_handler_t rt_hw_interrupt_install(int vector, rt_isr_handler_t handler,
void *param, char *name)
{
rt_isr_handler_t old_handler = RT_NULL;
if (vector >= 0 && vector < MAX_INTR)
{
if (old_handler != RT_NULL)
*old_handler = irq_handle_table[vector];
if (new_handler != RT_NULL)
irq_handle_table[vector] = (rt_isr_handler_t)new_handler;
}
old_handler = irq_handle_table[vector].handler;
if (handler != RT_NULL)
{
#ifdef RT_USING_INTERRUPT_INFO
rt_strncpy(irq_handle_table[vector].name, name, RT_NAME_MAX);
#endif /* RT_USING_INTERRUPT_INFO */
irq_handle_table[vector].handler = handler;
irq_handle_table[vector].param = param;
}
}
return old_handler;
}
void rt_interrupt_dispatch(void *ptreg)
{
int i;
int irq;
void *param;
rt_isr_handler_t irq_func;
static rt_uint32_t status = 0;
rt_uint32_t c0_status;
@ -134,18 +149,24 @@ void rt_interrupt_dispatch(void *ptreg)
if (!status)
return;
for (i = MAX_INTR; i > 0; --i)
for (irq = MAX_INTR; irq > 0; --irq)
{
if ((status & (1<<i)))
if ((status & (1 << irq)))
{
status &= ~(1<<i);
irq_func = irq_handle_table[i];
status &= ~(1 << irq);
irq_func = irq_handle_table[irq].handler;
param = irq_handle_table[irq].param;
/* do interrupt */
(*irq_func)(i);
(*irq_func)(irq, param);
#ifdef RT_USING_INTERRUPT_INFO
irq_handle_table[irq].counter++;
#endif /* RT_USING_INTERRUPT_INFO */
/* ack interrupt */
ls1b_hw0_icregs->int_clr |= (1 << i);
ls1b_hw0_icregs->int_clr |= (1 << irq);
}
}
}

View File

@ -12,7 +12,7 @@
* 2009-01-05 Bernard first version
*/
#include <rtthread.h>
#include <rthw.h>
#include <asm/ppc4xx.h>
#include <asm/processor.h>
@ -21,12 +21,12 @@ extern volatile rt_uint8_t rt_interrupt_nest;
/* exception and interrupt handler table */
#define MAX_HANDLERS 32
rt_isr_handler_t isr_table[MAX_HANDLERS];
struct rt_irq_desc isr_table[MAX_HANDLERS];
rt_uint32_t rt_interrupt_from_thread, rt_interrupt_to_thread;
rt_uint32_t rt_thread_switch_interrput_flag;
rt_isr_handler_t rt_hw_interrupt_handle(rt_uint32_t vector)
rt_isr_handler_t rt_hw_interrupt_handler(rt_uint32_t vector, void* param)
{
rt_kprintf("Unhandled interrupt %d occured!!!\n", vector);
return RT_NULL;
@ -42,9 +42,9 @@ void uic_int_handler (unsigned int vec)
rt_interrupt_enter();
/* Allow external interrupts to the CPU. */
if (isr_table [vec] != 0)
if (isr_table [vec].handler != 0)
{
(*isr_table[vec])(vec);
(*isr_table[vec].handler)(vec, isr_table[vec].param);
}
uic_irq_ack(vec);
@ -78,21 +78,24 @@ void uic_interrupt(rt_uint32_t uic_base, int vec_base)
}
}
void rt_hw_interrupt_install(int vector, rt_isr_handler_t new_handler, rt_isr_handler_t *old_handler)
rt_isr_handler_t rt_hw_interrupt_install(int vector, rt_isr_handler_t new_handler,
void* param, char* name)
{
int intVal;
rt_isr_handler_t old_handler;
if (((int)vector < 0) || ((int) vector >= MAX_HANDLERS))
{
return; /* out of range */
return RT_NULL; /* out of range */
}
/* install the handler in the system interrupt table */
intVal = rt_hw_interrupt_disable (); /* lock interrupts to prevent races */
if (*old_handler != RT_NULL) *old_handler = isr_table[vector];
if (new_handler != RT_NULL) isr_table[vector] = new_handler;
old_handler = isr_table[vector].handler;
isr_table[vector].handler = new_handler;
isr_table[vector].param = param;
rt_hw_interrupt_enable (intVal);
}
@ -120,7 +123,8 @@ void rt_hw_interrupt_init()
/* set default interrupt handler */
for (vector = 0; vector < MAX_HANDLERS; vector++)
{
isr_table [vector] = (rt_isr_handler_t)rt_hw_interrupt_handle;
isr_table [vector].handler = (rt_isr_handler_t)rt_hw_interrupt_handler;
isr_table [vector].param = RT_NULL;
}
/* initialize interrupt nest, and context in thread sp */

View File

@ -220,12 +220,12 @@ void rt_serial_set_baudrate(struct rt_ppc405_serial* device)
out_8((rt_uint8_t *)device->hw_base + UART_DLM, bdiv >> 8); /* set baudrate divisor */
}
void rt_serial_isr(int irqno)
void rt_serial_isr(int irqno, void* param)
{
unsigned char status;
struct rt_ppc405_serial *device;
device = (struct rt_ppc405_serial*) &ppc405_serial;
device = (struct rt_ppc405_serial*) param;
status = in_8((rt_uint8_t *)device->hw_base + UART_LSR);
if (status & 0x01)
@ -289,7 +289,7 @@ void rt_hw_serial_init(void)
device->hw_base = UART0_BASE;
device->baudrate = 115200;
device->irqno = VECNUM_U0;
rt_hw_interrupt_install(device->irqno, rt_serial_isr, RT_NULL); /* install isr */
rt_hw_interrupt_install(device->irqno, rt_serial_isr, device, "serial"); /* install isr */
rt_memset(device->rx_buffer, 0, sizeof(device->rx_buffer));
device->read_index = device->save_index = 0;

View File

@ -1190,6 +1190,54 @@ void rt_free_align(void *ptr)
RTM_EXPORT(rt_free_align);
#endif
#ifndef RT_USING_CPU_FFS
const rt_uint8_t __lowest_bit_bitmap[] =
{
/* 00 */ 0, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* 10 */ 4, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* 20 */ 5, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* 30 */ 4, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* 40 */ 6, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* 50 */ 4, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* 60 */ 5, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* 70 */ 4, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* 80 */ 7, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* 90 */ 4, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* A0 */ 5, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* B0 */ 4, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* C0 */ 6, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* D0 */ 4, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* E0 */ 5, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* F0 */ 4, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0
};
/**
* This function finds the first bit set (beginning with the least significant bit)
* in value and return the index of that bit.
*
* Bits are numbered starting at 1 (the least significant bit). A return value of
* zero from any of these functions means that the argument was zero.
*
* @return return the index of the first bit set. If value is 0, then this function
* shall return 0.
*/
int __rt_ffs(int value)
{
if (value == 0) return 0;
if (value & 0xff)
return __lowest_bit_bitmap[value & 0xff] + 1;
if (value & 0xff00)
return __lowest_bit_bitmap[(value & 0xff00) >> 8] + 9;
if (value & 0xff0000)
return __lowest_bit_bitmap[(value & 0xff0000) >> 16] + 17;
return __lowest_bit_bitmap[(value & 0xff000000) >> 24] + 25;
}
#endif
#if !defined (RT_USING_NEWLIB) && defined (RT_USING_MINILIBC) && defined (__GNUC__)
#include <sys/types.h>
void *memcpy(void *dest, const void *src, size_t n) __attribute__((weak, alias("rt_memcpy")));

View File

@ -31,6 +31,7 @@
static rt_int16_t rt_scheduler_lock_nest;
extern volatile rt_uint8_t rt_interrupt_nest;
extern int __rt_ffs(int value);
rt_list_t rt_thread_priority_table[RT_THREAD_PRIORITY_MAX];
struct rt_thread *rt_current_thread;
@ -48,26 +49,6 @@ rt_uint32_t rt_thread_ready_priority_group;
rt_list_t rt_thread_defunct;
const rt_uint8_t rt_lowest_bitmap[] =
{
/* 00 */ 0, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* 10 */ 4, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* 20 */ 5, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* 30 */ 4, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* 40 */ 6, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* 50 */ 4, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* 60 */ 5, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* 70 */ 4, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* 80 */ 7, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* 90 */ 4, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* A0 */ 5, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* B0 */ 4, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* C0 */ 6, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* D0 */ 4, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* E0 */ 5, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0,
/* F0 */ 4, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0
};
#ifdef RT_USING_HOOK
static void (*rt_scheduler_hook)(struct rt_thread *from, struct rt_thread *to);
@ -164,34 +145,13 @@ void rt_system_scheduler_start(void)
register struct rt_thread *to_thread;
register rt_ubase_t highest_ready_priority;
#if RT_THREAD_PRIORITY_MAX == 8
highest_ready_priority = rt_lowest_bitmap[rt_thread_ready_priority_group];
#else
register rt_ubase_t number;
/* find out the highest priority task */
if (rt_thread_ready_priority_group & 0xff)
{
number = rt_lowest_bitmap[rt_thread_ready_priority_group & 0xff];
}
else if (rt_thread_ready_priority_group & 0xff00)
{
number = rt_lowest_bitmap[(rt_thread_ready_priority_group >> 8) & 0xff] + 8;
}
else if (rt_thread_ready_priority_group & 0xff0000)
{
number = rt_lowest_bitmap[(rt_thread_ready_priority_group >> 16) & 0xff] + 16;
}
else
{
number = rt_lowest_bitmap[(rt_thread_ready_priority_group >> 24) & 0xff] + 24;
}
#if RT_THREAD_PRIORITY_MAX > 32
highest_ready_priority = (number << 3) +
rt_lowest_bitmap[rt_thread_ready_table[number]];
register rt_ubase_t number;
number = __rt_ffs(rt_thread_ready_priority_group) - 1;
highest_ready_priority = (number << 3) + __rt_ffs(rt_thread_ready_table[number]) - 1;
#else
highest_ready_priority = number;
#endif
highest_ready_priority = __rt_ffs(rt_thread_ready_priority_group) - 1;
#endif
/* get switch to thread */
@ -231,35 +191,15 @@ void rt_schedule(void)
{
register rt_ubase_t highest_ready_priority;
#if RT_THREAD_PRIORITY_MAX == 8
highest_ready_priority = rt_lowest_bitmap[rt_thread_ready_priority_group];
#if RT_THREAD_PRIORITY_MAX <= 32
highest_ready_priority = __rt_ffs(rt_thread_ready_priority_group) - 1;
#else
register rt_ubase_t number;
/* find out the highest priority task */
if (rt_thread_ready_priority_group & 0xff)
{
number = rt_lowest_bitmap[rt_thread_ready_priority_group & 0xff];
}
else if (rt_thread_ready_priority_group & 0xff00)
{
number = rt_lowest_bitmap[(rt_thread_ready_priority_group >> 8) & 0xff] + 8;
}
else if (rt_thread_ready_priority_group & 0xff0000)
{
number = rt_lowest_bitmap[(rt_thread_ready_priority_group >> 16) & 0xff] + 16;
}
else
{
number = rt_lowest_bitmap[(rt_thread_ready_priority_group >> 24) & 0xff] + 24;
}
#if RT_THREAD_PRIORITY_MAX > 32
highest_ready_priority = (number << 3) +
rt_lowest_bitmap[rt_thread_ready_table[number]];
#else
highest_ready_priority = number;
#endif
number = __rt_ffs(rt_thread_ready_priority_group) - 1;
highest_ready_priority = (number << 3) + __rt_ffs(rt_thread_ready_table[number]) - 1;
#endif
/* get switch to thread */
to_thread = rt_list_entry(rt_thread_priority_table[highest_ready_priority].next,
struct rt_thread,