diff --git a/ChangeLog b/ChangeLog
index 58a95e451a53b31c1401561047dd2f4c59dcb5d3..3af9ffeef6da04f69aa97c0e0af0c3880a00d148 100644
--- a/ChangeLog
+++ b/ChangeLog
@@ -1613,9 +1613,10 @@
 	  interrupt logic.
 	* net/netdev_unregister.c -- Add capability to un-register a network
 	  device.
+	* drivers/mmcsd/mmcsd_sdio.c: extra effort to correctly handle cases
+	  without the SDcard (but one issue still exists in STM32)
+	* arch/arm/src/stm32/stm32_tim.*: Added basic timer support without
+	  output PWMs and interrupt logic
+	* config/vsn/src: added basic support for Sensor Interface (GPIO and
+	  Power Output, and the sif utility program)
 
-
-	  
-
-
-	  
diff --git a/Documentation/NuttX.html b/Documentation/NuttX.html
index 75d09209abb43e8ca1c8fe1d0c5820da01b790fc..ff705681af973b0501e2361ee8bf076b949fe8c4 100644
--- a/Documentation/NuttX.html
+++ b/Documentation/NuttX.html
@@ -8,7 +8,7 @@
   <tr align="center" bgcolor="#e4e4e4">
     <td>
       <h1><big><font color="#3c34ec"><i>NuttX RTOS</i></font></big></h1>
-      <p>Last Updated: March 23, 2011</p>
+      <p>Last Updated: March 24, 2011</p>
     </td>
   </tr>
 </table>
@@ -2164,6 +2164,14 @@ nuttx-6.1 2011-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
       earlier, 'context' build phase.
     * arch/arm/src/lpc17_gpioint.c -- Finish coding of the LPC17xx GPIO
       interrupt logic.
+    * net/netdev_unregister.c -- Add capability to un-register a network
+      device.
+    * drivers/mmcsd/mmcsd_sdio.c: extra effort to correctly handle cases
+      without the SDcard (but one issue still exists in STM32)
+    * arch/arm/src/stm32/stm32_tim.*: Added basic timer support without
+      output PWMs and interrupt logic
+    * config/vsn/src: added basic support for Sensor Interface (GPIO and
+      Power Output, and the sif utility program)
 
 apps-6.1 2011-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
 
diff --git a/arch/arm/src/stm32/Make.defs b/arch/arm/src/stm32/Make.defs
index 7595ff944b37b3afe9fbba146c54cd817346572b..34b6458b1875022c22888a381092f3368cf575fe 100755
--- a/arch/arm/src/stm32/Make.defs
+++ b/arch/arm/src/stm32/Make.defs
@@ -47,5 +47,6 @@ CMN_CSRCS	= up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \
 CHIP_ASRCS	= 
 CHIP_CSRCS	= stm32_start.c stm32_rcc.c stm32_gpio.c stm32_idle.c \
 		  stm32_irq.c stm32_timerisr.c stm32_dma.c stm32_lowputc.c \
-		  stm32_serial.c stm32_spi.c stm32_usbdev.c stm32_sdio.c 
+		  stm32_serial.c stm32_spi.c stm32_usbdev.c stm32_sdio.c \
+		  stm32_tim.c
 
diff --git a/arch/arm/src/stm32/chip.h b/arch/arm/src/stm32/chip.h
index 9d6ed8eb3ee2f0f588e0cdd803c9f92633cabc3d..28d59c838197938cb14b377e333c5d4c5482d9e7 100755
--- a/arch/arm/src/stm32/chip.h
+++ b/arch/arm/src/stm32/chip.h
@@ -75,7 +75,7 @@
 #  undef  CONFIG_STM32_CONNECTIVITYLINE      /* STM32F105x and STM32F107x */
 #  define STM32_NATIM                    2   /* Two advanced timers TIM1 and TIM8 */
 #  define STM32_NGTIM                    4   /* General timers TIM2,3,4,5 */
-#  define STM32 NBTIM                    2   /* Two basic timers TIM6 and TIM7 */
+#  define STM32_NBTIM                    2   /* Two basic timers TIM6 and TIM7 */
 #  define STM32_NDMA                     2   /* DMA1-2 */
 #  define STM32_NSPI                     3   /* SPI1-3 */
 #  define STM32_NUSART                   5   /* USART1-5 */
diff --git a/arch/arm/src/stm32/stm32.h b/arch/arm/src/stm32/stm32.h
new file mode 100644
index 0000000000000000000000000000000000000000..92628ab2e3d7496cd78ae3f7b525eaa385b33fd9
--- /dev/null
+++ b/arch/arm/src/stm32/stm32.h
@@ -0,0 +1,65 @@
+/************************************************************************************
+ * arch/arm/src/stm32/stm32.h
+ *
+ *   Copyright (C) 2011 Uros Platise. All rights reserved.
+ *   Author: Uros Platise <uros.platise@isotel.eu>
+ *
+ * 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 NuttX 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 COPYRIGHT HOLDERS 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
+ * COPYRIGHT OWNER 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_STM32_STM32_H
+#define __ARCH_ARM_SRC_STM32_STM32_H
+
+#include "chip.h"
+#include "stm32_adc.h"
+#include "stm32_bkp.h"
+#include "stm32_can.h"
+#include "stm32_dgbmcu.h"
+#include "stm32_dma.h"
+#include "stm32_exti.h"
+#include "stm32_flash.h"
+#include "stm32_fsmc.h"
+#include "stm32_gpio.h"
+#include "stm32_i2c.h"
+#include "stm32_pwr.h"
+#include "stm32_rcc.h"
+#include "stm32_rtc.h"
+#include "stm32_sdio.h"
+#include "stm32_spi.h"
+#include "stm32_tim.h"
+#include "stm32_uart.h"
+#include "stm32_usbdev.h"
+#include "stm32_wdg.h"
+
+/* TODO: Inconsistency! Code uses GPIO macros from this file instead from gpio.h! 
+ * _internal also includes pinmap.h file. 
+ */
+#include "stm32_internal.h"     
+
+#endif /* __ARCH_ARM_SRC_STM32_STM32_H */
diff --git a/arch/arm/src/stm32/stm32_memorymap.h b/arch/arm/src/stm32/stm32_memorymap.h
index 09b91185f4a94a7bf5a9742dede68edcf6cd6441..dea7c49e7fa1c8ef5626f4a7952d57ef483417b5 100755
--- a/arch/arm/src/stm32/stm32_memorymap.h
+++ b/arch/arm/src/stm32/stm32_memorymap.h
@@ -105,7 +105,7 @@
 #define STM32_ADC2_BASE      0x40012800     /* 0x40012800 - 0x40012bff: ADC2 */
 #define STM32_TIM1_BASE      0x40012c00     /* 0x40012c00 - 0x40012fff: TIM1 timer */
 #define STM32_SPI1_BASE      0x40013000     /* 0x40013000 - 0x400133ff: SPI1 */
-#define STM32_TIM8_BASE      0x40012c00     /* 0x40013400 - 0x400137ff: TIM8 timer */
+#define STM32_TIM8_BASE      0x40013400     /* 0x40013400 - 0x400137ff: TIM8 timer */
 #define STM32_USART1_BASE    0x40013800     /* 0x40013800 - 0x40013bff: USART1 */
 #define STM32_ADC3_BASE      0x40012800     /* 0x40012800 - 0x40013fff: ADC3 */
                                             /* 0x40014000 - 0x40017fff: Reserved */
