浏览代码

Merge remote-tracking branch 'china/master'

Bernard Xiong 10 年之前
父节点
当前提交
1512da3b03

+ 6 - 2
bsp/realview-a8/SConstruct

@@ -31,8 +31,12 @@ if GetDepend('RT_USING_VMM'):
                   ldfile = rtconfig.LINK_SCRIPT)) != 0:
         print 'failed to generate linker script %s' % rtconfig.LINK_SCRIPT
         sys.exit(255)
-# if the linker script changed, relink the target
-Depends(TARGET, rtconfig.LINK_SCRIPT)
+    # if the linker script changed, relink the target
+    Depends(TARGET, rtconfig.LINK_SCRIPT)
+else:
+    # we should use none-vmm link script
+    link_flags = str(env['LINKFLAGS'])
+    env['LINKFLAGS'] = link_flags.replace('_vmm.lds', '.lds')
 
 # make a building
 DoBuilding(TARGET, objs)

+ 6 - 20
bsp/realview-a8/applications/application.c

@@ -15,32 +15,18 @@
 #include <rtthread.h>
 #include <components.h>
 
-#include <pthread.h>
-
-void *test_task(void *parameter)
+void init_thread(void* parameter)
 {
-    int count = 0;
-
-    while (1)
-    {
-        rt_thread_delay(RT_TICK_PER_SECOND);
-        rt_kprintf("count = %d\n", count ++);
-    }
-
-    return RT_NULL;
+    rt_components_init();
 }
 
 int rt_application_init()
 {
-    // pthread_t tid;
-
-    /* do component initialization */
-    rt_components_init();
-#ifdef RT_USING_NEWLIB
-    libc_system_init(RT_CONSOLE_DEVICE_NAME);
-#endif
+    rt_thread_t tid;
 
-    // pthread_create(&tid, RT_NULL, test_task, RT_NULL);
+    tid = rt_thread_create("init", init_thread, RT_NULL, 
+        1024, RT_THREAD_PRIORITY_MAX/3, 10);
+    if (tid != RT_NULL) rt_thread_startup(tid);
 
     return 0;
 }

+ 4 - 4
bsp/realview-a8/drivers/board.c

@@ -38,11 +38,11 @@
 #define SYS_CTRL                         __REG32(REALVIEW_SCTL_BASE)
 
 #ifdef RT_USING_VMM
- #include <vmm.h>
- static rt_uint32_t timer_hw_base = 0;
- #define TIMER_HW_BASE                  (timer_hw_base)
+#include <vmm.h>
+static rt_uint32_t timer_hw_base = 0;
+#define TIMER_HW_BASE                  (timer_hw_base)
 #else
- #define TIMER_HW_BASE                  REALVIEW_TIMER2_3_BASE
+#define TIMER_HW_BASE                  REALVIEW_TIMER2_3_BASE
 #endif
 
 void rt_hw_timer_ack(void)

+ 4 - 4
bsp/realview-a8/drivers/serial.c

@@ -32,7 +32,7 @@
 
 #include "serial.h"
 #ifdef RT_USING_VMM
- #include <vmm.h>
+#include <vmm.h>
 #endif
 
 struct hw_uart_device
@@ -165,8 +165,8 @@ int rt_hw_uart_init(void)
     config.parity    = PARITY_NONE;
     config.stop_bits = STOP_BITS_1;
     config.invert    = NRZ_NORMAL;
-	config.bufsz     = RT_SERIAL_RB_BUFSZ;
-	
+    config.bufsz     = RT_SERIAL_RB_BUFSZ;
+
 #ifdef RT_USING_UART0
     uart = &_uart0_device;
 #ifdef RT_USING_VMM
@@ -194,7 +194,7 @@ int rt_hw_uart_init(void)
 
     /* register UART1 device */
     rt_hw_serial_register(&_serial1, "uart1",
-        RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX, uart);
+                          RT_DEVICE_FLAG_RDWR | RT_DEVICE_FLAG_INT_RX, uart);
     /* enable Rx and Tx of UART */
     UART_CR(uart->hw_base) = (1 << 0) | (1 << 8) | (1 << 9);
 #endif

+ 3 - 3
bsp/realview-a8/rtconfig.h

@@ -107,8 +107,8 @@
 // </section>
 
 // <section name="LIBC" description="C Runtime library setting" default="always" >
