Browse Source

Prepare RT-Thread 1.2.3 release.

bernard 10 years ago
parent
commit
a00cc57487

+ 13 - 1
bsp/lpc176x/drivers/sd.c

@@ -397,7 +397,19 @@ static rt_size_t rt_sdcard_write (rt_device_t dev, rt_off_t pos, const void* buf
 
 static rt_err_t rt_sdcard_control(rt_device_t dev, rt_uint8_t cmd, void *args)
 {
-	return RT_EOK;
+    if (cmd == RT_DEVICE_CTRL_BLK_GETGEOME)
+    {
+        struct rt_device_blk_geometry *geometry;
+        
+        geometry = (struct rt_device_blk_geometry *)args;
+        if (geometry == RT_NULL) return -RT_ERROR;
+
+        geometry->bytes_per_sector = SDCfg.sectorsize;
+        geometry->block_size = SDCfg.blocksize;
+        geometry->sector_count = SDCfg.sectorcnt;
+    }
+
+    return RT_EOK;
 }
 
 void rt_hw_sdcard_init()

+ 22 - 20
bsp/lpc408x/Libraries/Device/NXP/LPC407x_8x_177x_8x/Source/Templates/GCC/startup_LPC407x_8x_177x_8x.s

@@ -102,18 +102,18 @@ __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
 
@@ -130,22 +130,24 @@ CRP_Value:
     .section .cs3.reset,"x",%progbits
     .thumb_func
     .globl  __cs3_reset_cortex_m
+    .globl  Reset_Handler
     .type   __cs3_reset_cortex_m, %function
 __cs3_reset_cortex_m:
+Reset_Handler:
     .fnstart
 .ifdef RAM_MODE
 /* Clear .bss section (Zero init) */
-	MOV     R0, #0
-	LDR     R1, =__bss_start__
-	LDR     R2, =__bss_end__
-	CMP     R1,R2
-	BEQ     BSSIsEmpty
+    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
+    CMP     R1, R2
+    BHS	    BSSIsEmpty
+    STR     R0, [R1]
+    ADD	    R1, #4
+    BLO     LoopZI
 BSSIsEmpty:
     LDR     R0, =SystemInit
     BLX     R0
@@ -154,7 +156,7 @@ BSSIsEmpty:
 .else
     LDR     R0, =SystemInit
     BLX     R0
-	LDR     R0,=_start
+    LDR     R0,=main
     BX      R0
 .endif
     .pool

+ 6 - 5
components/dfs/filesystems/nfs/dfs_nfs.c

@@ -750,11 +750,12 @@ int nfs_open(struct dfs_fd *file)
         if (file->flags & DFS_O_CREAT)
         {
             if (nfs_mkdir(nfs, file->path, 0755) < 0)
-                return -1;
+                return -DFS_STATUS_EAGAIN;
         }
 
         /* open directory */
         dir = nfs_opendir(nfs, file->path);
+        if (dir == RT_NULL) return -DFS_STATUS_ENOENT;
         file->data = dir;
     }
     else
@@ -766,20 +767,20 @@ int nfs_open(struct dfs_fd *file)
         if (file->flags & DFS_O_CREAT)
         {
             if (nfs_create(nfs, file->path, 0664) < 0)
-                return -1;
+                return -DFS_STATUS_EAGAIN;
         }
 
         /* open file (get file handle ) */
         fp = rt_malloc(sizeof(nfs_file));
         if (fp == RT_NULL)
-            return -1;
+            return -DFS_STATUS_ENOMEM;
 
         handle = get_handle(nfs, file->path);
         if (handle == RT_NULL)
         {
             rt_free(fp);
 
-            return -1;
+            return -DFS_STATUS_ENOENT;
         }
 
         /* get size of file */
@@ -798,7 +799,7 @@ int nfs_open(struct dfs_fd *file)
 
         /* set private file */
         file->data = fp;
-		file->size = fp->size;
+        file->size = fp->size;
     }
 
     return 0;

+ 6 - 3
components/dfs/src/dfs_file.c

@@ -335,6 +335,9 @@ int dfs_file_lseek(struct dfs_fd *fd, rt_off_t offset)
 
     if (fd == RT_NULL)
         return -DFS_STATUS_EINVAL;