diff --git a/arch/arm/src/stm32/stm32_tim.c b/arch/arm/src/stm32/stm32_tim.c
new file mode 100644
index 0000000000000000000000000000000000000000..e185b1a87958c91ea526dbc35f91594cfd4cfa48
--- /dev/null
+++ b/arch/arm/src/stm32/stm32_tim.c
@@ -0,0 +1,512 @@
+/************************************************************************************
+ * arm/arm/src/stm32/stm32_tim.c
+ *
+ *   Copyright (C) 2011 Uros Platise. All rights reserved.
+ *   Author: Uros Platise <uros.platise@isotel.eu>
+ *
+ * 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 NuttX 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 COPYRIGHT HOLDERS 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
+ * COPYRIGHT OWNER 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.
+ *
+ ************************************************************************************/
+
+/** \file
+ *  \author Uros Platise
+ *  \brief STM32 Basic, General and Advanced Timers
+ */
+
+#include <nuttx/config.h>
+#include <nuttx/arch.h>
+#include <nuttx/irq.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <semaphore.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+#include "stm32_internal.h"
+#include "stm32_gpio.h"
+#include "stm32_tim.h"
+
+
+#define getreg16(a)         (*(volatile uint16_t *)(a))
+#define putreg16(v,a)       (*(volatile uint16_t *)(a) = (v))
+
+
+/************************************************************************************
+ * Private Types
+ ************************************************************************************/
+
+/** TIM Device Structure 
+ */
+struct stm32_tim_priv_s {
+    struct stm32_tim_ops_s *ops;
+    stm32_tim_mode_t        mode;
+    
+    uint32_t    base;               /** TIMn base address */
+    uint8_t     irqno;              /** TIM IRQ number */
+};
+
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+
+/** Get register value by offset */
+static inline uint16_t stm32_tim_getreg(FAR struct stm32_tim_dev_s *dev, uint8_t offset)
+{
+    return getreg16( ((struct stm32_tim_priv_s *)dev)->base + offset);
+}
+
+
+/** Put register value by offset */
+static inline void stm32_tim_putreg(FAR struct stm32_tim_dev_s *dev, uint8_t offset, uint16_t value)
+{
+    //printf("putreg(%8x)=%4x\n", ((struct stm32_tim_priv_s *)dev)->base + offset, value );
+    putreg16(value, ((struct stm32_tim_priv_s *)dev)->base + offset);
+}
+
+
+/** Modify register value by offset */
+static inline void stm32_tim_modifyreg(FAR struct stm32_tim_dev_s *dev, uint8_t offset, uint16_t clearbits, uint16_t setbits)
+{
+    modifyreg16( ((struct stm32_tim_priv_s *)dev)->base + offset, clearbits, setbits);
+}
+
+
+static void stm32_tim_reload_counter(FAR struct stm32_tim_dev_s *dev)
+{
+    uint16_t val = stm32_tim_getreg(dev, STM32_BTIM_EGR_OFFSET);
+    val |= ATIM_EGR_UG;
+    stm32_tim_putreg(dev, STM32_BTIM_EGR_OFFSET, val);    
+}
+
+
+static void stm32_tim_enable(FAR struct stm32_tim_dev_s *dev)
+{
+    uint16_t val = stm32_tim_getreg(dev, STM32_BTIM_CR1_OFFSET);
+    val |= ATIM_CR1_CEN;
+    stm32_tim_reload_counter(dev);
+    stm32_tim_putreg(dev, STM32_BTIM_CR1_OFFSET, val);
+}
+
+
+static void stm32_tim_disable(FAR struct stm32_tim_dev_s *dev)
+{
+    uint16_t val = stm32_tim_getreg(dev, STM32_BTIM_CR1_OFFSET);
+    val &= ~ATIM_CR1_CEN;
+    stm32_tim_putreg(dev, STM32_BTIM_CR1_OFFSET, val);
+}
+
+
+/** Reset timer into system default state, but do not affect output/input pins */
+static void stm32_tim_reset(FAR struct stm32_tim_dev_s *dev)
+{
+    ((struct stm32_tim_priv_s *)dev)->mode = STM32_TIM_MODE_DISABLED;
+    stm32_tim_disable(dev);
+}
+
+
+/************************************************************************************
+ * Basic Functions
+ ************************************************************************************/
+
+static int stm32_tim_setclock(FAR struct stm32_tim_dev_s *dev, uint32_t freq)
+{
+    int prescaler;
+    
+    ASSERT(dev);
+    
+    /* Disable Timer? */
+    if (freq == 0) {
+        stm32_tim_disable(dev);
+        return 0;
+    }
+    
+#if STM32_NATIM > 0    
+    if (((struct stm32_tim_priv_s *)dev)->base == STM32_TIM1_BASE || 
+        ((struct stm32_tim_priv_s *)dev)->base == STM32_TIM8_BASE)
+        prescaler = STM32_TIM18_FREQUENCY / freq;
+    else 
+#endif
+        prescaler = STM32_TIM27_FREQUENCY / freq;
+        
+    /* we need to decrement value for '1', but only, if we are allowed to
+     * not to cause underflow. Check for overflow.
+     */
+    if (prescaler > 0) prescaler--;
+    if (prescaler > 0xFFFF) prescaler = 0xFFFF;
+    
+    stm32_tim_putreg(dev, STM32_BTIM_PSC_OFFSET, prescaler);    
+    stm32_tim_enable(dev);
+    
+    return prescaler;
+}
+
+
+static void stm32_tim_setperiod(FAR struct stm32_tim_dev_s *dev, uint16_t period)
+{
+    ASSERT(dev);
+    stm32_tim_putreg(dev, STM32_BTIM_ARR_OFFSET, period);
+}
+
+
+static int stm32_tim_setisr(FAR struct stm32_tim_dev_s *dev, int (*handler)(int irq, void *context), int source)
+{
+    int vectorno;
+
+    ASSERT(dev);
+    ASSERT(source==0);
+        
+    switch( ((struct stm32_tim_priv_s *)dev)->base ) {
+        case STM32_TIM3_BASE: vectorno = STM32_IRQ_TIM3;    break;
+        
+#if STM32_NATIM > 0
+        /** \todo add support for multiple sources and callbacks */
+        case STM32_TIM1_BASE: vectorno = STM32_IRQ_TIM1UP;  break;
+        case STM32_TIM8_BASE: vectorno = STM32_IRQ_TIM8UP;  break;
+#endif
+        default: return ERROR;
+    }
+    
+    /* Disable interrupt when callback is removed */
+    
+    if (!handler) {
+        up_disable_irq(vectorno);
+        irq_detach(vectorno);
+        return OK;
+    }
+    
+    /* Otherwise set callback and enable interrupt */
+    
+    printf("Attaching ISR: %d, %p\n", vectorno, handler);
+
+    irq_attach(vectorno, handler);
+    up_enable_irq(vectorno);
+//  up_prioritize_irq(vectorno, NVIC_SYSH_PRIORITY_DEFAULT);
+    return OK;
+}
+
+
+static void stm32_tim_enableint(FAR struct stm32_tim_dev_s *dev, int source)
+{
+    ASSERT(dev);
+    stm32_tim_modifyreg(dev, STM32_BTIM_DIER_OFFSET, 0, ATIM_DIER_UIE);
+}
+
+
+static void stm32_tim_disableint(FAR struct stm32_tim_dev_s *dev, int source)
+{
+    ASSERT(dev);
+    stm32_tim_modifyreg(dev, STM32_BTIM_DIER_OFFSET, ATIM_DIER_UIE, 0);
+}
+
+
+static void stm32_tim_ackint(FAR struct stm32_tim_dev_s *dev, int source)
+{
+    stm32_tim_putreg(dev, STM32_BTIM_SR_OFFSET, ~ATIM_SR_UIF);
+}
+
+
+
+/************************************************************************************
+ * General Functions
+ ************************************************************************************/
+
+static int stm32_tim_setmode(FAR struct stm32_tim_dev_s *dev, stm32_tim_mode_t mode)
+{
+    uint16_t val = ATIM_CR1_CEN | ATIM_CR1_ARPE;
+    
+    ASSERT(dev);
+    
+    /* This function is not supported on basic timers. To enable or 
+     * disable it, simply set its clock to valid frequency or zero.
+     */
+    
+#if STM32_NBTIM > 0
+    if (((struct stm32_tim_priv_s *)dev)->base == STM32_TIM6_BASE 
+#endif
+#if STM32_NBTIM > 1
+        ||  ((struct stm32_tim_priv_s *)dev)->base == STM32_TIM7_BASE
+#endif
+#if STM32_NBTIM > 0
+    ) return ERROR;
+#endif
+
+    /* Decode operational modes */
+    
+    switch(mode & STM32_TIM_MODE_MASK) {
+    
+        case STM32_TIM_MODE_DISABLED:
+            val = 0;
+            break;
+        
+        case STM32_TIM_MODE_DOWN:
+            val |= ATIM_CR1_DIR;
+
+        case STM32_TIM_MODE_UP:
+            break;
+            
+        case STM32_TIM_MODE_UPDOWN:
+            val |= ATIM_CR1_CENTER1;
+            // Our default: Interrupts are generated on compare, when counting down
+            break;
+
+        case STM32_TIM_MODE_PULSE:
+            val |= ATIM_CR1_OPM;
+            break;
+        
+        default: return ERROR;
+    }
+    
+    stm32_tim_reload_counter(dev);    
+    stm32_tim_putreg(dev, STM32_BTIM_CR1_OFFSET, val);
+    
+#if STM32_NATIM > 0
+    /* Advanced registers require Main Output Enable */
+    
+    if (((struct stm32_tim_priv_s *)dev)->base == STM32_TIM1_BASE ||
+        ((struct stm32_tim_priv_s *)dev)->base == STM32_TIM8_BASE) {
+        stm32_tim_modifyreg(dev, STM32_ATIM_BDTR_OFFSET, 0, ATIM_BDTR_MOE);
+    }
+#endif
+    
+    return OK;
+}
+
+
+static int stm32_tim_setchannel(FAR struct stm32_tim_dev_s *dev, uint8_t channel, stm32_tim_channel_t mode)
+{
+    uint16_t ccmr_val = 0;
+    uint16_t ccer_val = stm32_tim_getreg(dev, STM32_GTIM_CCER_OFFSET);
+    uint8_t  ccmr_offset = STM32_GTIM_CCMR1_OFFSET;
+    
+    ASSERT(dev);
+    
+    /* Further we use range as 0..3; if channel=0 it will also overflow here */
+    
+    if (--channel > 4) return ERROR;
+        
+    /* Assume that channel is disabled and polarity is active high */
+    
+    ccer_val &= ~(3 << (channel << 2));
+
+    /* This function is not supported on basic timers. To enable or 
+     * disable it, simply set its clock to valid frequency or zero.
+     */
+    
+#if STM32_NBTIM > 0
+    if (   ((struct stm32_tim_priv_s *)dev)->base == STM32_TIM6_BASE 
+#endif
+#if STM32_NBTIM > 1
+        || ((struct stm32_tim_priv_s *)dev)->base == STM32_TIM7_BASE
+#endif
+#if STM32_NBTIM > 0
+       ) return ERROR;
+#endif
+
+    /* Decode configuration */
+    
+    switch(mode & STM32_TIM_CH_MODE_MASK) {
+    
+        case STM32_TIM_CH_DISABLED:
+            break;
+    
+        case STM32_TIM_CH_OUTPWM:
+            ccmr_val  =  (ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC1M_SHIFT) + ATIM_CCMR1_OC1PE;
+            ccer_val |= ATIM_CCER_CC1E << (channel << 2);
+            break;
+            
+        default:
+            return ERROR;
+    }
+    
+    /* Set polarity */
+    
+    if (mode & STM32_TIM_CH_POLARITY_NEG)
+        ccer_val |= ATIM_CCER_CC1P << (channel << 2);
+    
+    /* define its position (shift) and get register offset */
+    
+    if (channel & 1) ccmr_val <<= 8;
+    if (channel > 1) ccmr_offset = STM32_GTIM_CCMR2_OFFSET;    
+
+    stm32_tim_putreg(dev, ccmr_offset, ccmr_val);
+    stm32_tim_putreg(dev, STM32_GTIM_CCER_OFFSET, ccer_val);
+    
+    return OK;
+}
+
+
+static int stm32_tim_setcompare(FAR struct stm32_tim_dev_s *dev, uint8_t channel, uint16_t compare)
+{
+    ASSERT(dev);
+    
+    switch(channel) {
+        case 1: stm32_tim_putreg(dev, STM32_GTIM_CCR1_OFFSET, compare); break;
+        case 2: stm32_tim_putreg(dev, STM32_GTIM_CCR2_OFFSET, compare); break;
+        case 3: stm32_tim_putreg(dev, STM32_GTIM_CCR3_OFFSET, compare); break;
+        case 4: stm32_tim_putreg(dev, STM32_GTIM_CCR4_OFFSET, compare); break;
+        default: return ERROR;
+    }
+    return OK;
+}
+
+
+static int stm32_tim_getcapture(FAR struct stm32_tim_dev_s *dev, uint8_t channel)
+{
+    ASSERT(dev);
+    
+    switch(channel) {
+        case 1: return stm32_tim_getreg(dev, STM32_GTIM_CCR1_OFFSET);
+        case 2: return stm32_tim_getreg(dev, STM32_GTIM_CCR2_OFFSET);
+        case 3: return stm32_tim_getreg(dev, STM32_GTIM_CCR3_OFFSET);
+        case 4: return stm32_tim_getreg(dev, STM32_GTIM_CCR4_OFFSET);
+    }
+    return ERROR;
+}
+
+
+/************************************************************************************
+ * Advanced Functions
+ ************************************************************************************/
+
+/** \todo Advanced functions for the STM32_ATIM */
+	
+
+/************************************************************************************
+ * Device Structures, Instantiation
+ ************************************************************************************/
+
+struct stm32_tim_ops_s stm32_tim_ops = {
+    .setmode        = &stm32_tim_setmode,
+    .setclock       = &stm32_tim_setclock,
+    .setperiod      = &stm32_tim_setperiod,
+    .setchannel     = &stm32_tim_setchannel,
+    .setcompare     = &stm32_tim_setcompare,
+    .getcapture     = &stm32_tim_getcapture,
+    .setisr         = &stm32_tim_setisr,
+    .enableint      = &stm32_tim_enableint,
+    .disableint     = &stm32_tim_disableint,
+    .ackint         = &stm32_tim_ackint
+};
+
+
+struct stm32_tim_priv_s stm32_tim3_priv = {
+    .ops        = &stm32_tim_ops,
+    .mode       = STM32_TIM_MODE_UNUSED,
+    .base       = STM32_TIM3_BASE,
+};
+
+#if STM32_NATIM > 0
+
+struct stm32_tim_priv_s stm32_tim1_priv = {
+    .ops        = &stm32_tim_ops,
+    .mode       = STM32_TIM_MODE_UNUSED,
+    .base       = STM32_TIM1_BASE,
+};
+
+struct stm32_tim_priv_s stm32_tim8_priv = {
+    .ops        = &stm32_tim_ops,
+    .mode       = STM32_TIM_MODE_UNUSED,
+    .base       = STM32_TIM8_BASE,
+};
+
+#endif
+
+
+/************************************************************************************
+ * Public Function - Initialization
+ ************************************************************************************/
+
+FAR struct stm32_tim_dev_s * stm32_tim_init(int timer)
+{
+    struct stm32_tim_dev_s * dev = NULL;
+        
+    /* Get structure and enable power */
+    
+    switch(timer) {
+        case 3: 
+            dev = (struct stm32_tim_dev_s *)&stm32_tim3_priv; 
+            modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_TIM3EN);
+            break;
+        
+#if STM32_NATIM > 0
+        case 1: 
+            dev = (struct stm32_tim_dev_s *)&stm32_tim1_priv; 
+            modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_TIM1EN);
+            break;
+            
+        case 8: 
+            dev = (struct stm32_tim_dev_s *)&stm32_tim8_priv; 
+            modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_TIM8EN);
+            break;
+#endif
+        default: return NULL;
+    }
+    
+    /* Is device already allocated */
+    
+    if ( ((struct stm32_tim_priv_s *)dev)->mode != STM32_TIM_MODE_UNUSED)
+        return NULL;
+        
+    stm32_tim_reset(dev);
+        
+    return dev;
+}
+
+
+int stm32_tim_deinit(FAR struct stm32_tim_dev_s * dev)
+{
+    ASSERT(dev);
+    
+    /* Disable power */
+    
+    switch( ((struct stm32_tim_priv_s *)dev)->base ) {
+        case STM32_TIM3_BASE: modifyreg32(STM32_RCC_APB1ENR, RCC_APB1ENR_TIM3EN, 0);  break;
+        
+#if STM32_NATIM > 0
+        case STM32_TIM1_BASE: modifyreg32(STM32_RCC_APB2ENR, RCC_APB2ENR_TIM1EN, 0);  break;
+        case STM32_TIM8_BASE: modifyreg32(STM32_RCC_APB2ENR, RCC_APB2ENR_TIM8EN, 0);  break;
+#endif
+        default: return ERROR;
+    }
+    
+    /* Mark it as free */
+    
+    ((struct stm32_tim_priv_s *)dev)->mode = STM32_TIM_MODE_UNUSED;
+        
+    return OK;
+}
diff --git a/arch/arm/src/stm32/stm32_tim.h b/arch/arm/src/stm32/stm32_tim.h
index 21b37bb72e1e487c681e2fd04ee205dbb51bdfcc..60cbec69196981f2cfa8f8f022db264c1b022044 100644
--- a/arch/arm/src/stm32/stm32_tim.h
+++ b/arch/arm/src/stm32/stm32_tim.h
@@ -2,7 +2,9 @@
  * arch/arm/src/stm32/stm32_tim.h
  *
  *   Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ *   Copyright (C) 2011 Uros Platise. All rights reserved.
  *   Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *           Uros Platise <uros.platise@isotel.eu>
  *
  * Redistribution and use in source and binary forms, with or without
  * modification, are permitted provided that the following conditions
@@ -33,6 +35,11 @@
  *
  ************************************************************************************/
 
+/** \file
+ *  \author Gregory Nutt, Uros Platise
+ *  \brief STM32 Timers
+ */
+
 #ifndef __ARCH_ARM_SRC_STM32_STM32_TIM_H
 #define __ARCH_ARM_SRC_STM32_STM32_TIM_H
 