-// <bool name="RT_USING_NEWLIB" description="Using newlib library, only available under GNU GCC" default="true" />
-#define RT_USING_NEWLIB
+// <bool name="RT_USING_LIBC" description="Using libc library" default="true" />
+#define RT_USING_LIBC
 // <bool name="RT_USING_PTHREADS" description="Using POSIX threads library" default="true" />
 #define RT_USING_PTHREADS
 // </section>
@@ -147,7 +147,7 @@
 #define RT_USING_LOGTRACE
 
 // <section name="RT_USING_VMM" description="Enable RT-Thread hypervisor" default="true" >
-#define RT_USING_VMM
+// #define RT_USING_VMM
 // </section>
 
 #endif

+ 1 - 6
bsp/realview-a8/rtconfig.py

@@ -21,8 +21,6 @@ if os.getenv('RTT_EXEC_PATH'):
 	EXEC_PATH = os.getenv('RTT_EXEC_PATH')
 
 BUILD = 'debug'
-VMM = True
-#VMM = False
 
 if PLATFORM == 'gcc':
     # toolchains
@@ -40,10 +38,7 @@ if PLATFORM == 'gcc':
     DEVICE = ' -march=armv7-a -mtune=cortex-a8 -mfpu=vfpv3-d16 -ftree-vectorize -ffast-math -mfloat-abi=softfp'
     CFLAGS = DEVICE + ' -Wall'
     AFLAGS = ' -c' + DEVICE + ' -x assembler-with-cpp -D__ASSEMBLY__'
-    if VMM:
-        LINK_SCRIPT = 'realview_vmm.lds'
-    else:
-        LINK_SCRIPT = 'realview.lds'
+    LINK_SCRIPT = 'realview_vmm.lds'
     LFLAGS = DEVICE + ' -Wl,--gc-sections,-Map=realview.map,-cref,-u,system_vectors'+\
                       ' -T %s' % LINK_SCRIPT
 

+ 13 - 13
bsp/stm32f40x/drivers/gpio.c

@@ -88,12 +88,12 @@ static const struct pin_index pins[] =
     {53, RCC_AHB1Periph_GPIOA, GPIOA, GPIO_Pin_4},
 };
 