+    fs = fd->fs;
+    if (fs == RT_NULL)
+        return -DFS_STATUS_EINVAL;
     if (fs->ops->lseek == RT_NULL)
         return -DFS_STATUS_ENOSYS;
 
@@ -555,7 +558,7 @@ void ls(const char *pathname)
     if (pathname == RT_NULL) 
         rt_free(path);
 }
-FINSH_FUNCTION_EXPORT(ls, list directory contents)
+FINSH_FUNCTION_EXPORT(ls, list directory contents);
 
 void rm(const char *filename)
 {
@@ -564,7 +567,7 @@ void rm(const char *filename)
         rt_kprintf("Delete %s failed\n", filename);
     }
 }
-FINSH_FUNCTION_EXPORT(rm, remove files or directories)
+FINSH_FUNCTION_EXPORT(rm, remove files or directories);
 
 void cat(const char* filename)
 {
@@ -590,7 +593,7 @@ void cat(const char* filename)
 
     dfs_file_close(&fd);
 }
-FINSH_FUNCTION_EXPORT(cat, print file)
+FINSH_FUNCTION_EXPORT(cat, print file);
 
 #define BUF_SZ  4096
 static void copyfile(const char *src, const char *dst)

+ 2 - 0
components/dfs/src/dfs_fs.c

@@ -85,6 +85,8 @@ struct dfs_filesystem *dfs_filesystem_lookup(const char *path)
 
     prefixlen = 0;
 
+    RT_ASSERT(path);
+
     /* lock filesystem */
     dfs_lock();
 

+ 16 - 8
components/dfs/src/dfs_posix.c

@@ -33,11 +33,11 @@
 
 /**
  * this function is a POSIX compliant version, which will open a file and
- * return a file descriptor.
+ * return a file descriptor according specified flags.
  *
  * @param file the path name of file.
  * @param flags the file open flags.
- * @param mode
+ * @param mode ignored parameter
  *
  * @return the non-negative integer on successful open, others for failed.
  */
@@ -120,7 +120,8 @@ RTM_EXPORT(close);
  * @param buf the buffer to save the read data.
  * @param len the maximal length of data buffer
  *