@@ -41,7 +48,6 @@
  ************************************************************************************/
 
 #include <nuttx/config.h>
-
 #include "chip.h"
 
 /************************************************************************************
@@ -50,28 +56,16 @@
 
 /* Register Offsets *****************************************************************/
 
-/* Advanced Timers - TIM1 and TIM8 */
+/* Basic Timers - TIM6 and TIM7 */
 
-#define STM32_ATIM_CR1_OFFSET     0x0000  /* Control register 1 (16-bit) */
-#define STM32_ATIM_CR2_OFFSET     0x0004  /* Control register 2 *(16-bit) */
-#define STM32_ATIM_SMCR_OFFSET    0x0008  /* Slave mode control register (16-bit) */
-#define STM32_ATIM_DIER_OFFSET    0x000c  /* DMA/Interrupt enable register (16-bit) */
-#define STM32_ATIM_SR_OFFSET      0x0010  /* Status register (16-bit) */
-#define STM32_ATIM_EGR_OFFSET     0x0014  /* Event generation register (16-bit) */
-#define STM32_ATIM_CCMR1_OFFSET   0x0018  /* Capture/compare mode register 1 (16-bit) */
-#define STM32_ATIM_CCMR2_OFFSET   0x001c  /* Capture/compare mode register 2 (16-bit) */
-#define STM32_ATIM_CCER_OFFSET    0x0020  /* Capture/compare enable register (16-bit) */
-#define STM32_ATIM_CNT_OFFSET     0x0024  /* Counter (16-bit) */
-#define STM32_ATIM_PSC_OFFSET     0x0028  /* Prescaler (16-bit) */
-#define STM32_ATIM_ARR_OFFSET     0x002c  /* Auto-reload register (16-bit) */
-#define STM32_ATIM_RCR_OFFSET     0x0030  /* Repetition counter register (16-bit) */
-#define STM32_ATIM_CCR1_OFFSET    0x0034  /* Capture/compare register 1 (16-bit) */
-#define STM32_ATIM_CCR2_OFFSET    0x0038  /* Capture/compare register 2 (16-bit) */
-#define STM32_ATIM_CCR3_OFFSET    0x003c  /* Capture/compare register 3 (16-bit) */
-#define STM32_ATIM_CCR4_OFFSET    0x0040  /* Capture/compare register 4 (16-bit) */
-#define STM32_ATIM_BDTR_OFFSET    0x0044  /* Break and dead-time register (16-bit) */
-#define STM32_ATIM_DCR_OFFSET     0x0048  /* DMA control register (16-bit) */
-#define STM32_ATIM_DMAR_OFFSET    0x004c  /* DMA address for burst mode (16-bit) */
+#define STM32_BTIM_CR1_OFFSET     0x0000  /* Control register 1 (16-bit) */
+#define STM32_BTIM_CR2_OFFSET     0x0004  /* Control register 2 (16-bit) */
+#define STM32_BTIM_DIER_OFFSET    0x000c  /* DMA/Interrupt enable register (16-bit) */
+#define STM32_BTIM_SR_OFFSET      0x0010  /* Status register (16-bit) */
+#define STM32_BTIM_EGR_OFFSET     0x0014  /* Event generation register (16-bit) */
+#define STM32_BTIM_CNT_OFFSET     0x0024  /* Counter (16-bit) */
+#define STM32_BTIM_PSC_OFFSET     0x0028  /* Prescaler (16-bit) */
+#define STM32_BTIM_ARR_OFFSET     0x002c  /* Auto-reload register (16-bit) */
 
 /* General Timers - TIM2, TIM3, TIM4, and TIM5 */
 
@@ -94,16 +88,28 @@
 #define STM32_GTIM_DCR_OFFSET     0x0048  /* DMA control register (16-bit) */
 #define STM32_GTIM_DMAR_OFFSET    0x004c  /* DMA address for burst mode (16-bit) */
 
-/* Basic Timers - TIM6 and TIM7 */
+/* Advanced Timers - TIM1 and TIM8 */
 
-#define STM32_BTIM_CR1_OFFSET     0x0000  /* Control register 1 (16-bit) */
-#define STM32_BTIM_CR2_OFFSET     0x0004  /* Control register 2 (16-bit) */
-#define STM32_BTIM_DIER_OFFSET    0x000c  /* DMA/Interrupt enable register (16-bit) */
-#define STM32_BTIM_SR_OFFSET      0x0010  /* Status register (16-bit) */
-#define STM32_BTIM_EGR_OFFSET     0x0014  /* Event generation register (16-bit) */
-#define STM32_BTIM_CNT_OFFSET     0x0024  /* Counter (16-bit) */
-#define STM32_BTIM_PSC_OFFSET     0x0028  /* Prescaler (16-bit) */
-#define STM32_BTIM_ARR_OFFSET     0x002c  /* Auto-reload register (16-bit) */
+#define STM32_ATIM_CR1_OFFSET     0x0000  /* Control register 1 (16-bit) */
+#define STM32_ATIM_CR2_OFFSET     0x0004  /* Control register 2 *(16-bit) */
+#define STM32_ATIM_SMCR_OFFSET    0x0008  /* Slave mode control register (16-bit) */
+#define STM32_ATIM_DIER_OFFSET    0x000c  /* DMA/Interrupt enable register (16-bit) */
+#define STM32_ATIM_SR_OFFSET      0x0010  /* Status register (16-bit) */
+#define STM32_ATIM_EGR_OFFSET     0x0014  /* Event generation register (16-bit) */
+#define STM32_ATIM_CCMR1_OFFSET   0x0018  /* Capture/compare mode register 1 (16-bit) */
+#define STM32_ATIM_CCMR2_OFFSET   0x001c  /* Capture/compare mode register 2 (16-bit) */
+#define STM32_ATIM_CCER_OFFSET    0x0020  /* Capture/compare enable register (16-bit) */
+#define STM32_ATIM_CNT_OFFSET     0x0024  /* Counter (16-bit) */
+#define STM32_ATIM_PSC_OFFSET     0x0028  /* Prescaler (16-bit) */
+#define STM32_ATIM_ARR_OFFSET     0x002c  /* Auto-reload register (16-bit) */
+#define STM32_ATIM_RCR_OFFSET     0x0030  /* Repetition counter register (16-bit) */
+#define STM32_ATIM_CCR1_OFFSET    0x0034  /* Capture/compare register 1 (16-bit) */
+#define STM32_ATIM_CCR2_OFFSET    0x0038  /* Capture/compare register 2 (16-bit) */
+#define STM32_ATIM_CCR3_OFFSET    0x003c  /* Capture/compare register 3 (16-bit) */
+#define STM32_ATIM_CCR4_OFFSET    0x0040  /* Capture/compare register 4 (16-bit) */
+#define STM32_ATIM_BDTR_OFFSET    0x0044  /* Break and dead-time register (16-bit) */
+#define STM32_ATIM_DCR_OFFSET     0x0048  /* DMA control register (16-bit) */
+#define STM32_ATIM_DMAR_OFFSET    0x004c  /* DMA address for burst mode (16-bit) */
 
 /* Register Addresses ***************************************************************/
 
@@ -269,23 +275,23 @@
 
 /* Control register 1 */
 
-#define ATIM_SR_CEN               (1 << 0)  /* Bit 0: Counter enable */
-#define ATIM_SR_UDIS              (1 << 1)  /* Bit 1: Update disable */
-#define ATIM_SR_URS               (1 << 2)  /* Bit 2: Update request source */
-#define ATIM_SR_OPM               (1 << 3)  /* Bit 3: One pulse mode */
-#define ATIM_SR_DIR               (1 << 4)  /* Bit 4: Direction */
-#define ATIM_SR_CMS_SHIFT         (5)       /* Bits 6-5: Center-aligned mode selection */
-#define ATIM_SR_CMS_MASK          (3 << ATIM_SR_CMS_SHIFT)
-#  define ATIM_SR_EDGE            (0 << ATIM_SR_CMS_SHIFT) /* 00: Edge-aligned mode */
-#  define ATIM_SR_CENTER1         (1 << ATIM_SR_CMS_SHIFT) /* 01: Center-aligned mode 1 */
-#  define ATIM_SR_CENTER2         (2 << ATIM_SR_CMS_SHIFT) /* 10: Center-aligned mode 2 */
-#  define ATIM_SR_CENTER3         (3 << ATIM_SR_CMS_SHIFT) /* 11: Center-aligned mode 3 */
-#define ATIM_SR_ARPE              (1 << 7)  /* Bit 7: Auto-reload preload enable */
-#define ATIM_SR_CKD_SHIFT         (8)       /* Bits 9-8: Clock division */
-#define ATIM_SR_CKD_MASK          (3 << ATIM_SR_CKD_SHIFT)
-#  define ATIM_SR_TCKINT          (0 << ATIM_SR_CKD_SHIFT) /* 00: tDTS=tCK_INT */
-#  define ATIM_SR_2TCKINT         (1 << ATIM_SR_CKD_SHIFT) /* 01: tDTS=2*tCK_INT */
-#  define ATIM_SR_4TCKINT         (2 << ATIM_SR_CKD_SHIFT) /* 10: tDTS=4*tCK_INT */
+#define ATIM_CR1_CEN               (1 << 0)  /* Bit 0: Counter enable */
+#define ATIM_CR1_UDIS              (1 << 1)  /* Bit 1: Update disable */
+#define ATIM_CR1_URS               (1 << 2)  /* Bit 2: Update request source */
+#define ATIM_CR1_OPM               (1 << 3)  /* Bit 3: One pulse mode */
+#define ATIM_CR1_DIR               (1 << 4)  /* Bit 4: Direction */
+#define ATIM_CR1_CMS_SHIFT         (5)       /* Bits 6-5: Center-aligned mode selection */
+#define ATIM_CR1_CMS_MASK          (3 << ATIM_CR1_CMS_SHIFT)
+#  define ATIM_CR1_EDGE            (0 << ATIM_CR1_CMS_SHIFT) /* 00: Edge-aligned mode */
+#  define ATIM_CR1_CENTER1         (1 << ATIM_CR1_CMS_SHIFT) /* 01: Center-aligned mode 1 */
+#  define ATIM_CR1_CENTER2         (2 << ATIM_CR1_CMS_SHIFT) /* 10: Center-aligned mode 2 */
+#  define ATIM_CR1_CENTER3         (3 << ATIM_CR1_CMS_SHIFT) /* 11: Center-aligned mode 3 */
+#define ATIM_CR1_ARPE              (1 << 7)  /* Bit 7: Auto-reload preload enable */
+#define ATIM_CR1_CKD_SHIFT         (8)       /* Bits 9-8: Clock division */
+#define ATIM_CR1_CKD_MASK          (3 << ATIM_CR1_CKD_SHIFT)
+#  define ATIM_CR1_TCKINT          (0 << ATIM_CR1_CKD_SHIFT) /* 00: tDTS=tCK_INT */
+#  define ATIM_CR1_2TCKINT         (1 << ATIM_CR1_CKD_SHIFT) /* 01: tDTS=2*tCK_INT */
+#  define ATIM_CR1_4TCKINT         (2 << ATIM_CR1_CKD_SHIFT) /* 10: tDTS=4*tCK_INT */
 
 /* Control register 2 */
 
@@ -508,7 +514,7 @@
 
                                             /* Bits 1-0:(same as output compare mode) */
 #define ATIM_CCMR2_IC3PSC_SHIFT   (2)       /* Bits 3-2: Input Capture 3 Prescaler */
-#define ATIM_CCMR1_IC1PSC_MASK    (3 << ATIM_CCMR2_IC3PSC_SHIFT)
+#define ATIM_CCMR1_IC3PSC_MASK    (3 << ATIM_CCMR2_IC3PSC_SHIFT)
                                             /* (See common (unshifted) bit field definitions above) */
 #define ATIM_CCMR2_IC3F_SHIFT     (4)       /* Bits 7-4: Input Capture 3 Filter */
 #define ATIM_CCMR2_IC3F_MASK      (0x0f << ATIM_CCMR2_IC3F_SHIFT)
@@ -589,7 +595,7 @@
 
 /* Control register 2 */
 
-#define GTIM_CR2_CCDS             (1 << 3)  /* Bit 3: Capture/Compare DMA Selection.
+#define GTIM_CR2_CCDS             (1 << 3)  /* Bit 3: Capture/Compare DMA Selection. */
 #define GTIM_CR2_MMS_SHIFT        (4)       /* Bits 6-4: Master Mode Selection */
 #define GTIM_CR2_MMS_MASK         (7 << GTIM_CR2_MMS_SHIFT)
 #  define GTIM_CR2_RESET          (0 << GTIM_CR2_MMS_SHIFT) /* 000: Reset */
@@ -609,7 +615,7 @@
 #  define GTIM_SMCR_DISAB         (0 << GTIM_SMCR_SMS_SHIFT) /* 000: Slave mode disabled */
 #  define GTIM_SMCR_ENCMD1        (1 << GTIM_SMCR_SMS_SHIFT) /* 001: Encoder mode 1 */
 #  define GTIM_SMCR_ENCMD2        (2 << GTIM_SMCR_SMS_SHIFT) /* 010: Encoder mode 2 */