-#define ITEM_NUM(items)	sizeof(items)/sizeof(items[0])
-const struct pin_index * get_pin(uint8_t pin)
+#define ITEM_NUM(items) sizeof(items)/sizeof(items[0])
+const struct pin_index *get_pin(uint8_t pin)
 {
-    const struct pin_index* index;
+    const struct pin_index *index;
 
-    if(pin < ITEM_NUM(pins))
+    if (pin < ITEM_NUM(pins))
     {
         index = &pins[pin];
     }
@@ -110,12 +110,12 @@ void stm32_pin_write(rt_device_t dev, rt_base_t pin, rt_base_t value)
     const struct pin_index *index;
 
     index = get_pin(pin);
-    if(index == RT_NULL)
+    if (index == RT_NULL)
     {
         return;
     }
 
-    if(value == PIN_LOW)
+    if (value == PIN_LOW)
     {
         GPIO_ResetBits(index->gpio, index->pin);
     }
@@ -133,12 +133,12 @@ int stm32_pin_read(rt_device_t dev, rt_base_t pin)
     value = PIN_LOW;
 
     index = get_pin(pin);
-    if(index == RT_NULL)
+    if (index == RT_NULL)
     {
         return value;
     }
 
-    if(GPIO_ReadInputDataBit(index->gpio, index->pin) == Bit_RESET)
+    if (GPIO_ReadInputDataBit(index->gpio, index->pin) == Bit_RESET)
     {
         value = PIN_LOW;
     }
@@ -156,7 +156,7 @@ void stm32_pin_mode(rt_device_t dev, rt_base_t pin, rt_base_t mode)
     GPIO_InitTypeDef  GPIO_InitStructure;
 
     index = get_pin(pin);
-    if(index == RT_NULL)
+    if (index == RT_NULL)
     {
         return;
     }
@@ -169,19 +169,19 @@ void stm32_pin_mode(rt_device_t dev, rt_base_t pin, rt_base_t mode)
     GPIO_InitStructure.GPIO_OType   = GPIO_OType_PP;
     GPIO_InitStructure.GPIO_Speed   = GPIO_Speed_100MHz;
 
-    if(mode == PIN_MODE_OUTPUT)
+    if (mode == PIN_MODE_OUTPUT)
     {
         /* output setting */
         GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
         GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
     }
-    else if(mode == PIN_MODE_INPUT)
+    else if (mode == PIN_MODE_INPUT)
     {
         /* input setting: not pull. */
         GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;
         GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
     }
-    else if(mode == PIN_MODE_INPUT_PULLUP)
+    else if (mode == PIN_MODE_INPUT_PULLUP)
     {
         /* input setting: pull up. */
         GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;
@@ -196,7 +196,7 @@ void stm32_pin_mode(rt_device_t dev, rt_base_t pin, rt_base_t mode)
     GPIO_Init(index->gpio, &GPIO_InitStructure);
 }
 
-const static struct rt_pin_ops _stm32_pin_ops = 
+const static struct rt_pin_ops _stm32_pin_ops =
 {
     stm32_pin_mode,
     stm32_pin_write,

+ 29 - 27
bsp/stm32f40x/drivers/usart.c

@@ -22,25 +22,25 @@
 #include <rtdevice.h>
 
 /* UART GPIO define. */
-#define UART1_GPIO_TX		GPIO_Pin_6
+#define UART1_GPIO_TX       GPIO_Pin_6
 #define UART1_TX_PIN_SOURCE GPIO_PinSource6
-#define UART1_GPIO_RX		GPIO_Pin_7
+#define UART1_GPIO_RX       GPIO_Pin_7
 #define UART1_RX_PIN_SOURCE GPIO_PinSource7
-#define UART1_GPIO			GPIOB
+#define UART1_GPIO          GPIOB
 #define UART1_GPIO_RCC      RCC_AHB1Periph_GPIOB
-#define RCC_APBPeriph_UART1	RCC_APB2Periph_USART1
-#define UART1_TX_DMA		DMA1_Channel4
-#define UART1_RX_DMA		DMA1_Channel5
+#define RCC_APBPeriph_UART1 RCC_APB2Periph_USART1
+#define UART1_TX_DMA        DMA1_Channel4
+#define UART1_RX_DMA        DMA1_Channel5
 
-#define UART2_GPIO_TX		GPIO_Pin_2
+#define UART2_GPIO_TX       GPIO_Pin_2
 #define UART2_TX_PIN_SOURCE GPIO_PinSource2
-#define UART2_GPIO_RX		GPIO_Pin_3
+#define UART2_GPIO_RX       GPIO_Pin_3
 #define UART2_RX_PIN_SOURCE GPIO_PinSource3
-#define UART2_GPIO			GPIOA
+#define UART2_GPIO          GPIOA
 #define UART2_GPIO_RCC      RCC_AHB1Periph_GPIOA
-#define RCC_APBPeriph_UART2	RCC_APB1Periph_USART2
-#define UART2_TX_DMA		DMA1_Channel4
-#define UART2_RX_DMA		DMA1_Channel5
+#define RCC_APBPeriph_UART2 RCC_APB1Periph_USART2
+#define UART2_TX_DMA        DMA1_Channel4
+#define UART2_RX_DMA        DMA1_Channel5
 
 #define UART3_GPIO_TX       GPIO_Pin_8
 #define UART3_TX_PIN_SOURCE GPIO_PinSource8
@@ -55,13 +55,13 @@
 /* STM32 uart driver */
 struct stm32_uart
 {
-    USART_TypeDef* uart_device;
+    USART_TypeDef *uart_device;
     IRQn_Type irq;
 };
 
 static rt_err_t stm32_configure(struct rt_serial_device *serial, struct serial_configure *cfg)
 {
-    struct stm32_uart* uart;
+    struct stm32_uart *uart;
     USART_InitTypeDef USART_InitStructure;
 
     RT_ASSERT(serial != RT_NULL);
@@ -89,15 +89,13 @@ static rt_err_t stm32_configure(struct rt_serial_device *serial, struct serial_c
 
     /* Enable USART */
     USART_Cmd(uart->uart_device, ENABLE);
-    /* enable interrupt */
-    USART_ITConfig(uart->uart_device, USART_IT_RXNE, ENABLE);
 
     return RT_EOK;
 }
 
 static rt_err_t stm32_control(struct rt_serial_device *serial, int cmd, void *arg)
 {
-    struct stm32_uart* uart;
+    struct stm32_uart *uart;
 
     RT_ASSERT(serial != RT_NULL);
     uart = (struct stm32_uart *)serial->parent.user_data;
@@ -107,10 +105,14 @@ static rt_err_t stm32_control(struct rt_serial_device *serial, int cmd, void *ar
     case RT_DEVICE_CTRL_CLR_INT:
         /* disable rx irq */
         UART_DISABLE_IRQ(uart->irq);
+        /* disable interrupt */
+        USART_ITConfig(uart->uart_device, USART_IT_RXNE, DISABLE);
         break;
     case RT_DEVICE_CTRL_SET_INT:
         /* enable rx irq */
         UART_ENABLE_IRQ(uart->irq);
+        /* enable interrupt */
+        USART_ITConfig(uart->uart_device, USART_IT_RXNE, ENABLE);
         break;
     }
 
@@ -119,7 +121,7 @@ static rt_err_t stm32_control(struct rt_serial_device *serial, int cmd, void *ar
 
 static int stm32_putc(struct rt_serial_device *serial, char c)
 {
-    struct stm32_uart* uart;
+    struct stm32_uart *uart;
 
     RT_ASSERT(serial != RT_NULL);
     uart = (struct stm32_uart *)serial->parent.user_data;
@@ -133,7 +135,7 @@ static int stm32_putc(struct rt_serial_device *serial, char c)
 static int stm32_getc(struct rt_serial_device *serial)
 {
     int ch;
-    struct stm32_uart* uart;
+    struct stm32_uart *uart;
 
     RT_ASSERT(serial != RT_NULL);
     uart = (struct stm32_uart *)serial->parent.user_data;
@@ -166,13 +168,13 @@ struct rt_serial_device serial1;
 
 void USART1_IRQHandler(void)
 {
-    struct stm32_uart* uart;
+    struct stm32_uart *uart;
 
     uart = &uart1;
 
     /* enter interrupt */
     rt_interrupt_enter();
-    if(USART_GetITStatus(uart->uart_device, USART_IT_RXNE) != RESET)
+    if (USART_GetITStatus(uart->uart_device, USART_IT_RXNE) != RESET)
     {
         rt_hw_serial_isr(&serial1, RT_SERIAL_EVENT_RX_IND);
         /* clear interrupt */
@@ -200,13 +202,13 @@ struct rt_serial_device serial2;
 
 void USART2_IRQHandler(void)
 {
-    struct stm32_uart* uart;
+    struct stm32_uart *uart;
 
     uart = &uart2;
 
     /* enter interrupt */
     rt_interrupt_enter();
-    if(USART_GetITStatus(uart->uart_device, USART_IT_RXNE) != RESET)
+    if (USART_GetITStatus(uart->uart_device, USART_IT_RXNE) != RESET)
     {
         rt_hw_serial_isr(&serial2, RT_SERIAL_EVENT_RX_IND);
         /* clear interrupt */
@@ -234,13 +236,13 @@ struct rt_serial_device serial3;
 
 void USART3_IRQHandler(void)
 {
-    struct stm32_uart* uart;
+    struct stm32_uart *uart;
 
     uart = &uart3;
 
     /* enter interrupt */
     rt_interrupt_enter();
-    if(USART_GetITStatus(uart->uart_device, USART_IT_RXNE) != RESET)
+    if (USART_GetITStatus(uart->uart_device, USART_IT_RXNE) != RESET)
     {
         rt_hw_serial_isr(&serial3, RT_SERIAL_EVENT_RX_IND);
         /* clear interrupt */
@@ -321,7 +323,7 @@ static void GPIO_Configuration(void)
 #endif /* RT_USING_UART3 */
 }
 
-static void NVIC_Configuration(struct stm32_uart* uart)
+static void NVIC_Configuration(struct stm32_uart *uart)
 {
     NVIC_InitTypeDef NVIC_InitStructure;
 
@@ -335,7 +337,7 @@ static void NVIC_Configuration(struct stm32_uart* uart)
 
 int stm32_hw_usart_init(void)
 {
-    struct stm32_uart* uart;
+    struct stm32_uart *uart;
     struct serial_configure config = RT_SERIAL_CONFIG_DEFAULT;
 
     RCC_Configuration();

+ 1 - 1
src/kservice.c

@@ -513,7 +513,7 @@ void rt_show_version(void)
     rt_kprintf("- RT -     Thread Operating System\n");
     rt_kprintf(" / | \\     %d.%d.%d build %s\n",
                RT_VERSION, RT_SUBVERSION, RT_REVISION, __DATE__);
-    rt_kprintf(" 2006 - 2013 Copyright by rt-thread team\n");
+    rt_kprintf(" 2006 - 2015 Copyright by rt-thread team\n");
 }
 RTM_EXPORT(rt_show_version);
 

+ 24 - 0
tools/building.py

@@ -1,3 +1,27 @@
+#
+# File      : building.py
+# This file is part of RT-Thread RTOS
+# COPYRIGHT (C) 2006 - 2015, RT-Thread Development Team
+#
+#  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
+# 2015-01-20     Bernard      Add copyright information
+#
+
 import os
 import sys
 import string

+ 24 - 0
tools/codeblocks.py

@@ -1,3 +1,27 @@
+#
+# File      : codeblocks.py
+# This file is part of RT-Thread RTOS
+# COPYRIGHT (C) 2006 - 2015, RT-Thread Development Team
+#
+#  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
+# 2015-01-20     Bernard      Add copyright information
+#
+
 import os
 import sys
 import string

+ 24 - 0
tools/cscope.py

@@ -1,3 +1,27 @@
+#
+# File      : cscope.py
+# This file is part of RT-Thread RTOS
+# COPYRIGHT (C) 2006 - 2015, RT-Thread Development Team
+#
+#  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
+# 2015-01-20     Bernard      Add copyright information
+#
+
 import os
 
 def _get_src(project):

+ 24 - 0
tools/iar.py

@@ -1,3 +1,27 @@
+#
+# File      : iar.py
+# This file is part of RT-Thread RTOS
+# COPYRIGHT (C) 2006 - 2015, RT-Thread Development Team
+#
+#  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
+# 2015-01-20     Bernard      Add copyright information
+#
+
 import os
 import sys
 import string

+ 24 - 0
tools/keil.py

@@ -1,3 +1,27 @@
+#
+# File      : keil.py
+# This file is part of RT-Thread RTOS
+# COPYRIGHT (C) 2006 - 2015, RT-Thread Development Team
+#
+#  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
+# 2015-01-20     Bernard      Add copyright information
+#
+
 import os
 import sys
 import string

+ 24 - 0
tools/sconsui.py

@@ -1,6 +1,30 @@
 #! /usr/bin/env python
 #coding=utf-8
 
+#
+# File      : sconsui.py
+# This file is part of RT-Thread RTOS
+# COPYRIGHT (C) 2006 - 2015, RT-Thread Development Team
+#
+#  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
+# 2015-01-20     Bernard      Add copyright information
+#
+
 import sys
 
 py2 = py30 = py31 = False

+ 24 - 0
tools/ua.py

@@ -1,3 +1,27 @@
+#
+# File      : ua.py
+# This file is part of RT-Thread RTOS
+# COPYRIGHT (C) 2006 - 2015, RT-Thread Development Team
+#
+#  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
+# 2015-01-20     Bernard      Add copyright information
+#
+
 import os
 import sys
 from utils import _make_path_relative

+ 24 - 0
tools/utils.py

@@ -1,3 +1,27 @@
+#
+# File      : utils.py
+# This file is part of RT-Thread RTOS
+# COPYRIGHT (C) 2006 - 2015, RT-Thread Development Team
+#
+#  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
+# 2015-01-20     Bernard      Add copyright information
+#
+
 import sys
 import os
 

+ 24 - 0
tools/vs.py

@@ -1,3 +1,27 @@
+#
+# File      : vs.py
+# This file is part of RT-Thread RTOS
+# COPYRIGHT (C) 2006 - 2015, RT-Thread Development Team
+#
+#  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
+# 2015-01-20     Bernard      Add copyright information
+#
+
 import os
 import sys
 import string

+ 24 - 0
tools/vs2012.py

@@ -1,3 +1,27 @@
+#
+# File      : vs2012.py
+# This file is part of RT-Thread RTOS
+# COPYRIGHT (C) 2006 - 2015, RT-Thread Development Team
+#
+#  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
+# 2015-01-20     Bernard      Add copyright information
+#
+
 import os
 import sys
 import string

+ 24 - 0
tools/win32spawn.py

@@ -1,3 +1,27 @@
+#
+# File      : win32spawn.py
+# This file is part of RT-Thread RTOS
+# COPYRIGHT (C) 2006 - 2015, RT-Thread Development Team
+#
+#  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
+# 2015-01-20     Bernard      Add copyright information
+#
+
 import os
 import threading
 import Queue

+ 24 - 0
tools/wizard.py

@@ -1,6 +1,30 @@
 #! /usr/bin/env python
 #coding=utf-8
 
+#
+# File      : wizard.py
+# This file is part of RT-Thread RTOS
+# COPYRIGHT (C) 2006 - 2015, RT-Thread Development Team
+#
+#  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
+# 2015-01-20     Bernard      Add copyright information
+#
+
 """
 wizard.py - a script to generate SConscript in RT-Thread RTOS.