- * @return the actual read data buffer length
+ * @return the actual read data buffer length. If the returned value is 0, it
+ * may be reach the end of file, please check errno.
  */
 int read(int fd, void *buf, size_t len)
 {
@@ -200,7 +201,7 @@ RTM_EXPORT(write);
  * @param offset the offset to be seeked.
  * @param whence the directory of seek.
  *
- * @return the current file position, or -1 on failed.
+ * @return the current read/write position in the file, or -1 on failed.
  */
 off_t lseek(int fd, off_t offset, int whence)
 {
@@ -336,6 +337,8 @@ RTM_EXPORT(stat);
  *
  * @param fildes the file description
  * @param buf the data buffer to save stat description.
+ *
+ * @return 0 on successful, -1 on failed.
  */
 int fstat(int fildes, struct stat *buf)
 {
@@ -470,7 +473,7 @@ RTM_EXPORT(rmdir);
  *
  * @param name the path name to be open.
  *
- * @return the DIR pointer of directory, NULL on open failed.
+ * @return the DIR pointer of directory, NULL on open directory failed.
  */
 DIR *opendir(const char *name)
 {
@@ -537,12 +540,17 @@ struct dirent *readdir(DIR *d)
     if (fd == RT_NULL)
     {
         rt_set_errno(-DFS_STATUS_EBADF);
-
         return RT_NULL;
     }
 
-    if (!d->num ||
-        (d->cur += ((struct dirent *)(d->buf + d->cur))->d_reclen) >= d->num)
+    if (d->num)
+    {
+        struct dirent* dirent_ptr;
+        dirent_ptr = (struct dirent*)&d->buf[d->cur];
+        d->cur += dirent_ptr->d_reclen;
+    }
+
+    if (!d->num || d->cur >= d->num)
     {
         /* get a new entry */
         result = dfs_file_getdents(fd,

+ 0 - 3
components/drivers/i2c/i2c-bit-ops.c

@@ -451,9 +451,6 @@ static const struct rt_i2c_bus_device_ops i2c_bit_bus_ops =
 rt_err_t rt_i2c_bit_add_bus(struct rt_i2c_bus_device *bus,
                             const char               *bus_name)
 {
-    struct rt_i2c_bit_ops *bit_ops = bus->priv;
-    RT_ASSERT(bit_ops != RT_NULL);
-
     bus->ops = &i2c_bit_bus_ops;
 
     return rt_i2c_bus_device_register(bus, bus_name);

+ 2 - 9
components/drivers/i2c/i2c_core.c

@@ -24,8 +24,6 @@
 
 #include <rtdevice.h>
 
-static struct rt_mutex i2c_core_lock;
-
 rt_err_t rt_i2c_bus_device_register(struct rt_i2c_bus_device *bus,
                                     const char               *bus_name)
 {
@@ -33,17 +31,12 @@ rt_err_t rt_i2c_bus_device_register(struct rt_i2c_bus_device *bus,
 
     rt_mutex_init(&bus->lock, "i2c_bus_lock", RT_IPC_FLAG_FIFO);
 
-    rt_mutex_take(&i2c_core_lock, RT_WAITING_FOREVER);
-
-    if (bus->timeout == 0)
-        bus->timeout = RT_TICK_PER_SECOND;
+    if (bus->timeout == 0) bus->timeout = RT_TICK_PER_SECOND;
 
     res = rt_i2c_bus_device_device_init(bus, bus_name);
 
     i2c_dbg("I2C bus [%s] registered\n", bus_name);
 
-    rt_mutex_release(&i2c_core_lock);
-
     return res;
 }
 
@@ -136,6 +129,6 @@ rt_size_t rt_i2c_master_recv(struct rt_i2c_bus_device *bus,
 
 int rt_i2c_core_init(void)
 {
-    return rt_mutex_init(&i2c_core_lock, "i2c_core_lock", RT_IPC_FLAG_FIFO);
+    return 0;
 }
 INIT_COMPONENT_EXPORT(rt_i2c_core_init);

+ 2 - 9
components/drivers/i2c/i2c_dev.c

@@ -20,18 +20,11 @@
  * Change Logs:
  * Date           Author        Notes
  * 2012-04-25     weety         first version
+ * 2014-08-03     bernard       fix some compiling warning
  */
 
 #include <rtdevice.h>
 
-static rt_err_t i2c_bus_device_init(rt_device_t dev)
-{
-    struct rt_i2c_bus_device *bus = (struct rt_i2c_bus_device *)dev->user_data;
-    RT_ASSERT(bus != RT_NULL);
-
-    return RT_EOK;
-}
-
 static rt_size_t i2c_bus_device_read(rt_device_t dev,
                                      rt_off_t    pos,
                                      void       *buffer,
@@ -122,7 +115,7 @@ rt_err_t rt_i2c_bus_device_device_init(struct rt_i2c_bus_device *bus,
     /* set device type */
     device->type    = RT_Device_Class_I2CBUS;
     /* initialize device interface */
-    device->init    = i2c_bus_device_init;
+    device->init    = RT_NULL;
     device->open    = RT_NULL;
     device->close   = RT_NULL;
     device->read    = i2c_bus_device_read;

+ 6 - 0
components/drivers/include/drivers/serial.h

@@ -30,9 +30,15 @@
 
 #include <rtthread.h>
 
+#define BAUD_RATE_2400                  2400
 #define BAUD_RATE_4800                  4800
 #define BAUD_RATE_9600                  9600
+#define BAUD_RATE_38400                 38400
+#define BAUD_RATE_57600                 57600
 #define BAUD_RATE_115200                115200
+#define BAUD_RATE_230400                230400
+#define BAUD_RATE_460800                460800
+#define BAUD_RATE_921600                921600
 
 #define DATA_BITS_5                     5
 #define DATA_BITS_6                     6

+ 3 - 32
components/drivers/spi/spi_dev.c

@@ -25,16 +25,6 @@
 #include <drivers/spi.h>
 
 /* SPI bus device interface, compatible with RT-Thread 0.3.x/1.0.x */
-static rt_err_t _spi_bus_device_init(rt_device_t dev)
-{
-    struct rt_spi_bus *bus;
-
-    bus = (struct rt_spi_bus *)dev;
-    RT_ASSERT(bus != RT_NULL);
-
-    return RT_EOK;
-}
-
 static rt_size_t _spi_bus_device_read(rt_device_t dev,
                                       rt_off_t    pos,
                                       void       *buffer,
@@ -67,11 +57,7 @@ static rt_err_t _spi_bus_device_control(rt_device_t dev,
                                         rt_uint8_t  cmd,
                                         void       *args)
 {
-    struct rt_spi_bus *bus;
-
-    bus = (struct rt_spi_bus *)dev;
-    RT_ASSERT(bus != RT_NULL);
-
+    /* TODO: add control command handle */
     switch (cmd)
     {
     case 0: /* set device */
@@ -93,7 +79,7 @@ rt_err_t rt_spi_bus_device_init(struct rt_spi_bus *bus, const char *name)
     /* set device type */
     device->type    = RT_Device_Class_SPIBUS;
     /* initialize device interface */
-    device->init    = _spi_bus_device_init;
+    device->init    = RT_NULL;
     device->open    = RT_NULL;
     device->close   = RT_NULL;
     device->read    = _spi_bus_device_read;
@@ -105,16 +91,6 @@ rt_err_t rt_spi_bus_device_init(struct rt_spi_bus *bus, const char *name)
 }
 
 /* SPI Dev device interface, compatible with RT-Thread 0.3.x/1.0.x */
-static rt_err_t _spidev_device_init(rt_device_t dev)
-{
-    struct rt_spi_device *device;
-
-    device = (struct rt_spi_device *)dev;
-    RT_ASSERT(device != RT_NULL);
-
-    return RT_EOK;
-}
-
 static rt_size_t _spidev_device_read(rt_device_t dev,
                                      rt_off_t    pos,
                                      void       *buffer,
@@ -147,11 +123,6 @@ static rt_err_t _spidev_device_control(rt_device_t dev,
                                        rt_uint8_t  cmd,
                                        void       *args)
 {
-    struct rt_spi_device *device;
-
-    device = (struct rt_spi_device *)dev;
-    RT_ASSERT(device != RT_NULL);
-
     switch (cmd)
     {
     case 0: /* set device */
@@ -172,7 +143,7 @@ rt_err_t rt_spidev_device_init(struct rt_spi_device *dev, const char *name)
 
     /* set device type */
     device->type    = RT_Device_Class_SPIDevice;
-    device->init    = _spidev_device_init;
+    device->init    = RT_NULL;
     device->open    = RT_NULL;
     device->close   = RT_NULL;
     device->read    = _spidev_device_read;

+ 9 - 3
components/finsh/msh.c

@@ -315,12 +315,15 @@ int msh_exec(char* cmd, rt_size_t length)
         return 0;
     }
 #endif
-#ifdef DFS_USING_WORKDIR
+
+#if defined(RT_USING_DFS) && defined(DFS_USING_WORKDIR)
+	/* change to this directory */
     if (chdir(cmd) == 0)
     {
         return 0;
     }
 #endif
+
     /* truncate the cmd at the first space. */
     {
         char *tcmd;
@@ -355,10 +358,12 @@ void msh_auto_complete_path(char *path)
     struct dirent *dirent = RT_NULL;
     char *full_path, *ptr, *index;
 
+    if (!path)
+        return;
+
     full_path = (char*)rt_malloc(256);
     if (full_path == RT_NULL) return; /* out of memory */
 
-    ptr = full_path;
     if (*path != '/')
     {
         getcwd(full_path, 256);
@@ -367,7 +372,8 @@ void msh_auto_complete_path(char *path)
     }
     else *full_path = '\0';
 
-    index = RT_NULL; ptr = path;
+    index = RT_NULL;
+    ptr = path;
     for (;;)
     {
         if (*ptr == '/') index = ptr + 1; if (!*ptr) break; ptr ++;

+ 2 - 0
components/finsh/msh_cmd.c

@@ -206,6 +206,7 @@ int cmd_time(int argc, char** argv)
 }
 FINSH_FUNCTION_EXPORT_ALIAS(cmd_time, __cmd_time, Execute command with time.);
 
+#ifdef RT_USING_HEAP
 int cmd_free(int argc, char** argv)
 {
     extern void list_mem(void);
@@ -214,6 +215,7 @@ int cmd_free(int argc, char** argv)
     return 0;
 }
 FINSH_FUNCTION_EXPORT_ALIAS(cmd_free, __cmd_free, Show the memory usage in the system.);
+#endif
 
 #endif
 

+ 2 - 1
components/finsh/shell.c

@@ -70,10 +70,11 @@ const char* finsh_get_prompt()
 #endif
     strcpy(finsh_prompt, _PROMPT);
 
-#ifdef DFS_USING_WORKDIR
+#if defined(RT_USING_DFS) && defined(DFS_USING_WORKDIR)
     /* get current working directory */
     getcwd(&finsh_prompt[rt_strlen(finsh_prompt)], RT_CONSOLEBUF_SIZE - rt_strlen(finsh_prompt));
 #endif
+
     strcat(finsh_prompt, ">");
 
     return finsh_prompt;

+ 11 - 1
components/finsh/shell.h

@@ -33,7 +33,17 @@
 #include <rtthread.h>
 #include "finsh.h"
 
-#define FINSH_USING_HISTORY
+/* For historical reasons, users don't define FINSH_USING_HISTORY in rtconfig.h
+ * but expect the history feature. So you sould define FINSH_USING_HISTORY to 0
+ * to disable it from the rtconfig.h. */
+#ifdef FINSH_USING_HISTORY
+#    if FINSH_USING_HISTORY == 0
+#        undef FINSH_USING_HISTORY
+#    endif
+#else
+#    define FINSH_USING_HISTORY
+#endif
+
 #ifndef FINSH_THREAD_PRIORITY
 #define FINSH_THREAD_PRIORITY 20
 #endif

+ 4 - 3
components/utilities/ymodem/ymodem.c

@@ -197,7 +197,7 @@ static rt_err_t _rym_do_trans(struct rym_ctx *ctx)
     {
         rt_err_t err;
         enum rym_code code;
-        rt_size_t data_sz;
+        rt_size_t data_sz, i;
 
         code = _rym_read_code(ctx,
                 RYM_WAIT_PKG_TICK);
@@ -223,8 +223,9 @@ static rt_err_t _rym_do_trans(struct rym_ctx *ctx)
         {
         case RYM_CODE_CAN:
             /* the spec require multiple CAN */
-            _rym_putchar(ctx, RYM_CODE_CAN);
-            _rym_putchar(ctx, RYM_CODE_CAN);
+            for (i = 0; i < RYM_END_SESSION_SEND_CAN_NUM; i++) {
+                _rym_putchar(ctx, RYM_CODE_CAN);
+            }
             return -RYM_ERR_CAN;
         case RYM_CODE_ACK:
             _rym_putchar(ctx, RYM_CODE_ACK);

+ 1 - 1
include/rtdef.h

@@ -50,7 +50,7 @@ extern "C" {
 /* RT-Thread version information */
 #define RT_VERSION                      1L              /**< major version number */
 #define RT_SUBVERSION                   2L              /**< minor version number */
-#define RT_REVISION                     2L              /**< revise version number */
+#define RT_REVISION                     3L              /**< revise version number */
 
 /* RT-Thread version */
 #define RTTHREAD_VERSION                ((RT_VERSION * 10000) + \

+ 5 - 38
src/device.c

@@ -79,45 +79,12 @@ RTM_EXPORT(rt_device_unregister);
  * This function initializes all registered device driver
  *
  * @return the error code, RT_EOK on successfully.
+ *
+ * @deprecated since 1.2.3, this function is not needed because the initialization 
+ *             of a device is performed when applicaiton opens it.
  */
 rt_err_t rt_device_init_all(void)
 {
-    struct rt_device *device;
-    struct rt_list_node *node;
-    struct rt_object_information *information;
-    register rt_err_t result;
-
-    extern struct rt_object_information rt_object_container[];
-
-    information = &rt_object_container[RT_Object_Class_Device];
-
-    /* for each device */
-    for (node  = information->object_list.next;
-         node != &(information->object_list);
-         node  = node->next)
-    {
-        rt_err_t (*init)(rt_device_t dev);
-        device = (struct rt_device *)rt_list_entry(node,
-                                                   struct rt_object,
-                                                   list);
-
-        /* get device init handler */
-        init = device->init;
-        if (init != RT_NULL && !(device->flag & RT_DEVICE_FLAG_ACTIVATED))
-        {
-            result = init(device);
-            if (result != RT_EOK)
-            {
-                rt_kprintf("To initialize device:%s failed. The error code is %d\n",
-                           device->parent.name, result);
-            }
-            else
-            {
-                device->flag |= RT_DEVICE_FLAG_ACTIVATED;
-            }
-        }
-    }
-
     return RT_EOK;
 }
 
@@ -395,8 +362,8 @@ rt_err_t rt_device_control(rt_device_t dev, rt_uint8_t cmd, void *arg)
 RTM_EXPORT(rt_device_control);
 
 /**
- * This function will set the indication callback function when device receives
- * data.
+ * This function will set the reception indication callback function. This callback function
+ * is invoked when this device receives data.
  *
  * @param dev the pointer of device driver structure
  * @param rx_ind the indication callback function

+ 16 - 2
src/idle.c

@@ -67,6 +67,20 @@ void rt_thread_idle_sethook(void (*hook)(void))
 /*@}*/
 #endif
 
+/* Return whether there is defunctional thread to be deleted. */
+rt_inline int _has_defunct_thread(void)
+{
+    /* The rt_list_isempty has prototype of "int rt_list_isempty(const rt_list_t *l)".
+     * So the compiler has a good reason that the rt_thread_defunct list does
+     * not change within rt_thread_idle_excute thus optimize the "while" loop
+     * into a "if".
+     *
+     * So add the volatile qualifier here. */
+    const volatile rt_list_t *l = (const volatile rt_list_t*)&rt_thread_defunct;
+
+    return l->next != l;
+}
+
 /**
  * @ingroup Thread
  *
@@ -76,7 +90,7 @@ void rt_thread_idle_excute(void)
 {
     /* Loop until there is no dead thread. So one call to rt_thread_idle_excute
      * will do all the cleanups. */
-    while (!rt_list_isempty(&rt_thread_defunct))
+    while (_has_defunct_thread())
     {
         rt_base_t lock;
         rt_thread_t thread;
@@ -89,7 +103,7 @@ void rt_thread_idle_excute(void)
         lock = rt_hw_interrupt_disable();
 
         /* re-check whether list is empty */
-        if (!rt_list_isempty(&rt_thread_defunct))
+        if (_has_defunct_thread())
         {
             /* get defunct thread */
             thread = rt_list_entry(rt_thread_defunct.next,

+ 3 - 3
src/mem.c

@@ -176,10 +176,10 @@ static void plug_holes(struct heap_mem *mem)
 /**
  * @ingroup SystemInit
  *
- * This function will init system heap
+ * This function will initialize system heap memory.
  *
- * @param begin_addr the beginning address of system page
- * @param end_addr the end address of system page
+ * @param begin_addr the beginning address of system heap memory.
+ * @param end_addr the end address of system heap memory.
  */
 void rt_system_heap_init(void *begin_addr, void *end_addr)
 {

+ 2 - 2
src/module.c

@@ -1120,8 +1120,8 @@ rt_module_t rt_module_open(const char *path)
  * This function will do a excutable program with main function and parameters.
  *
  * @param path the full path of application module
- * @cmd_line the command line of program
- * @size the size of command line of program
+ * @param cmd_line the command line of program
+ * @param size the size of command line of program
  *
  * @return the module object
  */

+ 1 - 1
src/module.h

@@ -239,7 +239,7 @@ typedef struct
 #define SHT_DYNAMIC             6              /* dynamic section */
 #define SHT_NOTE                7              /* note section */
 #define SHT_NOBITS              8              /* no space section */
-#define SHT_REL                 9              /* relation section without addends */
+#define SHT_REL                 9              /* relocation section without addends */
 #define SHT_SHLIB               10             /* reserved - purpose unknown */
 #define SHT_DYNSYM              11             /* dynamic symbol table section */
 #define SHT_NUM                 12             /* number of section types */

+ 12 - 10
tools/building.py

@@ -27,11 +27,9 @@ class Win32Spawn:
 
         newargs = string.join(args[1:], ' ')
         cmdline = cmd + " " + newargs
-        startupinfo = subprocess.STARTUPINFO()
-        startupinfo.dwFlags |= subprocess.STARTF_USESHOWWINDOW
 
         # Make sure the env is constructed by strings
-        _e = {k: str(v) for k, v in env.items()}
+        _e = dict([(k, str(v)) for k, v in env.items()])
 
         # Windows(tm) CreateProcess does not use the env passed to it to find
         # the executables. So we have to modify our own PATH to make Popen
@@ -40,8 +38,7 @@ class Win32Spawn:
         os.environ['PATH'] = _e['PATH']
 
         try:
-            proc = subprocess.Popen(cmdline, env=_e,
-                    startupinfo=startupinfo, shell=False)
+            proc = subprocess.Popen(cmdline, env=_e, shell=False)
         except Exception as e:
             print 'Error in calling:\n%s' % cmdline
             print 'Exception: %s: %s' % (e, os.strerror(e.errno))
@@ -212,18 +209,23 @@ def PrepareBuilding(env, root_directory, has_libcpu=False, remove_components = [
             LINKCOMSTR = 'LINK $TARGET'
         )
 
+    # we need to seperate the variant_dir for BSPs and the kernels. BSPs could
+    # have their own components etc. If they point to the same folder, SCons
+    # would find the wrong source code to compile.
+    bsp_vdir = 'build/bsp'
+    kernel_vdir = 'build/kernel'
     # board build script
-    objs = SConscript('SConscript', variant_dir='build', duplicate=0)
-    Repository(Rtt_Root)
+    objs = SConscript('SConscript', variant_dir=bsp_vdir, duplicate=0)
     # include kernel
-    objs.extend(SConscript(Rtt_Root + '/src/SConscript', variant_dir='build/src', duplicate=0))
+    objs.extend(SConscript(Rtt_Root + '/src/SConscript', variant_dir=kernel_vdir + '/src', duplicate=0))
     # include libcpu
     if not has_libcpu:
-        objs.extend(SConscript(Rtt_Root + '/libcpu/SConscript', variant_dir='build/libcpu', duplicate=0))
+        objs.extend(SConscript(Rtt_Root + '/libcpu/SConscript',
+                    variant_dir=kernel_vdir + '/libcpu', duplicate=0))
 
     # include components
     objs.extend(SConscript(Rtt_Root + '/components/SConscript',
-                           variant_dir='build/components',
+                           variant_dir=kernel_vdir + '/components',
                            duplicate=0,
                            exports='remove_components'))
 

+ 6 - 18
tools/keil.py

@@ -107,6 +107,7 @@ def MDK4Project(target, script):
     groups = tree.find('Targets/Target/Groups')
     if groups is None:
         groups = SubElement(tree.find('Targets/Target'), 'Groups')
+    groups.clear() # clean old groups
     for group in script:
         group_xml = MDK4AddGroup(ProjectFiles, groups, group['name'], group['src'], project_path)
         
@@ -142,33 +143,20 @@ def MDK4Project(target, script):
                 if lib_path != '':
                     MDK4AddGroupForFN(ProjectFiles, groups, group['name'], lib_path, project_path)
 
-    # remove repeat path
-    paths = set()
-    for path in CPPPATH:
-        inc = _make_path_relative(project_path, os.path.normpath(path))
-        paths.add(inc) #.replace('\\', '/')
-    
-    paths = [i for i in paths]
-    paths.sort()
-    CPPPATH = string.join(paths, ';')
-    
-    definitions = [i for i in set(CPPDEFINES)]
-    CPPDEFINES = string.join(definitions, ', ')
-    
     # write include path, definitions and link flags
     IncludePath = tree.find('Targets/Target/TargetOption/TargetArmAds/Cads/VariousControls/IncludePath')
-    IncludePath.text = CPPPATH
-    
+    IncludePath.text = ';'.join([_make_path_relative(project_path, os.path.normpath(i)) for i in CPPPATH])
+
     Define = tree.find('Targets/Target/TargetOption/TargetArmAds/Cads/VariousControls/Define')
-    Define.text = CPPDEFINES
+    Define.text = ', '.join(set(CPPDEFINES))
 
     Misc = tree.find('Targets/Target/TargetOption/TargetArmAds/LDads/Misc')
     Misc.text = LINKFLAGS
-    
+
     xml_indent(root)
     out.write(etree.tostring(root, encoding='utf-8'))
     out.close()
-    
+
     # copy uvopt file
     if os.path.exists('template.uvopt'):
         import shutil