-#  define GTIM_SMCR_ENCMD2        (3 << GTIM_SMCR_SMS_SHIFT) /* 011: Encoder mode 3 */
+#  define GTIM_SMCR_ENCMD3        (3 << GTIM_SMCR_SMS_SHIFT) /* 011: Encoder mode 3 */
 #  define GTIM_SMCR_RESET         (4 << GTIM_SMCR_SMS_SHIFT) /* 100: Reset Mode  */
 #  define GTIM_SMCR_GATED         (5 << GTIM_SMCR_SMS_SHIFT) /* 101: Gated Mode  */
 #  define GTIM_SMCR_TRIGGER       (6 << GTIM_SMCR_SMS_SHIFT) /* 110: Trigger Mode */
@@ -856,17 +862,117 @@
 
 #define BTIM_EGR_UG               (1 << 0)  /* Bit 0: Update generation */
 
+
 /************************************************************************************
  * Public Types
  ************************************************************************************/
 
-/************************************************************************************
- * Public Data
- ************************************************************************************/
+/** TIM Device Structure
+ */
+struct stm32_tim_dev_s {
+    struct stm32_tim_ops_s *ops;
+};
+
+
+/** TIM Modes of Operation
+ */
+typedef enum {
+    STM32_TIM_MODE_UNUSED       = -1,
+    
+    /* One of the following */
+    STM32_TIM_MODE_MASK         = 0x0300,
+    STM32_TIM_MODE_DISABLED     = 0x0000,
+    STM32_TIM_MODE_UP           = 0x0100,
+    STM32_TIM_MODE_DOWN         = 0x0110,
+    STM32_TIM_MODE_UPDOWN       = 0x0200,
+    STM32_TIM_MODE_PULSE        = 0x0300,
+    
+    /* One of the following */
+    STM32_TIM_MODE_CK_INT       = 0x0000,
+//  STM32_TIM_MODE_CK_INT_TRIG  = 0x0400,
+//  STM32_TIM_MODE_CK_EXT       = 0x0800,
+//  STM32_TIM_MODE_CK_EXT_TRIG  = 0x0C00,
+
+    /* Clock sources, OR'ed with CK_EXT */
+//  STM32_TIM_MODE_CK_CHINVALID = 0x0000,
+//  STM32_TIM_MODE_CK_CH1       = 0x0001,
+//  STM32_TIM_MODE_CK_CH2       = 0x0002,
+//  STM32_TIM_MODE_CK_CH3       = 0x0003,
+//  STM32_TIM_MODE_CK_CH4       = 0x0004
+    
+    /* Todo: external trigger block */
+    
+} stm32_tim_mode_t;
+
+
+/** TIM Channel Modes
+ */
+typedef enum {
+    STM32_TIM_CH_DISABLED       = 0x00,
+    
+    /* Common configuration */
+    STM32_TIM_CH_POLARITY_POS   = 0x00,
+    STM32_TIM_CH_POLARITY_NEG   = 0x01,
+    
+    /* MODES: */
+    STM32_TIM_CH_MODE_MASK      = 0x06,
+    
+    /* Output Compare Modes */
+    STM32_TIM_CH_OUTPWM         = 0x04,     /** Enable standard PWM mode, active high when counter < compare */
+//  STM32_TIM_CH_OUTCOMPARE     = 0x06,
+    
+    // TODO other modes ... as PWM capture, ENCODER and Hall Sensor
+//  STM32_TIM_CH_INCAPTURE      = 0x10,
+//  STM32_TIM_CH_INPWM          = 0x20
+    
+} stm32_tim_channel_t;
+
+
+/** TIM Operations
+ */
+struct stm32_tim_ops_s {
+
+    /* Basic Timers */
+    
+    int	    (*setmode)(FAR struct stm32_tim_dev_s *dev, stm32_tim_mode_t mode);
+    int     (*setclock)(FAR struct stm32_tim_dev_s *dev, uint32_t freq);
+    void    (*setperiod)(FAR struct stm32_tim_dev_s *dev, uint16_t period);
+    
+    /* General and Advanced Timers Adds */
+    
+    int     (*setchannel)(FAR struct stm32_tim_dev_s *dev, uint8_t channel, stm32_tim_channel_t mode);
+    int	    (*setcompare)(FAR struct stm32_tim_dev_s *dev, uint8_t channel, uint16_t compare);
+    int	    (*getcapture)(FAR struct stm32_tim_dev_s *dev, uint8_t channel);
+    
+    int     (*setisr)(FAR struct stm32_tim_dev_s *dev, int (*handler)(int irq, void *context), int source);
+    void    (*enableint)(FAR struct stm32_tim_dev_s *dev, int source);
+    void    (*disableint)(FAR struct stm32_tim_dev_s *dev, int source);
+    void    (*ackint)(FAR struct stm32_tim_dev_s *dev, int source);
+};
+
+
+/* Helpers */
+
+#define STM32_TIM_SETMODE(d,mode)       ((d)->ops->setmode(d,mode))
+#define STM32_TIM_SETCLOCK(d,freq)      ((d)->ops->setclock(d,freq))
+#define STM32_TIM_SETPERIOD(d,period)   ((d)->ops->setperiod(d,period))
+#define STM32_TIM_SETCHANNEL(d,ch,mode) ((d)->ops->setchannel(d,ch,mode))
+#define STM32_TIM_SETCOMPARE(d,ch,comp) ((d)->ops->setcompare(d,ch,comp))
+#define STM32_TIM_GETCAPTURE(d,ch)      ((d)->ops->getcapture(d,ch))
+#define STM32_TIM_SETISR(d,hnd,s)       ((d)->ops->setisr(d,hnd,s))
+#define STM32_TIM_ENABLEINT(d,s)        ((d)->ops->enableint(d,s))
+#define STM32_TIM_DISABLEINT(d,s)       ((d)->ops->disableint(d,s))
+#define STM32_TIM_ACKINT(d,s)           ((d)->ops->ackint(d,s))
 
 /************************************************************************************
  * Public Functions
  ************************************************************************************/
 
+/** Power-up timer and get its structure */
+FAR struct stm32_tim_dev_s * stm32_tim_init(int timer);
+
+/** Power-down timer, mark it as unused */
+int stm32_tim_deinit(FAR struct stm32_tim_dev_s * dev);
+
 #endif /* __ARCH_ARM_SRC_STM32_STM32_TIM_H */
 
diff --git a/configs/vsn/include/board.h b/configs/vsn/include/board.h
index f5c690f1e040ee8084f952f76bdd103fe46bd722..733f1fc32434f9b4c0fd0c9f36900dc36ae93bd0 100644
--- a/configs/vsn/include/board.h
+++ b/configs/vsn/include/board.h
@@ -105,7 +105,8 @@
 
 /* On-board external frequency source is 9MHz (HSE) provided by the CC1101, so it is
  * not available on power-up. Instead we are about to run on HSI*9 = 36 MHz, see 
- * up_sysclock.c for details. */
+ * up_sysclock.c for details. 
+ */
 
 #define STM32_BOARD_XTAL        9000000UL
 #define STM32_BOARD_HCLK       36000000UL
@@ -114,6 +115,7 @@
  * When HSI: PLL multiplier is 9, out frequency 36 MHz
  * When HSE: PLL multiplier is 8: out frequency is 9 MHz x 8 = 72MHz 
  */
+ 
 #define STM32_CFGR_PLLSRC_HSI  0
 #define STM32_CFGR_PLLMUL_HSI  RCC_CFGR_PLLMUL_CLKx9
 
@@ -134,13 +136,18 @@
 
 /* APB2 clock (PCLK2) is HCLK (36MHz) */
 
-#define STM32_RCC_CFGR_PPRE2   RCC_CFGR_PPRE2_HCLK
-#define STM32_PCLK2_FREQUENCY  STM32_BOARD_HCLK
+#define STM32_RCC_CFGR_PPRE2    RCC_CFGR_PPRE2_HCLK
+#define STM32_PCLK2_FREQUENCY   STM32_BOARD_HCLK
 
 /* APB1 clock (PCLK1) is HCLK (36MHz) */
 
-#define STM32_RCC_CFGR_PPRE1   RCC_CFGR_PPRE1_HCLK
-#define STM32_PCLK1_FREQUENCY  STM32_BOARD_HCLK
+#define STM32_RCC_CFGR_PPRE1    RCC_CFGR_PPRE1_HCLK
+#define STM32_PCLK1_FREQUENCY   STM32_BOARD_HCLK
+
+/* Timer 1..8 Frequencies */
+
+#define STM32_TIM27_FREQUENCY   (STM32_BOARD_HCLK)
+#define STM32_TIM18_FREQUENCY   (STM32_BOARD_HCLK)
 
 /* USB divider -- Divide PLL clock by 1.5 */
 
@@ -247,28 +254,10 @@ EXTERN uint8_t up_buttons(void);
 #endif
 
 
-/************************************************************************************
- * Memories
- *  - SDcard is tested to work up to 2 GB
- *  - RAMTRON has size of 128 kB
- ************************************************************************************/
-
-EXTERN int up_sdcard(void);
-EXTERN int up_ramtron(void);
-
-
-/************************************************************************************
- * Public Power Supply Contol
- ************************************************************************************/
-
-void board_power_reboot(void);
-void board_power_off(void);
-
-
 #undef EXTERN
 #if defined(__cplusplus)
 }
 #endif
 
 #endif /* __ASSEMBLY__ */
-#endif  /* __ARCH_BOARD_BOARD_H */
+#endif /* __ARCH_BOARD_BOARD_H */
diff --git a/configs/vsn/include/power.h b/configs/vsn/include/power.h
index 960c40fb1f9a22312c4492a4ba0b5dcf67e6c488..5be7ab7950e9e2aa7a31455c1d3de6397b31ad07 100644
--- a/configs/vsn/include/power.h
+++ b/configs/vsn/include/power.h
@@ -38,11 +38,6 @@
 #ifndef __ARCH_BOARD_POWER_H
 #define __ARCH_BOARD_POWER_H
 
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
 #ifndef __ASSEMBLY__
 #undef EXTERN
 #if defined(__cplusplus)
@@ -53,15 +48,21 @@ extern "C" {
 #endif
 
 /************************************************************************************
- * Public Power Supply Contol
+ * Public Functions
  ************************************************************************************/
 
+/** Perform system reset on board level
+ */
 void board_power_reboot(void);
 
-/* If this function returns, it means, that it was not possible to power-off the board */
+/** Power off the board
+ * 
+ * If it returns, then it was not possible to power-off the board due to some
+ * other constraints. In the case of VSN due to external power supply, press
+ * of a push-button or RTC alarm.
+ */
 void board_power_off(void);
 
-
 #undef EXTERN
 #if defined(__cplusplus)
 }
diff --git a/configs/vsn/nsh/defconfig b/configs/vsn/nsh/defconfig
index a6fffc4c6e3ad2caff9dedaa60c1177f50ff3956..b4055a00e30a92c22c3b8906f2ad175a277a9a95 100755
--- a/configs/vsn/nsh/defconfig
+++ b/configs/vsn/nsh/defconfig
@@ -750,7 +750,7 @@ CONFIG_NSH_DISABLEBG=n
 CONFIG_NSH_ROMFSETC=y
 CONFIG_NSH_CONSOLE=y
 CONFIG_NSH_TELNET=n
-CONFIG_NSH_ARCHINIT=y
+CONFIG_NSH_ARCHINIT=n
 CONFIG_NSH_IOBUFFER_SIZE=512
 CONFIG_NSH_DHCPC=n
 CONFIG_NSH_NOMAC=n
@@ -831,3 +831,7 @@ CONFIG_PTHREAD_STACK_MIN=256
 CONFIG_PTHREAD_STACK_DEFAULT=2048
 CONFIG_HEAP_BASE=
 CONFIG_HEAP_SIZE=
+
+# Application configuration
+
+CONFIG_APPS_DIR="../apps"
diff --git a/configs/vsn/src/Makefile b/configs/vsn/src/Makefile
index 8b00da4a7a267b5c9f00bee52cbd1cbe97dbdbc1..66ea8f32f61eb59a4ef2bdc064d89d6eb3d1010b 100644
--- a/configs/vsn/src/Makefile
+++ b/configs/vsn/src/Makefile
@@ -38,17 +38,23 @@
 
 -include $(TOPDIR)/Make.defs
 
+#$(TOPDIR)/$(CONFIG_APPS_DIR)
+APPDIR		= $(TOPDIR)/../apps/
+
+-include $(APPDIR)/Make.defs
+
+APPNAME		= sif
+PRIORITY	= SCHED_PRIORITY_DEFAULT
+STACKSIZE	= 4096
+
 CFLAGS		+= -I$(TOPDIR)/sched
 
 ASRCS		= 
 AOBJS		= $(ASRCS:.S=$(OBJEXT))
 
 CSRCS		= sysclock.c boot.c leds.c buttons.c spi.c \
-			  usbdev.c power.c
+			  usbdev.c power.c sif.c
 
-ifeq ($(CONFIG_NSH_ARCHINIT),y)
-CSRCS		+= nsh.c
-endif
 ifeq ($(CONFIG_USBSTRG),y)
 CSRCS		+= usbstrg.c
 endif
@@ -79,6 +85,16 @@ libboard$(LIBEXT): $(OBJS)
 		$(call ARCHIVE, $@, $${obj}); \
 	done ; )
 
+# Register application
+
+.context:
+	$(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main)
+	@touch $@
+
+context: .context
+
+# Create dependencies
+
 .depend: Makefile $(SRCS)
 	@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
 	@touch $@
@@ -90,6 +106,6 @@ clean:
 	$(call CLEAN)
 
 distclean: clean
-	@rm -f Make.dep .depend
+	@rm -f Make.dep .depend .context
 
 -include Make.dep
diff --git a/configs/vsn/src/README.txt b/configs/vsn/src/README.txt
index bacf82c17e2550eeb8b9e8a971fa16175fbf37fc..81f3ee4e12498dc00eada90194967812801c40ab 100644
--- a/configs/vsn/src/README.txt
+++ b/configs/vsn/src/README.txt
@@ -1,4 +1,8 @@
 
+VSN Board Support Package, for the NuttX, Uros Platise <uros.platise@isotel.eu>
+===============================================================================
+http://www.netClamps.com
+
 The directory contains start-up and board level functions. 
 Execution starts in the following order:
 
@@ -8,5 +12,47 @@ Execution starts in the following order:
    is set. It must be set for the VSN board.
    
  - boot, performs initial chip and board initialization
- - ...
- - nsh, as central application last.
+ - sched/os_bringup.c then calls either user_start or exec_nuttapp()
+   with application as set in the .config
+
+
+Naming throughout the code
+==========================
+
+ - _init(): used to be called once only, after powerup, to perform board
+   initialization
+ - _start() or called via FS _open(): starts peripheral power, puts it 
+   into operation
+ - _stop() or called via FS _close(): opposite to _start()
+ 
+
+System notifications (a sort of run-levels)
+===========================================
+
+On the VSN, NSH represents the core application as it supports scripts
+easily adaptable for any custom application configuration. NSH is 
+invoked as follows (argument runs a script from the /etc/init.d directory):
+
+ - nsh init: on system powerup called by the NuttX APP_START
+
+TODOs: 
+ 
+ - nsh xpowerup: run on external power used to:
+   - try to setup an USB serial connection
+   - configure SLIP mode, internet
+   - start other internet services, such as telnetd, ftpd, httpd
+   
+ - nsh xpowerdown: run whenever USB recevied suspend signal or
+   external power has been removed.
+   - used to stop internet services
+   
+ - nsh batdown: whenever battery is completely discharged
+
+   
+Compile notes
+===============================
+
+To link-in the sif_main() utility do, in this folder:
+ - make context TOPDIR=<path to nuttx top dir>
+ 
+This will result in registering the application into the nuttapp.
diff --git a/configs/vsn/src/boot.c b/configs/vsn/src/boot.c
index eb4ba9ef57213f165ef60b33d33f0145abe7031b..501bb07b5a593c21a5a0ac35100677de4d29b612 100644
--- a/configs/vsn/src/boot.c
+++ b/configs/vsn/src/boot.c
@@ -37,41 +37,26 @@
  *
  ************************************************************************************/
 
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <nuttx/config.h>
+/** \file
+ *  \author Gregory Nutt, Uros Platise
+ *  \brief VSN Button
+ */
 
 #include <debug.h>
-
-#include <arch/board/board.h>
-
-#include "stm32_gpio.h"
-#include "up_arch.h"
 #include "vsn.h"
 
-/************************************************************************************
- * Definitions
- ************************************************************************************/
-
-/************************************************************************************
- * Private Functions
- ************************************************************************************/
 
 /************************************************************************************
  * Public Functions
  ************************************************************************************/
 
-/************************************************************************************
- * Name: stm32_boardinitialize
+/** Initialize Board
  *
- * Description:
  *   All STM32 architectures must provide the following entry point.  This entry point
  *   is called early in the intitialization -- after all memory has been configured
  *   and mapped but before any devices have been initialized.
  *
- ************************************************************************************/
+ **/
 
 void stm32_boardinitialize(void)
 {
diff --git a/configs/vsn/src/buttons.c b/configs/vsn/src/buttons.c
index 3025b373c014135d177088559e0623e5dce83165..c0a0f72975f64542b27c3e9fc790cf6a523463be 100644
--- a/configs/vsn/src/buttons.c
+++ b/configs/vsn/src/buttons.c
@@ -1,11 +1,9 @@
 /****************************************************************************
  * configs/vsn/src/buttons.c
  *
- *   Copyright (C) 2009 Gregory Nutt. All rights reserved.
  *   Copyright (C) 2011 Uros Platise. All rights reserved.
  *
- *   Authors: Gregory Nutt <spudmonkey@racsa.co.cr>
- *            Uros Platise <uros.platise@isotel.eu>
+ *   Authors: Uros Platise <uros.platise@isotel.eu>
  *
  * Redistribution and use in source and binary forms, with or without
  * modification, are permitted provided that the following conditions
@@ -36,17 +34,18 @@
  *
  ****************************************************************************/
 
-/****************************************************************************
- * Included Files
- ****************************************************************************/
+/** \file
+ *  \author Uros Platise
+ *  \brief VSN Button
+ */
+
+#ifdef CONFIG_ARCH_BUTTONS
 
 #include <nuttx/config.h>
 #include <stdint.h>
 #include <arch/board/board.h>
 #include "vsn.h"
 
-#ifdef CONFIG_ARCH_BUTTONS
-
 /****************************************************************************
  * Definitions
  ****************************************************************************/
@@ -59,12 +58,19 @@
  * Private Functions
  ****************************************************************************/
 
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
+/** Called from an interrupt
+ * 
+ * \todo Measure the time button is being pressed, and then:
+ *  - if short signal all processes (tasks and threads) with 'button user request': SIGUSR1
+ *  - if long (>0.5 s) signal all with 'power-off request': SIGTERM
+ **/ 
+void buttons_callback(void)
+{
+}
+
 
 /****************************************************************************
- * Name: up_buttoninit
+ * Public Functions
  ****************************************************************************/
 
 void up_buttoninit(void)
@@ -72,13 +78,11 @@ void up_buttoninit(void)
   stm32_configgpio(GPIO_PUSHBUTTON);
 }
 
-/****************************************************************************
- * Name: up_buttons
- ****************************************************************************/
 
 uint8_t up_buttons(void)
 {
   return stm32_gpioread(GPIO_PUSHBUTTON);
 }
 
+
 #endif /* CONFIG_ARCH_BUTTONS */
diff --git a/configs/vsn/src/chipcon.c b/configs/vsn/src/chipcon.c
new file mode 100644
index 0000000000000000000000000000000000000000..c4428d66ff89efb3ef6ff6f739f996de071910f8
--- /dev/null
+++ b/configs/vsn/src/chipcon.c
@@ -0,0 +1,83 @@
+/****************************************************************************
+ * configs/vsn/src/chipcon.c
+ *
+ *   Copyright (C) 2011 Uros Platise. All rights reserved.
+ * 
+ *   Author: Uros Platise <uros.platise@isotel.eu>
+ *
+ * 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 NuttX 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 COPYRIGHT HOLDERS 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
+ * COPYRIGHT OWNER 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.
+ *
+ ****************************************************************************/
+
+/** \file
+ *  \author Uros Platise
+ *  \brief Chipcon CC1101 Interface
+ */
+
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/** Set external clock frequency, or disable it
+ */
+int chipcon_setXclock(int prescaler)
+{
+	// check present state, if it is enabled (in the chip!)
+	
+	// change state and with OK if everything is OK.
+	
+	return ERROR;
+}
+
+
+int chipcon_setchannel(uint16_t channel)
+{
+}
+
+
+void chipcon_init(int spino)
+{
+	// create stream driver, where STDIN is packet oriented
+	// means that two messages received are kept separated
+	// in internal buffers.
+	
+	// default mode is AUTO, RX enabled and auto TX on writes and
+	// when chipcon is IDLE.
+}
+
+
+void chipcon_open(void)
+{
+}
+
+
+void chipcon_ioctl(void)
+{
+	// access to setXclock
+}
diff --git a/configs/vsn/src/leds.c b/configs/vsn/src/leds.c
index c1cc1c573fa2216bd5522e5869939a7ada1026d0..e440e5fce3db5ba30303aa472cc16f5cdc273baa 100644
--- a/configs/vsn/src/leds.c
+++ b/configs/vsn/src/leds.c
@@ -2,11 +2,9 @@
  * configs/vsn/src/leds.c
  * arch/arm/src/board/leds.c
  *
- *   Copyright (C) 2009 Gregory Nutt. All rights reserved.
  *   Copyright (C) 2011 Uros Platise. All rights reserved.
  *
- *   Authors: Gregory Nutt <spudmonkey@racsa.co.cr>
- *            Uros Platise <uros.platise@isotel.eu>
+ *   Authors: Uros Platise <uros.platise@isotel.eu>
  *
  * Redistribution and use in source and binary forms, with or without
  * modification, are permitted provided that the following conditions
@@ -37,20 +35,22 @@
  *
  ****************************************************************************/
 
-/****************************************************************************
- * Included Files
- ****************************************************************************/
+/** \file
+ *  \author Uros Platise
+ *  \brief VSN LED
+ */
 
 #include <nuttx/config.h>
-
 #include <arch/board/board.h>
+
+#ifdef CONFIG_ARCH_LEDS
+
 #include <arch/stm32/irq.h>
 
 #include <stdint.h>
 #include <stdbool.h>
 #include <debug.h>
 
-#include "up_arch.h"
 #include "vsn.h"
 
 
@@ -79,6 +79,7 @@
  
 irqstate_t irqidle_mask;
 
+
 /****************************************************************************
  * Private Functions
  ****************************************************************************/
@@ -87,23 +88,17 @@ static void led_setonoff(unsigned int bits)
 {
 }
 
+
 /****************************************************************************
  * Public Functions
  ****************************************************************************/
 
-/****************************************************************************
- * Name: up_ledinit
- ****************************************************************************/
 
-#ifdef CONFIG_ARCH_LEDS
 void up_ledinit(void)
 {
    stm32_configgpio(GPIO_LED);
 }
 
-/****************************************************************************
- * Name: up_ledon
- ****************************************************************************/
 
 void up_ledon(int led)
 {
@@ -113,9 +108,6 @@ void up_ledon(int led)
   }
 }
 
-/****************************************************************************
- * Name: up_ledoff
- ****************************************************************************/
 
 void up_ledoff(int led)
 {
diff --git a/configs/vsn/src/power.c b/configs/vsn/src/power.c
index 2e5ed1d13505ab8d0c8d3586b950aefd9cd68b14..9cbcfaac869bfba4cef232249fc5ed9d82a2f6d7 100644
--- a/configs/vsn/src/power.c
+++ b/configs/vsn/src/power.c
@@ -35,6 +35,11 @@
  *
  ****************************************************************************/
 
+/** \file
+ *  \author Uros Platise
+ *  \brief VSN Power
+ */
+
 #include <nuttx/config.h>
 
 #include <arch/board/board.h>
@@ -44,50 +49,60 @@
 #include <stdbool.h>
 #include <debug.h>
 
-#include "stm32_gpio.h"
 #include "vsn.h"
-#include "up_arch.h"
 
 
+/****************************************************************************
+ * Declarations and Structures
+ ****************************************************************************/ 
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/ 
+
 void board_power_register(void);
 void board_power_adjust(void);
 void board_power_status(void);
 
 
 
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/ 
+
 void board_power_init(void)
 {
-	stm32_configgpio(GPIO_PVS);
-	stm32_configgpio(GPIO_PST);
-	stm32_configgpio(GPIO_XPWR);
-	stm32_configgpio(GPIO_SCTC);
-	stm32_configgpio(GPIO_PCLR);
+    stm32_configgpio(GPIO_PVS);
+    stm32_configgpio(GPIO_PST);
+    stm32_configgpio(GPIO_XPWR);
+    stm32_configgpio(GPIO_SCTC);
+    stm32_configgpio(GPIO_PCLR);
 }
 
 
 void board_power_reboot(void)
 {
-	// low-level board reset (not just MCU reset)
-	// if external power is present, stimulate power-off as board
-	// will wake-up immediatelly, if power is not present, set an alarm
-	// before power off the board.
+    // low-level board reset (not just MCU reset)
+    // if external power is present, stimulate power-off as board
+    // will wake-up immediatelly, if power is not present, set an alarm
+    // before power off the board.
 }
 
 
 void board_power_off(void)
 {
-	// Check if external supply is not present, otherwise return
-	// notifying that it is not possible to power-off the board
+    // Check if external supply is not present, otherwise return
+    // notifying that it is not possible to power-off the board
 
-	// \todo
-	
-	// stop background processes
-	irqsave();
+    // \todo
+    
+    // stop background processes
+    irqsave();
 
-	// switch to internal HSI and get the PD0 and PD1 as GPIO
-	sysclock_select_hsi();
+    // switch to internal HSI and get the PD0 and PD1 as GPIO
+    sysclock_select_hsi();
 
-	// trigger shutdown with pull-up resistor (not push-pull!) and wait.
-	stm32_gpiowrite(GPIO_PCLR, true);
-	for(;;);
+    // trigger shutdown with pull-up resistor (not push-pull!) and wait.
+    stm32_gpiowrite(GPIO_PCLR, true);
+    for(;;);
 }
diff --git a/configs/vsn/src/rtac.c b/configs/vsn/src/rtac.c
new file mode 100644
index 0000000000000000000000000000000000000000..b953bd85150fd3256aaad11e87ec973f93379a38
--- /dev/null
+++ b/configs/vsn/src/rtac.c
@@ -0,0 +1,82 @@
+/****************************************************************************
+ * config/vsn/src/rtac.c
+ * arch/arm/src/board/rtac.c
+ *
+ *   Copyright (C) 2011 Uros Platise. All rights reserved.
+ *
+ *   Authors: Uros Platise <uros.platise@isotel.eu>
+ *
+ * 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 NuttX 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 COPYRIGHT HOLDERS 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
+ * COPYRIGHT OWNER 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.
+ *
+ ****************************************************************************/
+
+/** \file
+ *  \author Uros Platise
+ *  \brief Real Time Alarm Clock
+ * 
+ * Implementation of the Real-Time Alarm Clock as per SNP Specifications.
+ * It provides real-time and phase controlled timer module while it 
+ * cooperates with hardware RTC for low-power operation.
+ * 
+ * It provides a replacement for a system 32-bit UTC time/date counter.
+ * 
+ * It runs at maximum STM32 allowed precision of 16384 Hz, providing 
+ * resolution of 61 us, required by the Sensor Network Protocol.
+ */
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/** Execute from a group of events
+ **/
+int rtac_execg(int group)
+{
+    // called by each thread to spawn its apps given by its ID or group ID of
+    // multiple threads, when group parameter is set.
+}
+
+
+/** Wait and execute from a group of events
+ **/
+int rtac_waitg(int group, int time)
+{
+    // blocking variant of rtac_exec with timeout if specified
+}
diff --git a/configs/vsn/src/sif.c b/configs/vsn/src/sif.c
new file mode 100644
index 0000000000000000000000000000000000000000..cdd7967f91e5863878a609ac515a7e6430544f54
--- /dev/null
+++ b/configs/vsn/src/sif.c
@@ -0,0 +1,502 @@
+/****************************************************************************
+ * config/vsn/src/sif.c
+ * arch/arm/src/board/sif.c
+ *
+ *   Copyright (C) 2011 Uros Platise. All rights reserved.
+ *
+ *   Authors: Uros Platise <uros.platise@isotel.eu>
+ *
+ * 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 NuttX 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 COPYRIGHT HOLDERS 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
+ * COPYRIGHT OWNER 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.
+ *
+ ****************************************************************************/
+
+/** \file
+ *  \author Uros Platise
+ *  \brief VSN Sensor Interface
+ * 
+ * Public interface:
+ *  - sif_init(): should be called just once after system starts, to 
+ *    initialize internal data structures, device driver and hardware
+ *  - individual starts() and stops() that control gpio, usart, i2c, ...
+ *    are wrapped throu open() and close()
+ *  - read() and write() are used for streaming
+ *  - ioctl() for configuration    
+ * 
+ * STDOUT Coding 16-bit (little endian):
+ *  - MSB = 0 GPIOs, followed by the both GPIO config bytes
+ *  - MSB = 1 Input AD, centered around 0x4000
+ * 
+ * STDIN Coding 16-bit (little endian):
+ *  - MSB = 0 GPIOs, followed by the both GPIO config bytes
+ *    - MSB-1 = 0 Analog Output (PWM or Power)
+ *    - MSB-1 = 1 Analog Reference Tap
+ * 
+ * GPIO Update cycle:
+ *  - if they follow the Analog Output, they are synced with them
+ *  - if they follow the Analog Reference Tap, they are synced with them
+ *  - if either is configured without sample rate value, they are updated
+ *    immediately, same as them
+ * 
+ * Implementation:
+ *  - Complete internal states and updateing is made via the struct 
+ *    vsn_sif_s, which is also accessible thru the ioctl() with 
+ *    SNP Message descriptor.
+ **/
+
+#include <nuttx/config.h>
+#include <nuttx/fs.h>
+#include <semaphore.h>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <string.h>
+#include <errno.h>
+
+#include "vsn.h"
+
+
+/****************************************************************************
+ * Declarations and Structures
+ ****************************************************************************/ 
+ 
+#define VSN_SIF_READ_BUFSIZE    128
+#define VSN_SIF_WRITE_BUFSIZE   128
+
+
+typedef unsigned char vsn_sif_state_t;
+
+#   define VSN_SIF_STATE_POWERDOWN  0x00    ///< power-down
+
+#   define VSN_SIF_STATE_ACT_GPIO   0x01    ///< gpio is active
+#   define VSN_SIF_STATE_ACT_USART  0x02    ///< usart is active
+#   define VSN_SIF_STATE_ACT_I2C    0x04    ///< i2c is active
+#   define VSN_SIF_STATE_ACT_OWIR1  0x08    ///< 1-wire is active on first GPIO
+#   define VSN_SIF_STATE_ACT_OWIR2  0x10    ///< 1-wire is active on second GPIO
+
+#   define VSN_SIF_STATE_ACT_ANOUT  0x20    ///< analog output is active
+#   define VSN_SIF_STATE_ACT_ANIN   0x40    ///< analog input is active
+
+
+typedef unsigned char vsn_sif_gpio_t;
+
+#   define VSN_SIF_GPIO_STATE_MASK  7
+#   define VSN_SIF_GPIO_HIGHZ       0       ///< High-Z
+#   define VSN_SIF_GPIO_PULLUP      1       ///< Pull-Up
+#   define VSN_SIF_GPIO_PULLDOWN    2       ///< Pull-Down
+#   define VSN_SIF_GPIO_OUTLOW      3       ///< Set Low
+#   define VSN_SIF_GPIO_OUTHIGH     4       ///< Set High
+
+#   define VSN_SIF_GPIO_DISALT_MASK 0x10    ///< Disable Alternate Function, Mask Bit
+#   define VSN_SIF_GPIO_TRIG_MASK   0x20    ///< Send data change to the stdout
+#   define VSN_SIF_GPIO_READ_MASK   0x40    ///< Readout mask
+
+
+#define VSN_SIF_ANOUT_LOW       0	// Pseudo Analog Output acts as GPIO
+#define VSN_SIF_ANOUT_HIGH      1	// Pseudo Analog Output acts as GPIO high
+#define	VSN_SIF_ANOUT_HIGHPWR   2	// ... acts as high power output
+#define VSN_SIF_ANOUT_PWM       3	// ... acts as PWM output 
+#define VSN_SIF_ANOUT_PWMPWR    4	// acts as power PWM output
+
+#define VSN_SIF_ANIN_GAINMASK   7
+#define VSN_SIF_ANIN_GAIN1      0
+#define VSN_SIF_ANIN_GAIN2      1
+#define VSN_SIF_ANIN_GAIN4      2
+#define VSN_SIF_ANIN_GAIN8      3
+#define VSN_SIF_ANIN_GAIN16     4
+#define VSN_SIF_ANIN_GAIN32     5
+#define VSN_SIF_ANIN_GAIN64     6
+#define VSN_SIF_ANIN_GAIN128    7
+
+#define VSN_SIF_ANIN_BITS8
+#define VSN_SIF_ANIN_BITS9
+#define VSN_SIF_ANIN_BITS10
+#define VSN_SIF_ANIN_BITS11
+#define VSN_SIF_ANIN_BITS12
+#define VSN_SIF_ANIN_BITS13
+#define VSN_SIF_ANIN_BITS14
+
+#define VSN_SIF_ANIN_OVERSMP1
+#define VSN_SIF_ANIN_OVERSMP2
+#define VSN_SIF_ANIN_OVERSMP4
+#define VSN_SIF_ANIN_OVERSMP8	
+#define VSN_SIF_ANIN_OVERSMP16
+
+
+struct vsn_sif_s {
+    vsn_sif_state_t     state;              // activity 
+    unsigned char       opencnt;            // open count
+	
+    vsn_sif_gpio_t      gpio[2];
+
+    unsigned char       anout_opts;
+    unsigned short int  anout_width;
+    unsigned short int  anout_period;       // setting it to 0, disables PWM
+    unsigned short int  anout_samplerate;   // as written by write()
+	 		
+    unsigned short int  anref_width;
+    unsigned short int  anref_period;       // setting it to 0, disables PWM
+    unsigned short int  anref_samplerate;   // as written by write()
+    
+    unsigned char       anin_opts;
+    unsigned int        anin_samplerate;    // returned on read() as 16-bit results
+    
+        /*--- Private Data ---*/
+    
+    struct stm32_tim_dev_s * tim3;          // Timer3 is used for PWM, and Analog RefTap
+    struct stm32_tim_dev_s * tim8;          // Timer8 is used for Power Switch
+    
+    sem_t               exclusive_access;
+};
+
+
+/****************************************************************************
+ * Private data
+ ****************************************************************************/ 
+
+struct vsn_sif_s vsn_sif;
+
+
+/****************************************************************************
+ * Semaphores
+ ****************************************************************************/ 
+
+void sif_sem_wait(void)
+{
+    while( sem_wait( &vsn_sif.exclusive_access ) != 0 ) {
+        ASSERT(errno == EINTR);
+    }
+}
+
+
+void inline sif_sem_post(void)
+{
+    sem_post( &vsn_sif.exclusive_access );
+}
+
+
+/****************************************************************************
+ * GPIOs and Alternative Functions
+ ****************************************************************************/ 
+
+
+void sif_gpios_reset(void)
+{
+    vsn_sif.gpio[0] = vsn_sif.gpio[1] = VSN_SIF_GPIO_HIGHZ;
+    
+    stm32_configgpio(GPIO_GP1_HIZ);
+    stm32_configgpio(GPIO_GP2_HIZ);
+}
+
+
+void sif_gpio1_update(void)
+{
+    uint32_t val;
+    
+    switch(vsn_sif.gpio[0] & VSN_SIF_GPIO_STATE_MASK) {
+        case VSN_SIF_GPIO_HIGHZ:    val = GPIO_GP1_HIZ; break;
+        case VSN_SIF_GPIO_PULLUP:   val = GPIO_GP1_PUP; break;
+        case VSN_SIF_GPIO_PULLDOWN: val = GPIO_GP1_PDN; break;
+        case VSN_SIF_GPIO_OUTLOW:   val = GPIO_GP1_LOW; break;
+        case VSN_SIF_GPIO_OUTHIGH:  val = GPIO_GP1_HIGH;break;
+        default: return;
+    }
+    stm32_configgpio(val);
+    
+    if ( stm32_gpioread(val) ) 
+        vsn_sif.gpio[0] |= VSN_SIF_GPIO_READ_MASK;
+    else vsn_sif.gpio[0] &= ~VSN_SIF_GPIO_READ_MASK;
+}
+
+
+void sif_gpio2_update(void)
+{
+    uint32_t val;
+    
+    switch(vsn_sif.gpio[1]) {
+        case VSN_SIF_GPIO_HIGHZ:    val = GPIO_GP2_HIZ; break;
+        case VSN_SIF_GPIO_PULLUP:   val = GPIO_GP2_PUP; break;
+        case VSN_SIF_GPIO_PULLDOWN: val = GPIO_GP2_PDN; break;
+        case VSN_SIF_GPIO_OUTLOW:   val = GPIO_GP2_LOW; break;
+        case VSN_SIF_GPIO_OUTHIGH:  val = GPIO_GP2_HIGH;break;
+        default: return;
+    }
+    stm32_configgpio(val);
+    
+    if ( stm32_gpioread(val) ) 
+        vsn_sif.gpio[1] |= VSN_SIF_GPIO_READ_MASK;
+    else vsn_sif.gpio[1] &= ~VSN_SIF_GPIO_READ_MASK;
+}
+
+
+int sif_gpios_lock(vsn_sif_state_t peripheral)
+{
+    return ERROR;
+}
+
+
+int sif_gpios_unlock(vsn_sif_state_t peripheral)
+{
+    return ERROR;
+}
+
+
+/****************************************************************************
+ * Analog Outputs
+ ****************************************************************************/ 
+ 
+static volatile int test = 0, test_irq;
+
+
+static int sif_anout_isr(int irq, void *context)
+{
+    STM32_TIM_ACKINT(vsn_sif.tim8, 0);
+
+    test++;
+    test_irq = irq;
+    
+    return OK;
+}
+
+
+int sif_anout_init(void)
+{
+    vsn_sif.tim3 = stm32_tim_init(3);
+    vsn_sif.tim8 = stm32_tim_init(8);
+    
+    if (!vsn_sif.tim3 || !vsn_sif.tim8) return ERROR;
+    
+    // Use the TIM3 as PWM modulated analogue output
+    
+    STM32_TIM_SETCHANNEL(vsn_sif.tim3, GPIO_OUT_PWM_TIM3_CH4, STM32_TIM_CH_OUTPWM | STM32_TIM_CH_POLARITY_NEG);
+    STM32_TIM_SETPERIOD(vsn_sif.tim3, 4096);
+    STM32_TIM_SETCOMPARE(vsn_sif.tim3, GPIO_OUT_PWM_TIM3_CH4, 1024);
+
+    STM32_TIM_SETCLOCK(vsn_sif.tim3, 36e6);
+    STM32_TIM_SETMODE(vsn_sif.tim3, STM32_TIM_MODE_UP);
+    stm32_configgpio(GPIO_OUT_HIZ);
+    
+    // Use the TIM8 to drive the upper power mosfet
+    
+    STM32_TIM_SETISR(vsn_sif.tim8, sif_anout_isr, 0);
+    STM32_TIM_ENABLEINT(vsn_sif.tim8, 0);
+
+    STM32_TIM_SETCHANNEL(vsn_sif.tim8, GPIO_OUT_PWRPWM_TIM8_CH1P, STM32_TIM_CH_OUTPWM | STM32_TIM_CH_POLARITY_NEG);
+    STM32_TIM_SETPERIOD(vsn_sif.tim8, 4096);
+    STM32_TIM_SETCOMPARE(vsn_sif.tim8, GPIO_OUT_PWRPWM_TIM8_CH1P, 0);
+    
+    STM32_TIM_SETCLOCK(vsn_sif.tim8, 36e6);
+    STM32_TIM_SETMODE(vsn_sif.tim8, STM32_TIM_MODE_UP);
+    stm32_configgpio(GPIO_OUT_PWRPWM);
+
+    return OK;
+}
+
+
+void sif_anout_update(void)
+{
+}
+
+
+void sif_anout_callback(void)
+{
+	// called at rate of PWM interrupt
+}
+
+
+/****************************************************************************
+ * Analog Input Reference Tap
+ ****************************************************************************/ 
+
+
+void sif_anref_init(void)
+{
+}
+
+
+/****************************************************************************
+ * Analog Input Sampler Unit
+ ****************************************************************************/ 
+
+
+void sif_anin_reset(void)
+{
+}
+
+
+/****************************************************************************
+ * Device driver functions
+ ****************************************************************************/ 
+
+int devsif_open(FAR struct file *filep)
+{
+    sif_sem_wait();
+    vsn_sif.opencnt++;
+    
+    // Start Hardware
+        
+    sif_sem_post();
+    return 0;
+}
+
+
+int devsif_close(FAR struct file *filep)
+{
+    sif_sem_wait();
+    
+    if (--vsn_sif.opencnt) {
+    
+        // suspend (powerdown) hardware
+        
+        sif_gpios_reset();
+        
+        //STM32_TIM_SETCLOCK(vsn_sif.tim3, 0);
+        //STM32_TIM_SETCLOCK(vsn_sif.tim8, 0);
+    }
+    
+    sif_sem_post();
+    return 0;
+}
+
+
+static ssize_t devsif_read(FAR struct file *filp, FAR char *buffer, size_t len)
+{
+    sif_sem_wait();
+    memset(buffer, 0, len);
+    sif_sem_post();
+    return len;
+}
+
+
+static ssize_t devsif_write(FAR struct file *filp, FAR const char *buffer, size_t len)
+{
+    sif_sem_wait();
+    printf("getpid: %d\n", getpid() );
+    sif_sem_post();
+    return len;
+}
+
+
+#ifndef CONFIG_DISABLE_POLL
+static int devsif_poll(FAR struct file *filp, FAR struct pollfd *fds,
+                        bool setup)
+{
+    if (setup) {
+        fds->revents |= (fds->events & (POLLIN|POLLOUT));
+        
+        if (fds->revents != 0) {
+            sem_post(fds->sem);
+        }
+    }
+    return OK;
+}
+#endif
+
+
+int devsif_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
+{
+    sif_sem_wait();
+    sif_sem_post();
+    return 0;
+}
+
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/ 
+
+
+static const struct file_operations devsif_fops = {
+    devsif_open,    /* open */
+    devsif_close,   /* close */
+    devsif_read,    /* read */
+    devsif_write,   /* write */
+    0,              /* seek */
+    devsif_ioctl    /* ioctl */
+#ifndef CONFIG_DISABLE_POLL
+  , devsif_poll     /* poll */
+#endif
+};
+
+ 
+/** Bring up the Sensor Interface by initializing all of the desired 
+ *  hardware components.
+ **/
+  
+int sif_init(void)
+{
+    /* Initialize data-structure */
+    
+    vsn_sif.state   = VSN_SIF_STATE_POWERDOWN;
+    vsn_sif.opencnt = 0;
+    sem_init(&vsn_sif.exclusive_access, 0, 1);
+    
+    /* Initialize hardware */
+    
+    sif_gpios_reset();
+    if ( sif_anout_init() != OK ) return -1;
+    
+    /* If everything is okay, register the driver */
+    
+    (void)register_driver("/dev/sif0", &devsif_fops, 0666, NULL);
+    return OK;
+}
+
+
+/** SIF Utility
+ * 
+ * Provides direct access to the sensor connector, readings, and diagnostic.
+ **/
+ 
+int sif_main(int argc, char *argv[])
+{
+    if (argc >= 2) {	
+        if (!strcmp(argv[1], "init")) {
+          return sif_init();
+        }
+        else if (!strcmp(argv[1], "gpio") && argc == 4) {
+            vsn_sif.gpio[0] = atoi(argv[2]);
+            vsn_sif.gpio[1] = atoi(argv[3]);
+            sif_gpio1_update();
+            sif_gpio2_update();
+            printf("GPIO States: %2x %2x\n", vsn_sif.gpio[0], vsn_sif.gpio[1] );
+            return 0;
+        }
+        else if (!strcmp(argv[1], "pwr") && argc == 3) {
+            int val = atoi(argv[2]);
+            STM32_TIM_SETCOMPARE(vsn_sif.tim8, GPIO_OUT_PWRPWM_TIM8_CH1P, val);
+            return 0;
+        }
+        else if (!strcmp(argv[1], "c")) {
+        }
+    }
+
+    fprintf(stderr, "%s:\tinit\n\tgpio\tA B\n\tpwr\tval\n", argv[0]);
+    fprintf(stderr, "test = %.8x, test irq = %.8x\n", test, test_irq);
+    return -1;
+}
diff --git a/configs/vsn/src/spi.c b/configs/vsn/src/spi.c
index 742fcfd41e02d8776caf34c6c8e1faed3068a6d0..a452197b7180c072735680e680161e47d31f50c8 100644
--- a/configs/vsn/src/spi.c
+++ b/configs/vsn/src/spi.c
@@ -37,12 +37,17 @@
  *
  ************************************************************************************/
 
-/************************************************************************************
- * Included Files
- ************************************************************************************/
+/** \file
+ *  \author Gregory Nutt, Uros Platise
+ *  \brief SPI Slave Selects
+ */
+
 
 #include <nuttx/config.h>
 #include <nuttx/spi.h>
+
+#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3)
+
 #include <arch/board/board.h>
 
 #include <stdint.h>
@@ -55,7 +60,6 @@
 #include "stm32_internal.h"
 #include "vsn.h"
 
-#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3)
 
 /************************************************************************************
  * Definitions
@@ -79,22 +83,15 @@
 #  define spivdbg(x...)
 #endif
 
-/************************************************************************************
- * Private Functions
- ************************************************************************************/
 
 /************************************************************************************
  * Public Functions
  ************************************************************************************/
 
-/************************************************************************************
- * Name: stm32_spiinitialize
- *
- * Description:
- *   Called to configure SPI chip select GPIO pins for the VSN board.
- *
- ************************************************************************************/
 
+/** Called to configure SPI chip select GPIO pins for the VSN board.
+ */
+ 
 void weak_function stm32_spiinitialize(void)
 {
   /* NOTE: Clocking for SPI1 and/or SPI2 and SPI3 was already provided in stm32_rcc.c.
@@ -109,10 +106,8 @@ void weak_function stm32_spiinitialize(void)
 #endif
 }
 
-/****************************************************************************
- * Name:  stm32_spi1/2/3select and stm32_spi1/2/3status
+/** Selects: stm32_spi1/2/3select and stm32_spi1/2/3status
  *
- * Description:
  *   The external functions, stm32_spi1/2/3select and stm32_spi1/2/3status must be
  *   provided by board-specific logic.  They are implementations of the select
  *   and status methods of the SPI interface defined by struct spi_ops_s (see
@@ -132,9 +127,10 @@ void weak_function stm32_spiinitialize(void)
  *      mmcsd_spislotinitialize(), for example, will bind the SPI driver to
  *      the SPI MMC/SD driver).
  *
- ****************************************************************************/
+ **/
 
 #ifdef CONFIG_STM32_SPI1
+
 void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
 {
   spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
@@ -144,9 +140,11 @@ uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
 {
   return SPI_STATUS_PRESENT;
 }
+
 #endif
 
 #ifdef CONFIG_STM32_SPI2
+
 void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
 {
   spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
@@ -156,9 +154,11 @@ uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
 {
   return SPI_STATUS_PRESENT;
 }
+
 #endif
 
 #ifdef CONFIG_STM32_SPI3
+
 void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
 {
   spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
@@ -173,6 +173,7 @@ uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
 {
   return SPI_STATUS_PRESENT;
 }
+
 #endif
 
 #endif /* CONFIG_STM32_SPI1 || CONFIG_STM32_SPI2 */
diff --git a/configs/vsn/src/sysclock.c b/configs/vsn/src/sysclock.c
index 928282b127d526348eaad17d4093d634bad088c6..f65ae0670726387e9f054b3d019f790b56673e24 100644
--- a/configs/vsn/src/sysclock.c
+++ b/configs/vsn/src/sysclock.c
@@ -35,18 +35,16 @@
  ****************************************************************************/
 
 /** \file
-  */
+ *  \author Uros Platise
+ *  \brief VSN System Clock Configuration
+ */
 
-#include <arch/board/board.h>
-#include "stm32_rcc.h"
-#include "stm32_gpio.h"
-#include "stm32_flash.h"
-#include "up_internal.h"
-#include "up_arch.h"
-#include "chip.h"
+#include "vsn.h"
 
 
-		/*--- Private ---*/
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/ 
 
 /** Selects internal HSI Clock, SYSCLK = 36 MHz, HCLK = 36 MHz
   *  - HSI at 8 MHz, :2 enters DPLL * 9, to get 36 MHz
@@ -67,28 +65,28 @@
   */
 void sysclock_select_hsi(void)
 {
-	uint32_t regval;
-
-	// Are we running on HSE?
-	regval = getreg32(STM32_RCC_CR);
-	if (regval & RCC_CR_HSEON) {
-		
-		// \todo: check is if we are running on HSE, we need the step down sequenuce from HSE -> HSI
-		
-		return;	// do nothing at this time
-	}
-	
-	// Set FLASH prefetch buffer and 1 wait state
-	regval  = getreg32(STM32_FLASH_ACR);
-	regval &= ~ACR_LATENCY_MASK;
-	regval |= (ACR_LATENCY_1|ACR_PRTFBE);
-	putreg32(regval, STM32_FLASH_ACR);
-	 
+    uint32_t regval;
+
+    // Are we running on HSE?
+    regval = getreg32(STM32_RCC_CR);
+    if (regval & RCC_CR_HSEON) {
+        
+        // \todo: check is if we are running on HSE, we need the step down sequenuce from HSE -> HSI
+        
+        return; // do nothing at this time
+    }
+    
+    // Set FLASH prefetch buffer and 1 wait state
+    regval  = getreg32(STM32_FLASH_ACR);
+    regval &= ~ACR_LATENCY_MASK;
+    regval |= (ACR_LATENCY_1|ACR_PRTFBE);
+    putreg32(regval, STM32_FLASH_ACR);
+     
     // Set the HCLK source/divider
-	regval = getreg32(STM32_RCC_CFGR);
-	regval &= ~RCC_CFGR_HPRE_MASK;
-	regval |= STM32_RCC_CFGR_HPRE_HSI;
-	putreg32(regval, STM32_RCC_CFGR);
+    regval = getreg32(STM32_RCC_CFGR);
+    regval &= ~RCC_CFGR_HPRE_MASK;
+    regval |= STM32_RCC_CFGR_HPRE_HSI;
+    putreg32(regval, STM32_RCC_CFGR);
 
     // Set the PCLK2 divider
     regval = getreg32(STM32_RCC_CFGR);
@@ -101,20 +99,27 @@ void sysclock_select_hsi(void)
     regval &= ~RCC_CFGR_PPRE1_MASK;
     regval |= STM32_RCC_CFGR_PPRE1;
     putreg32(regval, STM32_RCC_CFGR);
+    
+    // Set the TIM1..8 clock multipliers
+#ifdef STM32_TIM27_FREQMUL2  
+#endif
+
+#ifdef STM32_TIM18_FREQMUL2
+#endif
  
     // Set the PLL source = HSI, divider (/2) and multipler (*9)
-	regval = getreg32(STM32_RCC_CFGR);
-	regval &= ~(RCC_CFGR_PLLSRC|RCC_CFGR_PLLXTPRE|RCC_CFGR_PLLMUL_MASK);
-	regval |= (STM32_CFGR_PLLSRC_HSI|STM32_CFGR_PLLMUL_HSI);
-	putreg32(regval, STM32_RCC_CFGR);
+    regval = getreg32(STM32_RCC_CFGR);
+    regval &= ~(RCC_CFGR_PLLSRC|RCC_CFGR_PLLXTPRE|RCC_CFGR_PLLMUL_MASK);
+    regval |= (STM32_CFGR_PLLSRC_HSI|STM32_CFGR_PLLMUL_HSI);
+    putreg32(regval, STM32_RCC_CFGR);
  
     // Enable the PLL
-	regval = getreg32(STM32_RCC_CR);
-	regval |= RCC_CR_PLLON;
-	putreg32(regval, STM32_RCC_CR);
+    regval = getreg32(STM32_RCC_CR);
+    regval |= RCC_CR_PLLON;
+    putreg32(regval, STM32_RCC_CR);
  
     // Wait until the PLL is ready
-	while ((getreg32(STM32_RCC_CR) & RCC_CR_PLLRDY) == 0);
+    while ((getreg32(STM32_RCC_CR) & RCC_CR_PLLRDY) == 0);
  
     // Select the system clock source (probably the PLL)
     regval  = getreg32(STM32_RCC_CFGR);
@@ -126,9 +131,9 @@ void sysclock_select_hsi(void)
     while ((getreg32(STM32_RCC_CFGR) & RCC_CFGR_SWS_MASK) != STM32_SYSCLK_SWS);
     
     // map port PD0 and PD1 on OSC pins
-	regval = getreg32(STM32_AFIO_MAPR);
-	regval |= AFIO_MAPR_PD01_REMAP;
-	putreg32(regval, STM32_AFIO_MAPR);
+    regval = getreg32(STM32_AFIO_MAPR);
+    regval |= AFIO_MAPR_PD01_REMAP;
+    putreg32(regval, STM32_AFIO_MAPR);
 }
 
 
@@ -146,21 +151,23 @@ void sysclock_select_hsi(void)
   */
 int sysclock_select_hse(void)
 {
-	uint32_t regval;
+    uint32_t regval;
 
     // be sure to release PD0 and PD1 pins from the OSC pins
-	regval = getreg32(STM32_AFIO_MAPR);
-	regval &= ~AFIO_MAPR_PD01_REMAP;
-	putreg32(regval, STM32_AFIO_MAPR);
-
-	// if (is cc1101 9 MHz clock output enabled), otherwise return with -1
-	// I think that clock register provides HSE valid signal to detect that as well.
-	
-	return 0;
+    regval = getreg32(STM32_AFIO_MAPR);
+    regval &= ~AFIO_MAPR_PD01_REMAP;
+    putreg32(regval, STM32_AFIO_MAPR);
+
+    // if (is cc1101 9 MHz clock output enabled), otherwise return with -1
+    // I think that clock register provides HSE valid signal to detect that as well.
+    
+    return 0;
 }
 
 
-		/*--- Interrupts ---*/
+/****************************************************************************
+ * Interrupts, Callbacks
+ ****************************************************************************/ 
 
 
 /** TODO: Interrupt on lost HSE clock, change it to HSI, ... restarting is 
@@ -173,7 +180,9 @@ void sysclock_hse_lost(void)
 }
 
 
-		/*--- Public API ---*/
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/ 
 
 /** Setup system clock, enabled when:
   *   - CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG
@@ -181,5 +190,5 @@ void sysclock_hse_lost(void)
   */
 void stm32_board_clockconfig(void)
 {
-	sysclock_select_hsi();
+    sysclock_select_hsi();
 }
diff --git a/configs/vsn/src/vsn.h b/configs/vsn/src/vsn.h
index 33282c5a156b501a4e0b23154b955a1eb09b7e4d..5d017b07a68bb8135deb5ca09c20e3cd4113db3b 100644
--- a/configs/vsn/src/vsn.h
+++ b/configs/vsn/src/vsn.h
@@ -2,11 +2,9 @@
  * configs/vsn/src/vsn.h
  * arch/arm/src/board/vsn.n
  *
- *   Copyright (C) 2009 Gregory Nutt. All rights reserved.
  *   Copyright (c) 2011 Uros Platise. All rights reserved.
  *
- *   Authors: Gregory Nutt <spudmonkey@racsa.co.cr>
- *            Uros Platise <uros.platise@isotel.eu>
+ *   Authors: Uros Platise <uros.platise@isotel.eu>
  *
  * Redistribution and use in source and binary forms, with or without
  * modification, are permitted provided that the following conditions
@@ -37,20 +35,21 @@
  *
  ************************************************************************************/
 
-#ifndef __CONFIGS_VSN_1_2_SRC_VSN_INTERNAL_H
+#ifndef __CONFIGS_VSN_SRC_VSN_INTERNAL_H
 #define __CONFIGS_VSN_SRC_VSN_INTERNAL_H
 
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <arch/board/board.h>
 #include <nuttx/config.h>
+#include <arch/board/board.h>
 #include <nuttx/compiler.h>
 #include <stdint.h>
 
+#include "stm32.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+
 /************************************************************************************
- * Definitions
+ * PIN Definitions
  ************************************************************************************/
 
 /* LED */
@@ -69,12 +68,53 @@
 #define GPIO_PCLR		(GPIO_INPUT |GPIO_CNF_INPULLDWN|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN1 )	// by default this pin is OSCOUT, requires REMAP
 #define GPIO_XPWR		(GPIO_INPUT |GPIO_CNF_INFLOAT  |GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4 )
 
-/* FRAM */
+/* FRAM (alt pins are not listed here and are a part of SPI) */
 
 #define GPIO_FRAM_CS	(GPIO_OUTPUT|GPIO_CNF_OUTPP    |GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN15|GPIO_OUTPUT_SET)
 
+/* Sensor Interface */
+
+#define GPIO_GP1_HIZ	(GPIO_INPUT |GPIO_CNF_INFLOAT  |GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_GP1_PUP	(GPIO_INPUT |GPIO_CNF_INPULLUP |GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_GP1_PDN	(GPIO_INPUT |GPIO_CNF_INPULLDWN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_GP1_LOW	(GPIO_OUTPUT|GPIO_CNF_OUTPP    |GPIO_MODE_2MHz |GPIO_PORTB|GPIO_PIN10|GPIO_OUTPUT_CLEAR)
+#define GPIO_GP1_HIGH	(GPIO_OUTPUT|GPIO_CNF_OUTPP    |GPIO_MODE_2MHz |GPIO_PORTB|GPIO_PIN10|GPIO_OUTPUT_SET)
+
+#define GPIO_GP2_HIZ	(GPIO_INPUT |GPIO_CNF_INFLOAT  |GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11)
+#define GPIO_GP2_PUP	(GPIO_INPUT |GPIO_CNF_INPULLUP |GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11)
+#define GPIO_GP2_PDN	(GPIO_INPUT |GPIO_CNF_INPULLDWN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11)
+#define GPIO_GP2_LOW	(GPIO_OUTPUT|GPIO_CNF_OUTPP    |GPIO_MODE_2MHz |GPIO_PORTB|GPIO_PIN11|GPIO_OUTPUT_CLEAR)
+#define GPIO_GP2_HIGH	(GPIO_OUTPUT|GPIO_CNF_OUTPP    |GPIO_MODE_2MHz |GPIO_PORTB|GPIO_PIN11|GPIO_OUTPUT_SET)
+
+#define GPIO_OPA_INPUT	(GPIO_INPUT |GPIO_CNF_ANALOGIN |GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0 )
+#define GPIO_OPA_ENABLE	(GPIO_OUTPUT|GPIO_CNF_OUTPP    |GPIO_MODE_2MHz |GPIO_PORTC|GPIO_PIN1 |GPIO_OUTPUT_CLEAR)
+#define GPIO_OPA_REFAIN	(GPIO_INPUT |GPIO_CNF_ANALOGIN |GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0 )
+#define GPIO_OPA_REFPWM	(GPIO_ALT   |GPIO_CNF_AFPP     |GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN0 )
+
+#define GPIO_OUT_PWRON  (GPIO_OUTPUT|GPIO_CNF_OUTPP    |GPIO_MODE_2MHz |GPIO_PORTC|GPIO_PIN6 |GPIO_OUTPUT_CLEAR)
+#define GPIO_OUT_PWROFF	(GPIO_OUTPUT|GPIO_CNF_OUTPP    |GPIO_MODE_2MHz |GPIO_PORTC|GPIO_PIN6 |GPIO_OUTPUT_SET)
+#define GPIO_OUT_PWRPWM	(GPIO_ALT   |GPIO_CNF_AFPP     |GPIO_MODE_10MHz|GPIO_PORTC|GPIO_PIN6 )
+#define GPIO_OUT_PWRPWM_TIM8_CH1P   1   /* TIM8.CH1 */
 
-/* Debug ********************************************************************/
+#define GPIO_OUT_HIZ	(GPIO_INPUT |GPIO_CNF_INFLOAT  |GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1 )
+#define GPIO_OUT_PUP	(GPIO_INPUT |GPIO_CNF_INPULLUP |GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1 )
+#define GPIO_OUT_PDN	(GPIO_INPUT |GPIO_CNF_INPULLDWN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1 )
+#define GPIO_OUT_LOW	(GPIO_OUTPUT|GPIO_CNF_OUTPP    |GPIO_MODE_2MHz |GPIO_PORTB|GPIO_PIN1 |GPIO_OUTPUT_CLEAR)
+#define GPIO_OUT_HIGH	(GPIO_OUTPUT|GPIO_CNF_OUTPP    |GPIO_MODE_2MHz |GPIO_PORTB|GPIO_PIN1 |GPIO_OUTPUT_SET)
+#define GPIO_OUT_AIN	(GPIO_INPUT |GPIO_CNF_ANALOGIN |GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1 )
+#define GPIO_OUT_PWM	(GPIO_ALT   |GPIO_CNF_AFPP     |GPIO_MODE_10MHz|GPIO_PORTB|GPIO_PIN1 )
+#define GPIO_OUT_PWM_TIM3_CH4       4   /* TIM3.CH4 */ 
+
+
+/* Radio Connector */
+
+
+/* Expansion Connector */
+
+
+/************************************************************************************
+ * Debugging
+ ************************************************************************************/
 
 #ifdef CONFIG_CPP_HAVE_VARARGS
 #  ifdef CONFIG_DEBUG
@@ -91,10 +131,6 @@
 #endif
 
 
-/************************************************************************************
- * Public Types
- ************************************************************************************/
-
 /************************************************************************************
  * Public data
  ************************************************************************************/
diff --git a/drivers/mmcsd/mmcsd_sdio.c b/drivers/mmcsd/mmcsd_sdio.c
index 61bbb417a3e2e01536c6766b8753c6440878fbed..3fd7b08475097afc3bcafa952177774c9f745999 100644
--- a/drivers/mmcsd/mmcsd_sdio.c
+++ b/drivers/mmcsd/mmcsd_sdio.c
@@ -2033,7 +2033,7 @@ static void mmcsd_mediachange(FAR void *arg)
   DEBUGASSERT(priv);
 
   /* Is there a card present in the slot? */
-
+  
   mmcsd_takesem(priv);
   if (SDIO_PRESENT(priv->dev))
     {
@@ -2688,7 +2688,9 @@ static int mmcsd_probe(FAR struct mmcsd_state_s *priv)
       if (ret != OK)
         {
           fdbg("ERROR: Failed to initialize card: %d\n", ret);
+#ifdef CONFIG_MMCSD_HAVECARDDETECT
           SDIO_CALLBACKENABLE(priv->dev, SDIOMEDIA_INSERTED);
+#endif
         }
       else
         {
@@ -2738,7 +2740,9 @@ static int mmcsd_probe(FAR struct mmcsd_state_s *priv)
       /* There is no card in the slot */
 
       fvdbg("No card\n");
+#ifdef CONFIG_MMCSD_HAVECARDDETECT
       SDIO_CALLBACKENABLE(priv->dev, SDIOMEDIA_INSERTED);
+#endif
       ret = -ENODEV;
     }