paparazzi-commits
[Top][All Lists]
Advanced

[Date Prev][Date Next][Thread Prev][Thread Next][Date Index][Thread Index]

[paparazzi-commits] [5936] move stm32 dir to arch


From: Felix Ruess
Subject: [paparazzi-commits] [5936] move stm32 dir to arch
Date: Thu, 23 Sep 2010 22:28:37 +0000

Revision: 5936
          http://svn.sv.gnu.org/viewvc/?view=rev&root=paparazzi&revision=5936
Author:   flixr
Date:     2010-09-23 22:28:37 +0000 (Thu, 23 Sep 2010)
Log Message:
-----------
move stm32 dir to arch

Modified Paths:
--------------
    paparazzi3/trunk/conf/Makefile.stm32

Added Paths:
-----------
    paparazzi3/trunk/sw/airborne/arch/stm32/
    paparazzi3/trunk/sw/airborne/arch/stm32/adc_hw.c
    paparazzi3/trunk/sw/airborne/arch/stm32/adc_hw.h
    paparazzi3/trunk/sw/airborne/arch/stm32/can_hw.c
    paparazzi3/trunk/sw/airborne/arch/stm32/can_hw.c.bak
    paparazzi3/trunk/sw/airborne/arch/stm32/can_hw.h
    paparazzi3/trunk/sw/airborne/arch/stm32/gps_hw.h
    paparazzi3/trunk/sw/airborne/arch/stm32/i2c_hw.c
    paparazzi3/trunk/sw/airborne/arch/stm32/i2c_hw.h
    paparazzi3/trunk/sw/airborne/arch/stm32/init_hw.h
    paparazzi3/trunk/sw/airborne/arch/stm32/interrupt_hw.h
    paparazzi3/trunk/sw/airborne/arch/stm32/led_hw.c
    paparazzi3/trunk/sw/airborne/arch/stm32/led_hw.h
    paparazzi3/trunk/sw/airborne/arch/stm32/link_mcu_hw.h
    paparazzi3/trunk/sw/airborne/arch/stm32/my_debug_servo.h
    paparazzi3/trunk/sw/airborne/arch/stm32/ppm_hw.c
    paparazzi3/trunk/sw/airborne/arch/stm32/ppm_hw.h
    paparazzi3/trunk/sw/airborne/arch/stm32/servos_direct_hw.c
    paparazzi3/trunk/sw/airborne/arch/stm32/servos_direct_hw.h
    paparazzi3/trunk/sw/airborne/arch/stm32/stm32_exceptions.c
    paparazzi3/trunk/sw/airborne/arch/stm32/stm32_exceptions.h
    paparazzi3/trunk/sw/airborne/arch/stm32/stm32_vector_table.c
    paparazzi3/trunk/sw/airborne/arch/stm32/stm32_vector_table.h
    paparazzi3/trunk/sw/airborne/arch/stm32/stm32f103rb_flash.ld
    paparazzi3/trunk/sw/airborne/arch/stm32/stm32f103re_flash.ld
    paparazzi3/trunk/sw/airborne/arch/stm32/sys_time_hw.c
    paparazzi3/trunk/sw/airborne/arch/stm32/sys_time_hw.h
    paparazzi3/trunk/sw/airborne/arch/stm32/uart_hw.c
    paparazzi3/trunk/sw/airborne/arch/stm32/uart_hw.h

Removed Paths:
-------------
    paparazzi3/trunk/sw/airborne/stm32/

Modified: paparazzi3/trunk/conf/Makefile.stm32
===================================================================
--- paparazzi3/trunk/conf/Makefile.stm32        2010-09-23 22:28:29 UTC (rev 
5935)
+++ paparazzi3/trunk/conf/Makefile.stm32        2010-09-23 22:28:37 UTC (rev 
5936)
@@ -25,7 +25,7 @@
 # This is the common Makefile for the stm32-target.
 #
 
-SRC_ARCH = stm32
+SRC_ARCH = arch/stm32
 
 # Pretty Printer
 # Call with "make Q=''" to get full command display

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/adc_hw.c (from rev 5935, 
paparazzi3/trunk/sw/airborne/stm32/adc_hw.c)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/adc_hw.c                            
(rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/adc_hw.c    2010-09-23 22:28:37 UTC 
(rev 5936)
@@ -0,0 +1,493 @@
+/*
+ *
+ * Copyright (C) 2010 The Paparazzi Team
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ *
+ */
+
+/**
+ *
+ * This is the driver for the analog to digital converters
+ * on STM32
+ *
+ * Usage: 
+ * Define flags for ADCs to use and their channels: 
+ *
+ *   -DUSE_AD1 -DUSE_AD1_1 -DUSE_AD1_3
+ *
+ * would enable ADC1 and it's channels 1 and 3. 
+ *
+ */
+
+/*
+  For better understanding of timer and GPIO settings: 
+
+  Table of GPIO pins available per ADC: 
+
+  ADC1/2:                                      ADC3: 
+               C0  -> PA0                              C0  -> PA0
+               C1  -> PA1                              C1  -> PA1
+               C2  -> PA2                              C2  -> PA2
+               C3  -> PA3                              C3  -> PA3
+               C4  -> PA4                              C4  -> PF6
+               C5  -> PA5                              C5  -> PF7
+               C6  -> PA6                              C6  -> PF8
+               C7  -> PA7                              C7  -> PF9
+               C8  -> PB0                              C8  -> PF10
+               C9  -> PB1                              
+               C10 -> PC0                              C10 -> PC0
+               C11 -> PC1                              C11 -> PC1
+               C12 -> PC2                              C12 -> PC2
+               C13 -> PC3                              C13 -> PC3
+               C14 -> PC4                              
+               C15 -> PC5                              
+
+  Table of timers available per ADC (from libstm/src/stm32_adc.c): 
+
+               T1_TRGO:        Timer1 TRGO event (ADC1, ADC2 and ADC3)
+               T1_CC4:         Timer1 capture compare4 (ADC1, ADC2 and ADC3)
+               T2_TRGO:        Timer2 TRGO event (ADC1 and ADC2)
+               T2_CC1:         Timer2 capture compare1 (ADC1 and ADC2)
+               T3_CC4:         Timer3 capture compare4 (ADC1 and ADC2)
+               T4_TRGO:        Timer4 TRGO event (ADC1 and ADC2)
+               TIM8_CC4: External interrupt line 15 or Timer8 capture compare4 
event (ADC1 and ADC2)
+               T4_CC3:         Timer4 capture compare3 (ADC3 only)
+               T8_CC2:         Timer8 capture compare2 (ADC3 only)
+               T8_CC4:         Timer8 capture compare4 (ADC3 only)
+               T5_TRGO:        Timer5 TRGO event (ADC3 only)
+               T5_CC4:         Timer5 capture compare4 (ADC3 only)
+  
+       By setting ADC_ExternalTrigInjecConv_None, injected conversion
+       is started by software instead of external trigger for any ADC. 
+
+       Table of APB per Timer (from libstm/src/stm32_tim.c): 
+
+               RCC_APB1: TIM2, TIM3, TIM4, TIM5, TIM7 (non-advanced timers)
+               RCC_APB2: TIM1, TIM8 (advanced timers)
+
+*/
+
+#include "adc.h"
+#include "adc_hw.h"
+#include <stm32/rcc.h>
+#include <stm32/misc.h>
+#include <stm32/adc.h>
+#include <stm32/gpio.h>
+#include <stm32/rcc.h>
+#include <stm32/tim.h>
+#include "led.h"
+#include BOARD_CONFIG
+
+void adc1_2_irq_handler(void);
+
+uint8_t adc_new_data_trigger;
+
+/* Static functions */
+
+static inline void adc_init_single(ADC_TypeDef * adc_t, 
+                                  uint8_t chan1, uint8_t chan2, 
+                                  uint8_t chan3, uint8_t chan4);
+
+static inline void adc_push_sample(struct adc_buf * buf, 
+                                  uint16_t sample);
+
+static inline void adc_init_rcc( void );
+static inline void adc_init_irq( void );
+
+#ifdef USE_AD2
+#error NOT_IMPLEMENTED__currently_only_ADC1_is_supported
+#endif
+
+/* 
+  Only 4 ADC channels may be enabled at the same time
+  on each ADC, as there are only 4 injection registers. 
+*/
+
+// ADCx_GPIO_INIT
+// {{{
+
+/* 
+  GPIO mapping for ADC1 pins (PA.B, PB.1, PC.3, PC.5). 
+       Can be changed by predefining ADC1_GPIO_INIT. 
+*/
+#ifdef USE_AD1
+#ifndef ADC1_GPIO_INIT
+#define ADC1_GPIO_INIT(gpio) { \
+       (gpio).GPIO_Pin  = GPIO_Pin_0 | GPIO_Pin_1; \
+       (gpio).GPIO_Mode = GPIO_Mode_AIN; \
+       GPIO_Init(GPIOB, (&gpio)); \
+       (gpio).GPIO_Pin  = GPIO_Pin_3 | GPIO_Pin_5; \
+       GPIO_Init(GPIOC, (&gpio)); \
+}
+#endif // ADC1_GPIO_INIT
+#endif // USE_AD1
+
+/* 
+  GPIO mapping for ADC2 pins. 
+       Can be changed by predefining ADC2_GPIO_INIT. 
+       Uses the same GPIOs as ADC1 (lisa specific). 
+*/
+#ifdef USE_AD2
+#define ADC2_GPIO_INIT(gpio) { \
+       (gpio).GPIO_Pin  = GPIO_Pin_0 | GPIO_Pin_1; \
+       (gpio).GPIO_Mode = GPIO_Mode_AIN; \
+       GPIO_Init(GPIOB, (&gpio)); \
+       (gpio).GPIO_Pin  = GPIO_Pin_3 | GPIO_Pin_5; \
+       GPIO_Init(GPIOC, (&gpio)); \
+}
+#ifndef ADC2_GPIO_INIT
+#define ADC2_GPIO_INIT(gpio) { }
+#endif // ADC2_GPIO_INIT
+#endif // USE_AD2
+
+// }}}
+
+/* 
+  Currently, the enums adc1_channels and adc2_channels only 
+  serve to resolve the number of channels on each ADC. 
+*/
+
+/* 
+       Separate buffers for each ADC. 
+       Every ADC has a list of buffers, one for each active 
+       channel. 
+*/
+
+#ifdef USE_AD1
+static struct adc_buf * adc1_buffers[NB_ADC1_CHANNELS];
+#endif
+#ifdef USE_AD2
+static struct adc_buf * adc2_buffers[NB_ADC2_CHANNELS];
+#endif
+
+/* 
+       Static mapping from channel index to channel injection
+       index: 
+*/
+
+/*
+ Maps integer value x to ADC_InjectedChannel_x, 
+ so they can be iterated safely 
+*/
+static uint8_t adc_injected_channels[4]; 
+/*
+ Maps integer value x to ADC_Channel_y, like
+ 
+ 0 --> ADC_Channel_5
+ 1 --> ADC_Channel_8
+ 2 --> ADC_Channel_13
+
+ so they can be iterated incrementally. 
+*/
+static uint8_t adc_channel_map[4]; 
+
+/* 
+  TODO: Extend interface to allow adressing a 
+  specific ADC (at least ADC1 and ADC2)?
+*/
+void adc_buf_channel(uint8_t adc_channel, 
+                    struct adc_buf * s, 
+                    uint8_t av_nb_sample) 
+{
+  adc1_buffers[adc_channel] = s; 
+  s->av_nb_sample = av_nb_sample;
+}
+
+// #define USE_AD_TIM4
+/* Configure and enable RCC for peripherals (ADC1, ADC2, Timer) */
+static inline void adc_init_rcc( void ) 
+{ // {{{
+#if defined (USE_AD1) || defined (USE_AD2)
+       TIM_TypeDef * timer; 
+       uint32_t rcc_apb; 
+#if defined(USE_AD_TIM4)
+       timer   = TIM4;
+       rcc_apb = RCC_APB1Periph_TIM4;
+#elif defined(USE_AD_TIM1)
+       timer   = TIM1;
+       rcc_apb = RCC_APB2Periph_TIM1;
+#else 
+       timer   = TIM2;
+       rcc_apb = RCC_APB1Periph_TIM2;
+#endif
+
+       TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+
+       RCC_ADCCLKConfig(RCC_PCLK2_Div2);
+       RCC_APB1PeriphClockCmd(rcc_apb, ENABLE);
+       RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB | 
+                              RCC_APB2Periph_GPIOC, ENABLE);
+#ifdef USE_AD1
+       RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1, ENABLE);
+#endif
+#ifdef USE_AD2
+       RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC2, ENABLE);
+#endif
+       
+       /* Time Base configuration */
+       TIM_TimeBaseStructInit(&TIM_TimeBaseStructure); 
+       TIM_TimeBaseStructure.TIM_Period        = 0xFF;          
+       TIM_TimeBaseStructure.TIM_Prescaler     = 0x8; 
+       TIM_TimeBaseStructure.TIM_ClockDivision = 0x0; 
+       TIM_TimeBaseStructure.TIM_CounterMode   = TIM_CounterMode_Up;  
+       TIM_TimeBaseInit(timer, &TIM_TimeBaseStructure);
+       TIM_SelectOutputTrigger(timer, TIM_TRGOSource_Update);
+       TIM_Cmd(timer, ENABLE);
+
+#endif // defined (USE_AD1) || defined (USE_AD2)
+} // }}}
+
+/* Configure and enable ADC interrupt */
+static inline void adc_init_irq( void ) 
+{ // {{{
+       NVIC_InitTypeDef nvic;
+       nvic.NVIC_IRQChannel                   = ADC1_2_IRQn; 
+       nvic.NVIC_IRQChannelPreemptionPriority = 0;
+       nvic.NVIC_IRQChannelSubPriority        = 0;
+       nvic.NVIC_IRQChannelCmd                = ENABLE;
+       NVIC_Init(&nvic);
+} // }}}
+
+/* 
+       Usage: 
+       
+               adc_init_single(ADC1, 1, 1, 0, 0);
+       
+       ... would enable ADC1, enabling channels 1 and 2, 
+       but not 3 and 4. 
+*/
+static inline void adc_init_single(ADC_TypeDef * adc_t, 
+                                  uint8_t chan1, uint8_t chan2, 
+                                  uint8_t chan3, uint8_t chan4) 
+{ 
+       GPIO_InitTypeDef gpio;
+       ADC_InitTypeDef adc;
+       uint8_t num_channels, rank; 
+
+       // Paranoia, must be down for 2+ ADC clock cycles before calibration
+       ADC_Cmd(adc_t, DISABLE); 
+
+       /* enable adc_t clock */
+       if (adc_t == ADC1) { 
+#ifdef USE_AD1
+               num_channels = NB_ADC1_CHANNELS;
+               ADC1_GPIO_INIT(gpio);
+#endif
+       }
+       else if (adc_t == ADC2) { 
+#ifdef USE_AD2
+               num_channels = NB_ADC2_CHANNELS;
+               ADC2_GPIO_INIT(gpio); 
+#endif
+       }
+
+       /* Configure ADC */
+       
+       adc.ADC_Mode               = ADC_Mode_Independent; 
+       adc.ADC_ScanConvMode       = ENABLE;
+       adc.ADC_ContinuousConvMode = DISABLE;
+       adc.ADC_ExternalTrigConv   = ADC_ExternalTrigConv_None;
+       adc.ADC_DataAlign          = ADC_DataAlign_Right;
+       adc.ADC_NbrOfChannel       = 0; // No. of channels in regular mode
+       ADC_Init(adc_t, &adc);
+
+       ADC_InjectedSequencerLengthConfig(adc_t, num_channels);
+
+       rank = 1; 
+       if (chan1) { 
+               ADC_InjectedChannelConfig(adc_t, adc_channel_map[0], rank,
+                                         ADC_SampleTime_41Cycles5);
+               rank++;
+       }
+       if (chan2) { 
+               ADC_InjectedChannelConfig(adc_t, adc_channel_map[1], rank,
+                                         ADC_SampleTime_41Cycles5);
+               rank++;
+       }
+       if (chan3) { 
+               ADC_InjectedChannelConfig(adc_t, adc_channel_map[2], rank,
+                                         ADC_SampleTime_41Cycles5);
+               rank++;
+       }
+       if (chan4) { 
+               ADC_InjectedChannelConfig(adc_t, adc_channel_map[3], rank,
+                                         ADC_SampleTime_41Cycles5);
+       }
+
+
+       ADC_ExternalTrigInjectedConvCmd(adc_t, ENABLE);
+#if defined(USE_AD_TIM4)
+       ADC_ExternalTrigInjectedConvConfig(adc_t, 
ADC_ExternalTrigInjecConv_T4_TRGO);
+#elif defined(USE_AD_TIM1)
+       ADC_ExternalTrigInjectedConvConfig(adc_t, 
ADC_ExternalTrigInjecConv_T1_TRGO);
+#else
+       ADC_ExternalTrigInjectedConvConfig(adc_t, 
ADC_ExternalTrigInjecConv_T2_TRGO);
+#endif
+
+       /* Enable ADC<X> JEOC interrupt */
+       ADC_ITConfig(adc_t, ADC_IT_JEOC, ENABLE);
+
+       /* Enable ADC<X> */
+       ADC_Cmd(adc_t, ENABLE);
+
+       /* Enable ADC<X> reset calibaration register */
+       ADC_ResetCalibration(adc_t);
+
+       /* Check the end of ADC<X> reset calibration */
+       while (ADC_GetResetCalibrationStatus(adc_t)) ;
+       /* Start ADC<X> calibaration */
+       ADC_StartCalibration(adc_t);
+       /* Check the end of ADC<X> calibration */
+       while (ADC_GetCalibrationStatus(adc_t)) ;
+
+} // adc_init_single
+
+void adc_init( void ) { 
+
+       /* initialize buffer pointers with 0 (not set). 
+                buffer null pointers will be ignored in interrupt 
+                handler, which is important as there are no 
+                buffers registered at the time the ADC trigger 
+                interrupt is enabled. 
+       */
+       uint8_t channel;
+#ifdef USE_AD1
+       for(channel = 0; channel < NB_ADC1_CHANNELS; channel++)
+               adc1_buffers[channel] = 0; 
+#endif
+#ifdef USE_AD2
+       for(channel = 0; channel < NB_ADC2_CHANNELS; channel++)
+               adc2_buffers[channel] = 0; 
+#endif
+       
+       adc_new_data_trigger = 0;
+       adc_injected_channels[0] = ADC_InjectedChannel_1;
+       adc_injected_channels[1] = ADC_InjectedChannel_2;
+       adc_injected_channels[2] = ADC_InjectedChannel_3;
+       adc_injected_channels[3] = ADC_InjectedChannel_4;
+       // TODO: Channel selection could be configured 
+       // using defines. 
+       adc_channel_map[0] = ADC_Channel_8;
+       adc_channel_map[1] = ADC_Channel_9;
+       adc_channel_map[2] = ADC_Channel_13;
+       adc_channel_map[3] = ADC_Channel_15;
+
+       adc_init_rcc(); 
+       adc_init_irq(); 
+
+// adc_init_single(ADCx, c1, c2, c3, c4)
+// {{{
+#ifdef USE_AD1
+       adc_init_single(ADC1, 
+#ifdef USE_AD1_1
+                       1, 
+#else 
+                       0, 
+#endif
+#ifdef USE_AD1_2
+                       1, 
+#else 
+                       0, 
+#endif
+#ifdef USE_AD1_3
+                       1, 
+#else 
+                       0, 
+#endif
+#ifdef USE_AD1_4
+                       1 
+#else 
+                       0 
+#endif
+       );
+#endif // USE_AD1
+
+#ifdef USE_AD2
+       adc_init_single(ADC2, 
+#ifdef USE_AD2_1
+                       1, 
+#else 
+                       0, 
+#endif
+#ifdef USE_AD2_2
+                       1, 
+#else 
+                       0, 
+#endif
+#ifdef USE_AD2_3
+                       1, 
+#else 
+                       0, 
+#endif
+#ifdef USE_AD2_4
+                       1 
+#else 
+                       0 
+#endif
+       );
+#endif // USE_AD2
+
+// }}}
+}
+
+static inline void adc_push_sample(struct adc_buf * buf, uint16_t value) { 
+       uint8_t new_head = buf->head + 1; 
+       
+       if (new_head >= buf->av_nb_sample) { new_head = 0; }
+       buf->sum -= buf->values[new_head];
+       buf->values[new_head] = value;
+       buf->sum += value;
+       buf->head = new_head;
+}
+
+/**
+ * ADC1+2 interrupt hander
+ */
+void adc1_2_irq_handler(void)
+{
+       uint8_t channel = 0;
+       uint16_t value  = 0; 
+       struct adc_buf * buf; 
+
+#ifdef USE_AD1
+       // Clear Injected End Of Conversion
+       ADC_ClearITPendingBit(ADC1, ADC_IT_JEOC); 
+       for(channel = 0; channel < NB_ADC1_CHANNELS; channel++) { 
+               buf = adc1_buffers[channel];
+               if(buf) { 
+                       value = ADC_GetInjectedConversionValue(ADC1, 
adc_injected_channels[channel]);
+                       adc_push_sample(buf, value);
+               }
+       }
+       adc_new_data_trigger = 1;
+#endif
+#ifdef USE_AD2
+       // Clear Injected End Of Conversion
+       ADC_ClearITPendingBit(ADC2, ADC_IT_JEOC); 
+       for(channel = 0; channel < NB_ADC2_CHANNELS; channel++) { 
+               buf = adc2_buffers[channel];
+               if(buf) { 
+                       value = ADC_GetInjectedConversionValue(ADC2, 
adc_injected_channels[channel]);
+                       adc_push_sample(buf, value);
+               }
+       }
+       adc_new_data_trigger = 1;
+#endif
+}
+

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/adc_hw.h (from rev 5935, 
paparazzi3/trunk/sw/airborne/stm32/adc_hw.h)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/adc_hw.h                            
(rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/adc_hw.h    2010-09-23 22:28:37 UTC 
(rev 5936)
@@ -0,0 +1,86 @@
+/*
+ * $Id$
+ *  
+ * Copyright (C) 2010  Paparazzi team
+ *
+ * This file is part of Paparazzi.
+ *
+ * Paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * Paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA. 
+ *
+ */
+
+#ifndef ADC_HW_H
+#define ADC_HW_H
+
+/*
+ * Architecture dependant ADC functions for STM32
+ * For now only hard coded for Lisa/L
+ *
+ * Logic   STM32  
+ * ADC1    PC3     ADC13 
+ * ADC2    PC5     ADC15
+ * ADC3    PB0     ADC8
+ * ADC4    PB1     ADC9
+ * ADC5    PB2     BOOT1
+ *         PA0     ADC0   bat monitor        
+ */
+
+// NB_ADCx_CHANNELS
+// {{{
+enum adc1_channels { 
+#ifdef USE_AD1_1
+       ADC1_C1,
+#endif
+#ifdef USE_AD1_2
+       ADC1_C2,
+#endif
+#ifdef USE_AD1_3
+       ADC1_C3,
+#endif
+#ifdef USE_AD1_4
+       ADC1_C4,
+#endif
+       NB_ADC1_CHANNELS
+};
+
+enum adc2_channels { 
+#ifdef USE_AD2_1
+       ADC2_C1,
+#endif
+#ifdef USE_AD2_2
+       ADC2_C2,
+#endif
+#ifdef USE_AD2_3
+       ADC2_C3,
+#endif
+#ifdef USE_AD2_4
+       ADC2_C4,
+#endif
+       NB_ADC2_CHANNELS
+};
+
+#ifdef NB_ADC
+#undef NB_ADC
+#endif
+
+#define NB_ADC (NB_ADC1_CHANNELS + NB_ADC2_CHANNELS)
+
+// }}}
+
+#define AdcBank0(x) (x)
+#define AdcBank1(x) (x+NB_ADC)
+
+#endif /* ADC_HW_H */

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/can_hw.c (from rev 5935, 
paparazzi3/trunk/sw/airborne/stm32/can_hw.c)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/can_hw.c                            
(rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/can_hw.c    2010-09-23 22:28:37 UTC 
(rev 5936)
@@ -0,0 +1,154 @@
+/*
+ * $Id:$
+ *
+ * Copyright (C) 2010 Piotr Esden-Tempski <address@hidden>
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ *
+ */
+
+#include <stdint.h>
+#include <string.h>
+
+#include "can_hw.h"
+
+#include <stm32/rcc.h>
+#include <stm32/gpio.h>
+#include <stm32/flash.h>
+#include <stm32/misc.h>
+#include <stm32/can.h>
+
+#include "led.h"
+
+#define RCC_APB2Periph_GPIO_CAN RCC_APB2Periph_GPIOA
+#define GPIO_CAN GPIOA
+#define GPIO_Pin_CAN_RX GPIO_Pin_11
+#define GPIO_Pin_CAN_TX GPIO_Pin_12
+
+CanTxMsg can_tx_msg;
+CanRxMsg can_rx_msg;
+
+void _can_run_rx_callback(uint32_t id, uint8_t *buf, uint8_t len);
+
+void can_hw_init(void)
+{
+       GPIO_InitTypeDef gpio;
+       NVIC_InitTypeDef nvic;
+       CAN_InitTypeDef can;
+       CAN_FilterInitTypeDef can_filter;
+
+       /* Enable peripheral clocks */
+       RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO |
+                              RCC_APB2Periph_GPIOA, ENABLE);
+       RCC_APB1PeriphClockCmd(RCC_APB1Periph_CAN1, ENABLE);
+
+       /* Configure CAN pin: RX */
+       gpio.GPIO_Pin = GPIO_Pin_11;
+       gpio.GPIO_Mode = GPIO_Mode_IPU;
+       GPIO_Init(GPIOA, &gpio);
+
+       /* Configure CAN pin: TX */
+       gpio.GPIO_Pin = GPIO_Pin_12;
+       gpio.GPIO_Mode = GPIO_Mode_AF_PP;
+       gpio.GPIO_Speed = GPIO_Speed_50MHz;
+       GPIO_Init(GPIOA, &gpio);
+
+       /* NVIC configuration */
+       NVIC_PriorityGroupConfig(NVIC_PriorityGroup_0);
+
+       nvic.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn;
+       nvic.NVIC_IRQChannelPreemptionPriority = 0x00;
+       nvic.NVIC_IRQChannelSubPriority = 0x00;
+       nvic.NVIC_IRQChannelCmd = ENABLE;
+       NVIC_Init(&nvic);
+
+       /* CAN register init */
+       CAN_DeInit(CAN1);
+       CAN_StructInit(&can);
+
+       /* CAN cell init */
+       can.CAN_TTCM = DISABLE;
+       can.CAN_ABOM = CAN_ERR_RESUME;
+       can.CAN_AWUM = DISABLE;
+       can.CAN_NART = DISABLE;
+       can.CAN_RFLM = DISABLE;
+       can.CAN_TXFP = DISABLE;
+       can.CAN_Mode = CAN_Mode_Normal;
+       can.CAN_SJW = CAN_SJW_TQ;
+       can.CAN_BS1 = CAN_BS1_TQ;
+       can.CAN_BS2 = CAN_BS2_TQ;
+       can.CAN_Prescaler = CAN_PRESCALER;
+       can.CAN_ABOM = ENABLE;
+       CAN_Init(CAN1, &can);
+
+       /* CAN filter init */
+       can_filter.CAN_FilterNumber = 0;
+       can_filter.CAN_FilterMode = CAN_FilterMode_IdMask;
+       can_filter.CAN_FilterScale = CAN_FilterScale_32bit;
+       can_filter.CAN_FilterIdHigh = 0x0000;
+       can_filter.CAN_FilterIdLow = 0x0000;
+       can_filter.CAN_FilterMaskIdHigh = 0x0000;
+       can_filter.CAN_FilterMaskIdLow = 0x0000;
+       can_filter.CAN_FilterFIFOAssignment = 0;
+       can_filter.CAN_FilterActivation = ENABLE;
+       CAN_FilterInit(&can_filter);
+
+       /* transmit struct init */
+       can_tx_msg.StdId = 0x0;
+       can_tx_msg.ExtId = 0x0;
+       can_tx_msg.RTR = CAN_RTR_DATA;
+#ifdef USE_CAN_EXT_ID
+       can_tx_msg.IDE = CAN_ID_EXT;
+#else
+       can_tx_msg.IDE = CAN_ID_STD;
+#endif
+       can_tx_msg.DLC = 1;
+
+       CAN_ITConfig(CAN1, CAN_IT_FMP0, ENABLE);
+}
+
+int can_hw_transmit(uint32_t id, const uint8_t *buf, uint8_t len)
+{
+       if(len > 8){
+               return -1;
+       }
+
+#ifdef USE_CAN_EXT_ID
+       can_tx_msg.ExtId = id;
+#else
+       can_tx_msg.StdId = id;
+#endif
+       can_tx_msg.DLC = len;
+
+       memcpy(can_tx_msg.Data, buf, len);
+
+       CAN_Transmit(CAN1, &can_tx_msg);
+
+       return 0;
+}
+
+void usb_lp_can1_rx0_irq_handler(void)
+{
+       CAN_Receive(CAN1, CAN_FIFO0, &can_rx_msg);
+#ifdef USE_CAN_EXT_ID
+       _can_run_rx_callback(can_rx_msg.ExtId, can_rx_msg.Data, can_rx_msg.DLC);
+#else
+       _can_run_rx_callback(can_rx_msg.StdId, can_rx_msg.Data, can_rx_msg.DLC);
+#endif
+}
+

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/can_hw.c.bak (from rev 5935, 
paparazzi3/trunk/sw/airborne/stm32/can_hw.c.bak)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/can_hw.c.bak                        
        (rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/can_hw.c.bak        2010-09-23 
22:28:37 UTC (rev 5936)
@@ -0,0 +1,143 @@
+/*
+ * $Id:$
+ *
+ * Copyright (C) 2010 Piotr Esden-Tempski <address@hidden>
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ *
+ */
+
+#include <stdint.h>
+#include <string.h>
+
+#include "can_hw.h"
+
+#include <stm32/rcc.h>
+#include <stm32/gpio.h>
+#include <stm32/flash.h>
+#include <stm32/misc.h>
+#include <stm32/can.h>
+
+#include "led.h"
+
+#define RCC_APB2Periph_GPIO_CAN RCC_APB2Periph_GPIOA
+#define GPIO_CAN GPIOA
+#define GPIO_Pin_CAN_RX GPIO_Pin_11
+#define GPIO_Pin_CAN_TX GPIO_Pin_12
+
+CanTxMsg can_tx_msg;
+
+void can_hw_init(void)
+{
+       GPIO_InitTypeDef gpio;
+       NVIC_InitTypeDef nvic;
+       CAN_InitTypeDef can;
+       CAN_FilterInitTypeDef can_filter;
+
+       /* Enable peripheral clocks */
+       RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO |
+                              RCC_APB2Periph_GPIO_CAN, ENABLE);
+       RCC_APB1PeriphClockCmd(RCC_APB1Periph_CAN1, ENABLE);
+
+       /* Configure CAN pin: RX */
+       gpio.GPIO_Pin = GPIO_Pin_CAN_RX;
+       gpio.GPIO_Mode = GPIO_Mode_IPU;
+       gpio.GPIO_Speed = GPIO_Speed_50MHz;
+       GPIO_Init(GPIO_CAN, &gpio);
+
+       /* Configure CAN pin: TX */
+       gpio.GPIO_Pin = GPIO_Pin_CAN_TX;
+       gpio.GPIO_Mode = GPIO_Mode_AF_PP;
+       gpio.GPIO_Speed = GPIO_Speed_50MHz;
+       GPIO_Init(GPIO_CAN, &gpio);
+
+       /* NVIC configuration */
+       NVIC_PriorityGroupConfig(NVIC_PriorityGroup_0);
+
+       nvic.NVIC_IRQChannel = USB_LP_CAN1_RX0_IRQn;
+       nvic.NVIC_IRQChannelPreemptionPriority = 0x00;
+       nvic.NVIC_IRQChannelSubPriority = 0x00;
+       nvic.NVIC_IRQChannelCmd = ENABLE;
+       NVIC_Init(&nvic);
+
+       /* CAN register init */
+       CAN_DeInit(CAN1);
+       CAN_StructInit(&can);
+
+       /* CAN cell init */
+       can.CAN_TTCM = DISABLE;
+       can.CAN_ABOM = DISABLE;
+       can.CAN_AWUM = DISABLE;
+       can.CAN_NART = DISABLE;
+       can.CAN_RFLM = DISABLE;
+       can.CAN_TXFP = DISABLE;
+       can.CAN_Mode = CAN_Mode_Normal;
+       can.CAN_SJW = CAN_SJW_1tq;
+       can.CAN_BS1 = CAN_BS1_3tq;
+       can.CAN_BS2 = CAN_BS2_5tq;
+       can.CAN_Prescaler = 4;
+       CAN_Init(CAN1, &can);
+
+       /* CAN filter init */
+       can_filter.CAN_FilterNumber = 0;
+       can_filter.CAN_FilterMode = CAN_FilterMode_IdMask;
+       can_filter.CAN_FilterScale = CAN_FilterScale_32bit;
+       can_filter.CAN_FilterIdHigh = 0x0000;
+       can_filter.CAN_FilterIdLow = 0x0000;
+       can_filter.CAN_FilterMaskIdHigh = 0x0000;
+       can_filter.CAN_FilterMaskIdLow = 0x0000;
+       can_filter.CAN_FilterFIFOAssignment = 0;
+       can_filter.CAN_FilterActivation = ENABLE;
+       CAN_FilterInit(&can_filter);
+
+       /* transmit struct init */
+       can_tx_msg.StdId = 0x321;
+       can_tx_msg.ExtId = 0x00;
+       can_tx_msg.RTR = CAN_RTR_DATA;
+       can_tx_msg.IDE = CAN_ID_STD;
+       can_tx_msg.DLC = 1;
+
+       CAN_ITConfig(CAN1, CAN_IT_FMP0, ENABLE);
+
+       can_tx_msg.Data[0] = 0x55;
+
+       CAN_Transmit(CAN1, &can_tx_msg);
+}
+
+int can_hw_transmit(uint16_t id, const uint8_t *buf, uint8_t len)
+{
+       if(len > 8){
+               return -1;
+       }
+
+//     can_tx_msg.StdId = id >> 8;
+//     can_tx_msg.ExtId = id & 0xFF;
+//     can_tx_msg.DLC = len;
+//     memcpy(&can_tx_msg.Data, buf, len);
+//
+//     CAN_Transmit(CAN1, &can_tx_msg);
+
+       //can_tx_msg.StdId = 0;
+       //can_tx_msg.ExtId = 0x1234;
+       //can_tx_msg.DLC = 1;
+       //can_tx_msg.Data[0] = 0x55;
+
+       //CAN_Transmit(CAN1, &can_tx_msg);
+
+       return 0;
+}

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/can_hw.h (from rev 5935, 
paparazzi3/trunk/sw/airborne/stm32/can_hw.h)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/can_hw.h                            
(rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/can_hw.h    2010-09-23 22:28:37 UTC 
(rev 5936)
@@ -0,0 +1,32 @@
+/*
+ * $Id:$
+ *
+ * Copyright (C) 2010 Piotr Esden-Tempski <address@hidden>
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ *
+ */
+
+#ifndef CAN_HW_H
+#define CAN_HW_H
+
+void can_hw_init(void);
+void usb_lp_can1_rx0_irq_handler(void);
+int can_hw_transmit(uint32_t id, const uint8_t *buf, uint8_t len);
+
+#endif /* CAN_HW_H */

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/gps_hw.h (from rev 5935, 
paparazzi3/trunk/sw/airborne/stm32/gps_hw.h)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/gps_hw.h                            
(rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/gps_hw.h    2010-09-23 22:28:37 UTC 
(rev 5936)
@@ -0,0 +1,4 @@
+#ifndef GPS_HW_H
+#define GPS_HW_H
+
+#endif /* GPS_HW_H */

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/i2c_hw.c (from rev 5935, 
paparazzi3/trunk/sw/airborne/stm32/i2c_hw.c)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/i2c_hw.c                            
(rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/i2c_hw.c    2010-09-23 22:28:37 UTC 
(rev 5936)
@@ -0,0 +1,719 @@
+#include "i2c.h"
+
+#include <stm32/rcc.h>
+#include <stm32/gpio.h>
+#include <stm32/flash.h>
+#include <stm32/misc.h>
+
+
+static void start_transaction(struct i2c_periph* p);
+
+
+
+#ifdef USE_I2C1
+
+struct i2c_errors i2c1_errors;
+
+#include "my_debug_servo.h"
+
+#define I2C1_APPLY_CONFIG() {                                          \
+    I2C_InitTypeDef  I2C_InitStructure;                                        
\
+    I2C_InitStructure.I2C_Mode = I2C_Mode_I2C;                         \
+    I2C_InitStructure.I2C_DutyCycle = I2C_DutyCycle_2;                 \
+    I2C_InitStructure.I2C_OwnAddress1 = 0x00;                          \
+    I2C_InitStructure.I2C_Ack = I2C_Ack_Enable;                                
\
+    I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit; \
+    I2C_InitStructure.I2C_ClockSpeed = 200000;                         \
+    I2C_Init(I2C1, &I2C_InitStructure);                                        
\
+  }
+
+#define I2C1_END_OF_TRANSACTION() {                                    \
+    i2c1.trans_extract_idx++;                                          \
+    if (i2c1.trans_extract_idx>=I2C_TRANSACTION_QUEUE_LEN)             \
+      i2c1.trans_extract_idx = 0;                                      \
+    /* if we have no more transaction to process, stop here */         \
+    if (i2c1.trans_extract_idx == i2c1.trans_insert_idx)               \
+      i2c1.status = I2CIdle;                                           \
+    /* if not, start next transaction */                               \
+    else                                                               \
+      start_transaction(&i2c1);                                                
\
+  }
+
+#define I2C1_ABORT_AND_RESET() {                                       \
+    struct i2c_transaction* trans2 = i2c1.trans[i2c1.trans_extract_idx]; \
+    trans2->status = I2CTransFailed;                                   \
+    i2c1.status = I2CFailed;                                           \
+    I2C_ITConfig(I2C1, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR, DISABLE); \
+    I2C_Cmd(I2C1, DISABLE);                                            \
+    I2C_DeInit(I2C1);                                                  \
+    I2C_Cmd(I2C1, ENABLE);                                             \
+    I2C1_APPLY_CONFIG();                                               \
+    I2C_ITConfig(I2C1, I2C_IT_ERR, ENABLE);                            \
+    I2C1_END_OF_TRANSACTION();                                         \
+  }
+
+//
+// I2C1 base 0x40005400
+//
+//   I2C1 CR1 0x40005400
+//   I2C1 CR2 0x40005404
+//
+// I2C2 base 0x40005800
+//
+
+
+void i2c1_hw_init(void) {
+
+  i2c1.reg_addr = I2C1;
+
+  /* zeros error counter */
+  ZEROS_ERR_COUNTER(i2c1_errors);
+  
+  I2C_DeInit(I2C1);
+    
+  NVIC_PriorityGroupConfig(NVIC_PriorityGroup_0);
+  NVIC_InitTypeDef  NVIC_InitStructure;
+  
+  /* Configure and enable I2C1 event interrupt 
-------------------------------*/
+  NVIC_InitStructure.NVIC_IRQChannel = I2C1_EV_IRQn;
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+
+  /* Configure and enable I2C1 err interrupt -------------------------------*/
+  NVIC_InitStructure.NVIC_IRQChannel = I2C1_ER_IRQn;
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+
+  /* Enable peripheral clocks 
--------------------------------------------------*/
+  /* Enable I2C1 clock */
+  RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE);
+  /* Enable GPIOB clock */
+  RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
+
+  /* Configure I2C1 pins: SCL and SDA 
------------------------------------------*/
+  GPIO_InitTypeDef GPIO_InitStructure;
+  GPIO_StructInit(&GPIO_InitStructure);
+  GPIO_InitStructure.GPIO_Pin =  GPIO_Pin_6 | GPIO_Pin_7;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_OD;
+  GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+  /* I2C configuration 
----------------------------------------------------------*/
+  
+  /* I2C Peripheral Enable */
+  I2C_Cmd(I2C1, ENABLE);
+  /* Apply I2C configuration after enabling it */
+  I2C1_APPLY_CONFIG();
+  
+  /* Enable I2C1 error interrupts */
+  I2C_ITConfig(I2C1, I2C_IT_ERR, ENABLE);
+
+}
+
+
+void i2c1_ev_irq_handler(void) {
+
+  uint32_t event = I2C_GetLastEvent(I2C1);
+  struct i2c_transaction* trans = i2c1.trans[i2c1.trans_extract_idx];
+  switch (event) {
+    /* EV5 */
+  case I2C_EVENT_MASTER_MODE_SELECT:        
+    if (trans->type == I2CTransTx || trans->type == I2CTransTxRx) {
+      /* Master Transmitter : Send slave Address for write */
+      I2C_Send7bitAddress(I2C1, (trans->slave_addr&0xFE), 
I2C_Direction_Transmitter);
+    }
+    else {
+      /* Master Receiver : Send slave Address for read */
+      I2C_Send7bitAddress(I2C1, (trans->slave_addr&0xFE), 
I2C_Direction_Receiver);
+    }
+    break;
+    
+    /* Master Transmitter --------------------------------------------------*/
+    /* Test on I2C1 EV6 and first EV8 and clear them */
+  case I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED:  
+    /* enable empty dr if we have more than one byte to send */
+    //    if (i2c1_len_w > 1)
+    I2C_ITConfig(I2C1, I2C_IT_BUF, ENABLE);
+    /* Send the first data */
+    I2C_SendData(I2C1, trans->buf[0]);
+    i2c1.idx_buf = 1;
+    break;
+    
+    /* Test on I2C1 EV8 and clear it */
+  case I2C_EVENT_MASTER_BYTE_TRANSMITTING:  /* Without BTF, EV8 */     
+    //    DEBUG_S5_TOGGLE();
+    if(i2c1.idx_buf < trans->len_w) {
+      I2C_SendData(I2C1, trans->buf[i2c1.idx_buf]);
+      i2c1.idx_buf++;
+    }
+    else {
+      I2C_GenerateSTOP(I2C1, ENABLE);
+      //  I2C_GenerateSTART(I2C1, ENABLE);
+      I2C_ITConfig(I2C1, I2C_IT_BUF, DISABLE);
+    }
+    break;
+
+  case I2C_EVENT_MASTER_BYTE_TRANSMITTED: /* With BTF EV8-2 */
+    //    DEBUG_S6_TOGGLE();
+    if(i2c1.idx_buf < trans->len_w) {
+      I2C_SendData(I2C1, trans->buf[i2c1.idx_buf]);
+      i2c1.idx_buf++;
+    }
+    else {
+      trans->status = I2CTransSuccess;
+      I2C_ITConfig(I2C1, I2C_IT_EVT, DISABLE);
+      I2C1_END_OF_TRANSACTION();
+    }
+    //      while (I2C_GetFlagStatus(I2C1, I2C_FLAG_MSL));
+    break;
+
+  default:
+    i2c1_errors.unexpected_event_cnt++;
+    i2c1_errors.last_unexpected_event = event;
+    // spurious Interrupt
+    //    DEBUG_S2_TOGGLE();
+    // I have already had I2C_EVENT_SLAVE_STOP_DETECTED ( 0x10 )
+    // let's clear that by restarting I2C
+    //    if (event ==  I2C_EVENT_SLAVE_STOP_DETECTED) {
+    // ok....? let's try that
+    I2C1_ABORT_AND_RESET();
+    break;
+  }
+
+}
+
+
+void i2c1_er_irq_handler(void) {
+  
+  if (I2C_GetITStatus(I2C1, I2C_IT_AF)) {   /* Acknowledge failure */
+    i2c1_errors.ack_fail_cnt++;
+    I2C_ClearITPendingBit(I2C1, I2C_IT_AF);
+    I2C_GenerateSTOP(I2C1, ENABLE);
+  }
+  if (I2C_GetITStatus(I2C1, I2C_IT_BERR)) {   /* Misplaced Start or Stop 
condition */
+    i2c1_errors.miss_start_stop_cnt++;
+    I2C_ClearITPendingBit(I2C1, I2C_IT_BERR);
+  }
+  if (I2C_GetITStatus(I2C1, I2C_IT_ARLO)) {   /* Arbitration lost */
+    i2c1_errors.arb_lost_cnt++;
+    I2C_ClearITPendingBit(I2C1, I2C_IT_ARLO);
+  }
+  if (I2C_GetITStatus(I2C1, I2C_IT_OVR)) {    /* Overrun/Underrun */
+    i2c1_errors.over_under_cnt++;
+    I2C_ClearITPendingBit(I2C1, I2C_IT_OVR);
+  }
+  if (I2C_GetITStatus(I2C1, I2C_IT_PECERR)) { /* PEC Error in reception */
+    i2c1_errors.pec_recep_cnt++;
+    I2C_ClearITPendingBit(I2C1, I2C_IT_PECERR);
+  }
+  if (I2C_GetITStatus(I2C1, I2C_IT_TIMEOUT)) { /* Timeout or Tlow error */
+    i2c1_errors.timeout_tlow_cnt++;
+    I2C_ClearITPendingBit(I2C1, I2C_IT_TIMEOUT);
+  }
+  if (I2C_GetITStatus(I2C1, I2C_IT_SMBALERT)) { /* SMBus alert */
+    i2c1_errors.smbus_alert_cnt++;
+    I2C_ClearITPendingBit(I2C1, I2C_IT_SMBALERT);
+  }
+  
+  I2C1_ABORT_AND_RESET();
+  
+}
+
+#endif /* USE_I2C1 */
+
+
+
+
+
+#ifdef USE_I2C2
+
+//  dec      hex
+//  196609   30001        BUSY  MSL |                 SB
+//  458882   70082    TRA BUSY  MSL | TXE       ADDR
+//  458884   70084    TRA BUSY  MSL | TXE  BTF    
+//  196609   30001        BUSY  MSL |                 SB   
+//  196610   30002        BUSY  MSL |           ADDR
+//  
+
+
+struct i2c_errors i2c2_errors;
+
+#include "my_debug_servo.h"
+
+#define I2C2_APPLY_CONFIG() {                                          \
+                                                                       \
+    I2C_InitTypeDef  I2C_InitStructure= {                              \
+      .I2C_Mode = I2C_Mode_I2C,                                                
\
+      .I2C_DutyCycle = I2C_DutyCycle_2,                                        
\
+      .I2C_OwnAddress1 = 0x00,                                         \
+      .I2C_Ack = I2C_Ack_Enable,                                       \
+      .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,         \
+      .I2C_ClockSpeed = 300000                                         \
+    };                                                                 \
+    I2C_Init(I2C2, &I2C_InitStructure);                                        
\
+                                                                       \
+  }
+
+
+void i2c2_hw_init(void) {
+  
+  i2c2.reg_addr = I2C2;
+
+  /* zeros error counter */
+  ZEROS_ERR_COUNTER(i2c2_errors);
+  
+  /* reset periphearl to default state ( sometimes not achieved on reset :(  ) 
*/
+  I2C_DeInit(I2C2);
+
+  NVIC_PriorityGroupConfig(NVIC_PriorityGroup_0);
+  NVIC_InitTypeDef  NVIC_InitStructure;
+  
+  /* Configure and enable I2C2 event interrupt 
--------------------------------*/
+  NVIC_InitStructure.NVIC_IRQChannel = I2C2_EV_IRQn;
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+
+  /* Configure and enable I2C2 err interrupt 
----------------------------------*/
+  NVIC_InitStructure.NVIC_IRQChannel = I2C2_ER_IRQn;
+  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0;
+  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&NVIC_InitStructure);
+
+  /* Enable peripheral clocks 
-------------------------------------------------*/
+  /* Enable I2C2 clock */
+  RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C2, ENABLE);
+  /* Enable GPIOB clock */
+  RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);
+
+  /* Configure I2C2 pins: SCL and SDA 
-----------------------------------------*/
+  GPIO_InitTypeDef GPIO_InitStructure;
+  GPIO_InitStructure.GPIO_Pin =  GPIO_Pin_10 | GPIO_Pin_11;
+  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_10MHz;
+  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_OD;
+  GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+  /* I2C Peripheral Enable 
----------------------------------------------------*/
+  I2C_Cmd(I2C2, ENABLE);
+
+  /* Apply I2C configuration after enabling it */
+  I2C2_APPLY_CONFIG();
+
+  /* Enable I2C2 error interrupts 
---------------------------------------------*/
+  I2C_ITConfig(I2C2, I2C_IT_ERR, ENABLE);
+
+  //  DEBUG_SERVO1_INIT();
+  //  DEBUG_SERVO2_INIT();
+
+}
+
+
+
+
+static inline void on_status_start_requested(struct i2c_transaction* trans, 
uint32_t event);
+static inline void on_status_addr_wr_sent(struct i2c_transaction* trans, 
uint32_t event);
+static inline void on_status_sending_byte(struct i2c_transaction* trans, 
uint32_t event);
+//static inline void on_status_sending_last_byte(struct i2c_transaction* 
trans, uint32_t event);
+static inline void on_status_stop_requested(struct i2c_transaction* trans, 
uint32_t event);
+static inline void on_status_addr_rd_sent(struct i2c_transaction* trans, 
uint32_t event);
+static inline void on_status_reading_byte(struct i2c_transaction* trans, 
uint32_t event);
+static inline void on_status_reading_last_byte(struct i2c_transaction* trans, 
uint32_t event);
+static inline void on_status_restart_requested(struct i2c_transaction* trans, 
uint32_t event);
+
+#ifdef DEBUG_I2C
+#define SPURIOUS_INTERRUPT(_status, _event) { while(1); }
+#define OUT_OF_SYNC_STATE_MACHINE(_status, _event) { while(1); }
+#else
+#define SPURIOUS_INTERRUPT(_status, _event) {}
+#define OUT_OF_SYNC_STATE_MACHINE(_status, _event) {}
+#endif
+
+
+#define I2C2_END_OF_TRANSACTION() {                                    \
+    i2c2.trans_extract_idx++;                                          \
+    if (i2c2.trans_extract_idx>=I2C_TRANSACTION_QUEUE_LEN)             \
+      i2c2.trans_extract_idx = 0;                                      \
+    /* if we have no more transaction to process, stop here */         \
+    if (i2c2.trans_extract_idx == i2c2.trans_insert_idx)               \
+      i2c2.status = I2CIdle;                                           \
+    /* if not, start next transaction */                               \
+    else                                                               \
+      start_transaction(&i2c2);                                                
\
+  }
+
+#define I2C2_ABORT_AND_RESET() {                                       \
+    struct i2c_transaction* trans = i2c2.trans[i2c2.trans_extract_idx];        
\
+    trans->status = I2CTransFailed;                                    \
+    I2C_ITConfig(I2C2, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR, DISABLE); \
+    I2C_Cmd(I2C2, DISABLE);                                            \
+    I2C_DeInit(I2C2);                                                  \
+    I2C_Cmd(I2C2, ENABLE);                                             \
+    I2C2_APPLY_CONFIG();                                               \
+    I2C_ITConfig(I2C2, I2C_IT_ERR, ENABLE);                            \
+    I2C2_END_OF_TRANSACTION();                                         \
+  }
+
+
+
+/*
+ * Start Requested
+ *
+ */
+static inline void on_status_start_requested(struct i2c_transaction* trans, 
uint32_t event) {
+  if (event & I2C_FLAG_SB) {
+    if(trans->type == I2CTransRx) {
+      I2C_Send7bitAddress(I2C2, trans->slave_addr, I2C_Direction_Receiver);
+      i2c2.status = I2CAddrRdSent;
+    }
+    else {
+      I2C_Send7bitAddress(I2C2, trans->slave_addr, I2C_Direction_Transmitter);
+      i2c2.status = I2CAddrWrSent;
+    }                          
+  }                            
+  else
+    SPURIOUS_INTERRUPT(I2CStartRequested, event);
+}
+
+/*
+ * Addr WR sent 
+ *
+ */
+static inline void on_status_addr_wr_sent(struct i2c_transaction* trans, 
uint32_t event) {
+  if ((event & I2C_FLAG_ADDR) && (event & I2C_FLAG_TRA)) {
+    I2C_SendData(I2C2, trans->buf[0]);
+    if (trans->len_w > 1) {
+      I2C_SendData(I2C2, trans->buf[1]);
+      i2c2.idx_buf = 2;
+      I2C_ITConfig(I2C2, I2C_IT_BUF, ENABLE);
+      i2c2.status = I2CSendingByte;
+    }
+    else {
+      i2c2.idx_buf = 1;
+      if (trans->type == I2CTransTx) {
+       I2C_GenerateSTOP(I2C2, ENABLE); 
+       i2c2.status = I2CStopRequested;
+      }
+      else {
+       I2C_GenerateSTART(I2C2, ENABLE);
+       i2c2.status = I2CRestartRequested;
+      }
+    }
+  }
+  else
+    SPURIOUS_INTERRUPT(I2CAddrWrSent, event); 
+}
+
+/*
+ * Sending Byte 
+ *
+ */
+static inline void on_status_sending_byte(struct i2c_transaction* trans, 
uint32_t event) {
+  if (event & I2C_FLAG_TXE) {
+    if (i2c2.idx_buf < trans->len_w) {                         
+      I2C_SendData(I2C2, trans->buf[i2c2.idx_buf]);
+      i2c2.idx_buf++;
+    }
+    else { 
+      I2C_ITConfig(I2C2, I2C_IT_BUF, DISABLE);
+      if (trans->type == I2CTransTx) {
+       I2C_GenerateSTOP(I2C2, ENABLE); 
+       i2c2.status = I2CStopRequested;
+      }
+      else {
+       I2C_GenerateSTART(I2C2, ENABLE);
+       i2c2.status = I2CRestartRequested;
+      }
+    }
+  }
+  else
+    SPURIOUS_INTERRUPT(I2CSendingByte, event); 
+}
+
+#if 0
+/*
+ * Sending last byte 
+ *
+ */
+static inline void on_status_sending_last_byte(struct i2c_transaction* trans, 
uint32_t event) {
+  if (event & I2C_FLAG_TXE) {     // should really be BTF as we're supposed to 
have disabled buf it already
+    struct i2c_transaction* trans = i2c2.trans[i2c2.trans_extract_idx];
+    if (trans->type == I2CTransTx) {
+      I2C_GenerateSTOP(I2C2, ENABLE);
+      i2c2.status = I2CStopRequested;
+    }
+    else {
+      I2C_GenerateSTART(I2C2, ENABLE);
+      i2c2.status = I2CRestartRequested;
+    }
+    //    I2C_ITConfig(I2C2, I2C_IT_BUF, DISABLE);
+  }
+  else
+    SPURIOUS_INTERRUPT(I2CSendingLastByte, event); 
+}
+#endif
+
+
+/*
+ * Stop Requested 
+ *
+ */
+static inline void on_status_stop_requested(struct i2c_transaction* trans, 
uint32_t event) {
+  /* bummer.... */
+  if (event & I2C_FLAG_RXNE) {     
+    uint8_t read_byte =  I2C_ReceiveData(I2C2);
+    if (i2c2.idx_buf < trans->len_r) {                               
+      trans->buf[i2c2.idx_buf] = read_byte;
+    }
+  }
+  I2C_ITConfig(I2C2, I2C_IT_EVT|I2C_IT_BUF, DISABLE);  // should only need to 
disable evt, buf already disabled
+  trans->status = I2CTransSuccess;
+  I2C2_END_OF_TRANSACTION();
+}
+
+/*
+ * Addr RD sent 
+ *
+ */
+static inline void on_status_addr_rd_sent(struct i2c_transaction* trans, 
uint32_t event) {
+  if ((event & I2C_FLAG_ADDR) && !(event & I2C_FLAG_TRA)) {
+    i2c2.idx_buf = 0;  
+    if(trans->len_r == 1) {                                         // If 
we're going to read only one byte
+      I2C_AcknowledgeConfig(I2C2, DISABLE);                       // make sure 
it's gonna be nacked 
+      I2C_GenerateSTOP(I2C2, ENABLE);                             // and 
followed by a stop
+      i2c2.status = I2CReadingLastByte;                           // and 
remember we did
+    }
+    else {
+      I2C_AcknowledgeConfig(I2C2, ENABLE);                        // if it's 
more than one byte, ack it
+      I2C_ITConfig(I2C2, I2C_IT_BUF, ENABLE);
+      i2c2.status = I2CReadingByte;                               // and 
remember we did
+    }
+  }
+  else
+    SPURIOUS_INTERRUPT(I2CAddrRdSent, event); 
+}
+
+
+/*
+ * Reading byte 
+ *
+ */
+static inline void on_status_reading_byte(struct i2c_transaction* trans, 
uint32_t event) {
+  if (event & I2C_FLAG_RXNE) {          
+    uint8_t read_byte =  I2C_ReceiveData(I2C2);
+    if (i2c2.idx_buf < trans->len_r) {                               
+      trans->buf[i2c2.idx_buf] = read_byte;
+      i2c2.idx_buf++;
+      if (i2c2.idx_buf >= trans->len_r-1) {                    // We're 
reading our last byte
+       I2C_AcknowledgeConfig(I2C2, DISABLE);                  // give them a 
nack once it's done
+       I2C_GenerateSTOP(I2C2, ENABLE);                        // and follow 
with a stop
+       i2c2.status = I2CStopRequested;                        // remember we 
already trigered the stop
+      }
+    } // else { something very wrong has happened }
+  }
+  else
+    SPURIOUS_INTERRUPT(I2CReadingByte, event); 
+}
+
+/*
+ * Reading last byte 
+ *
+ */
+static inline void on_status_reading_last_byte(struct i2c_transaction* trans, 
uint32_t event) {
+  if (event & I2C_FLAG_BTF) {
+    uint8_t read_byte =  I2C_ReceiveData(I2C2);
+    trans->buf[i2c2.idx_buf] = read_byte;
+    I2C_GenerateSTOP(I2C2, ENABLE);
+    i2c2.status = I2CStopRequested;   
+  }
+  else if (event & I2C_FLAG_RXNE) {       // should really be BTF ?   
+    uint8_t read_byte =  I2C_ReceiveData(I2C2);
+    trans->buf[i2c2.idx_buf] = read_byte;
+    i2c2.status = I2CStopRequested;   
+  }
+  else
+    SPURIOUS_INTERRUPT(I2CReadingLastByte, event); 
+}
+
+/*
+ * Restart requested 
+ *
+ */
+static inline void on_status_restart_requested(struct i2c_transaction* trans, 
uint32_t event) {
+  //  DEBUG_S6_ON();
+  if (event & I2C_FLAG_SB) {
+    //    DEBUG_S2_ON();
+    I2C_Send7bitAddress(I2C2, trans->slave_addr, I2C_Direction_Receiver);
+    i2c2.status = I2CAddrRdSent;
+    //    DEBUG_S2_OFF();
+  }
+  
+  if (event & I2C_FLAG_BTF) {
+    //    DEBUG_S5_ON();
+    //    DEBUG_S5_OFF();
+  }
+
+  if (event & I2C_FLAG_TXE) {
+    //    DEBUG_S3_ON();
+    //    DEBUG_S3_OFF();
+  }
+
+  //  if (event & I2C_FLAG_TXE) {
+  //    DEBUG_S2_ON();
+  //    DEBUG_S2_OFF();
+  //  }
+
+
+  //  else if (event & I2C_FLAG_TXE) {
+    //    i2c2.status = I2CReadingByte;
+  //  }
+  //  else
+  //    SPURIOUS_INTERRUPT(I2CRestartRequested, event); 
+  //  DEBUG_S6_OFF();
+}
+
+void i2c2_ev_irq_handler(void) {
+  //  DEBUG_S4_ON();
+  uint32_t event = I2C_GetLastEvent(I2C2);
+  struct i2c_transaction* trans = i2c2.trans[i2c2.trans_extract_idx];
+  //#if 0
+  //  if (i2c2_errors.irq_cnt < 16) {
+  //  i2c2_errors.event_chain[i2c2_errors.irq_cnt] = event;
+  //  i2c2_errors.status_chain[i2c2_errors.irq_cnt] = i2c2.status;
+  //  i2c2_errors.irq_cnt++;
+  //  } else { while (1);}
+  //#endif
+  switch (i2c2.status) {
+  case I2CStartRequested:
+    on_status_start_requested(trans, event);
+    break;
+  case I2CAddrWrSent:
+    on_status_addr_wr_sent(trans, event);
+    break;
+  case I2CSendingByte:
+    //    DEBUG_S4_ON();
+    on_status_sending_byte(trans, event);
+    //    DEBUG_S4_OFF();
+    break;
+#if 0
+  case I2CSendingLastByte:
+    //    DEBUG_S5_ON();
+    on_status_sending_last_byte(trans, event);
+    //    DEBUG_S5_OFF();
+    break;
+#endif
+  case I2CStopRequested:
+    //    DEBUG_S1_ON();
+    on_status_stop_requested(trans, event);
+    //    DEBUG_S1_OFF();
+    break;
+  case I2CAddrRdSent:
+    on_status_addr_rd_sent(trans, event);
+    break;
+  case I2CReadingByte:
+    //    DEBUG_S2_ON();
+    on_status_reading_byte(trans, event);
+    //    DEBUG_S2_OFF();
+    break;
+  case I2CReadingLastByte:
+    //    DEBUG_S5_ON();
+    on_status_reading_last_byte(trans, event);
+    //    DEBUG_S5_OFF();
+    break;
+  case I2CRestartRequested:
+    //    DEBUG_S5_ON();
+    on_status_restart_requested(trans, event);
+    //    DEBUG_S5_OFF();
+    break;
+  default:
+    OUT_OF_SYNC_STATE_MACHINE(i2c2.status, event);
+    break;
+  }
+  //  DEBUG_S4_OFF();
+}
+
+
+void i2c2_er_irq_handler(void) {
+  //  DEBUG_S5_ON();
+  i2c2_errors.er_irq_cnt;
+  if (I2C_GetITStatus(I2C2, I2C_IT_AF)) {       /* Acknowledge failure */
+    i2c2_errors.ack_fail_cnt++;
+    I2C_ClearITPendingBit(I2C2, I2C_IT_AF);
+    I2C_GenerateSTOP(I2C2, ENABLE);
+  }
+  if (I2C_GetITStatus(I2C2, I2C_IT_BERR)) {     /* Misplaced Start or Stop 
condition */
+    i2c2_errors.miss_start_stop_cnt++;
+    I2C_ClearITPendingBit(I2C2, I2C_IT_BERR);
+  }
+  if (I2C_GetITStatus(I2C2, I2C_IT_ARLO)) {     /* Arbitration lost */
+    i2c2_errors.arb_lost_cnt++;
+    I2C_ClearITPendingBit(I2C2, I2C_IT_ARLO);
+    //    I2C_AcknowledgeConfig(I2C2, DISABLE);
+    //    uint8_t dummy __attribute__ ((unused)) = I2C_ReceiveData(I2C2);
+    //    I2C_GenerateSTOP(I2C2, ENABLE);
+  }
+  if (I2C_GetITStatus(I2C2, I2C_IT_OVR)) {      /* Overrun/Underrun */
+    i2c2_errors.over_under_cnt++;
+    I2C_ClearITPendingBit(I2C2, I2C_IT_OVR);
+  }
+  if (I2C_GetITStatus(I2C2, I2C_IT_PECERR)) {   /* PEC Error in reception */
+    i2c2_errors.pec_recep_cnt++;
+    I2C_ClearITPendingBit(I2C2, I2C_IT_PECERR);
+  }
+  if (I2C_GetITStatus(I2C2, I2C_IT_TIMEOUT)) {  /* Timeout or Tlow error */
+    i2c2_errors.timeout_tlow_cnt++;
+    I2C_ClearITPendingBit(I2C2, I2C_IT_TIMEOUT);
+  }
+  if (I2C_GetITStatus(I2C2, I2C_IT_SMBALERT)) { /* SMBus alert */
+    i2c2_errors.smbus_alert_cnt++;
+    I2C_ClearITPendingBit(I2C2, I2C_IT_SMBALERT);
+  }
+  
+  I2C2_ABORT_AND_RESET();
+  
+  //  DEBUG_S5_OFF();
+
+}
+
+#endif /* USE_I2C2 */
+
+
+
+bool_t i2c_submit(struct i2c_periph* p, struct i2c_transaction* t) {
+
+  uint8_t temp;
+  temp = p->trans_insert_idx + 1;
+  if (temp >= I2C_TRANSACTION_QUEUE_LEN) temp = 0;
+  if (temp == p->trans_extract_idx)
+    return FALSE;                          // queue full
+
+  t->status = I2CTransPending;
+  
+
+  __disable_irq();
+  /* put transacation in queue */
+  p->trans[p->trans_insert_idx] = t;
+  p->trans_insert_idx = temp;
+  
+  /* if peripheral is idle, start the transaction */
+  if (p->status == I2CIdle)
+    start_transaction(p);
+  /* else it will be started by the interrupt handler when the previous 
transactions completes */
+  __enable_irq();
+
+  return TRUE;
+}
+
+
+static void start_transaction(struct i2c_periph* p) {
+  p->idx_buf = 0;
+  p->status = I2CStartRequested;
+  //  I2C_ZERO_EVENTS();
+  I2C_ITConfig(p->reg_addr, I2C_IT_EVT, ENABLE);
+  I2C_GenerateSTART(p->reg_addr, ENABLE);
+}

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/i2c_hw.h (from rev 5935, 
paparazzi3/trunk/sw/airborne/stm32/i2c_hw.h)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/i2c_hw.h                            
(rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/i2c_hw.h    2010-09-23 22:28:37 UTC 
(rev 5936)
@@ -0,0 +1,59 @@
+/*
+ * $Id$
+ *  
+ * Copyright (C) 2009 Antoine Drouin <address@hidden>
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA. 
+ */
+
+/*
+ * Hardware level I2C handling
+ */
+
+#ifndef I2C_HW_H
+#define I2C_HW_H
+
+#include "i2c.h"
+#include <stm32/i2c.h>
+
+
+#ifdef USE_I2C1
+
+extern struct i2c_errors i2c1_errors;
+
+extern void i2c1_hw_init(void);
+extern void i2c1_ev_irq_handler(void);
+extern void i2c1_er_irq_handler(void);
+
+#endif /* USE_I2C1 */
+
+
+
+#ifdef USE_I2C2
+
+extern struct i2c_errors i2c2_errors;
+
+extern void i2c2_hw_init(void);
+extern void i2c2_ev_irq_handler(void);
+extern void i2c2_er_irq_handler(void);
+
+
+#endif /* USE_I2C2 */
+
+
+#endif /* I2C_HW_H */

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/init_hw.h (from rev 5935, 
paparazzi3/trunk/sw/airborne/stm32/init_hw.h)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/init_hw.h                           
(rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/init_hw.h   2010-09-23 22:28:37 UTC 
(rev 5936)
@@ -0,0 +1,151 @@
+/*
+ * Paparazzi $Id$
+ *
+ * Copyright (C) 2009-2010 The Paparazzi Team
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ */
+
+/*
+ *\brief STM low level hardware initialisation 
+ * PLL, MAM, VIC
+ *
+ */
+
+#ifndef INIT_HW_H
+#define INIT_HW_H
+
+#include <inttypes.h>
+#include <stm32/gpio.h>
+#include <stm32/rcc.h>
+#include <stm32/flash.h>
+#include <stm32/misc.h>
+
+#include BOARD_CONFIG
+
+/* should probably not be here
+ *   a couple of macros to use the rev instruction
+ */
+#define MyByteSwap16(in, out) {                        \
+    asm volatile (                             \
+                 "rev16        %0, %1\n\t"     \
+                 : "=r" (out)                  \
+                 : "r"(in)                     \
+                 );                            \
+  }
+
+
+#ifdef PERIPHERALS_AUTO_INIT
+#ifdef USE_LED
+#include "led.h"
+#endif
+#if defined USE_RADIO_CONTROL 
+#if defined RADIO_CONTROL_LINK  || defined RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT
+#include "booz/booz_radio_control.h"
+#endif
+#endif
+#if defined USE_UART1 || defined USE_UART2 || defined USE_UART3
+#include "uart.h"
+#endif
+#if defined USE_I2C1 || defined USE_I2C2
+#include "i2c.h"
+#endif
+#endif /* PERIPHERALS_AUTO_INIT */
+
+
+/* declare functions and values from crt0.S & the linker control file */
+extern void reset(void);
+/* extern void exit(void); */
+extern void abort(void);
+
+
+static inline void hw_init(void) {
+
+#ifdef HSE_TYPE_EXT_CLK
+  /* Setup the microcontroller system. 
+   *  Initialize the Embedded Flash Interface,  
+   *  initialize the PLL and update the SystemFrequency variable. 
+   */
+  /* RCC system reset(for debug purpose) */
+  RCC_DeInit();
+  /* Enable HSE with external clock ( HSE_Bypass ) */
+  RCC_HSEConfig( RCC_HSE_Bypass );
+  /* Wait till HSE is ready */
+  ErrorStatus HSEStartUpStatus = RCC_WaitForHSEStartUp();
+  if (HSEStartUpStatus != SUCCESS) {
+    /* block if something went wrong */
+    while(1) {}
+  }
+  else {
+    /* Enable Prefetch Buffer */
+    FLASH_PrefetchBufferCmd(FLASH_PrefetchBuffer_Enable);
+    /* Flash 2 wait state */
+    FLASH_SetLatency(FLASH_Latency_2);
+    /* HCLK = SYSCLK */
+    RCC_HCLKConfig(RCC_SYSCLK_Div1); 
+    /* PCLK2 = HCLK */
+    RCC_PCLK2Config(RCC_HCLK_Div1); 
+    /* PCLK1 = HCLK/2 */
+    RCC_PCLK1Config(RCC_HCLK_Div2);
+    /* PLLCLK = 8MHz * 9 = 72 MHz */
+    RCC_PLLConfig(RCC_PLLSource_HSE_Div1, RCC_PLLMul_9);
+    /* Enable PLL */ 
+    RCC_PLLCmd(ENABLE);
+    /* Wait till PLL is ready */
+    while (RCC_GetFlagStatus(RCC_FLAG_PLLRDY) == RESET) {}
+    /* Select PLL as system clock source */
+    RCC_SYSCLKConfig(RCC_SYSCLKSource_PLLCLK);
+    /* Wait till PLL is used as system clock source */
+    while(RCC_GetSYSCLKSource() != 0x08) {}
+  }
+#else  /* HSE_TYPE_EXT_CLK */
+  SystemInit();
+#endif /* HSE_TYPE_EXT_CLK */
+   /* Set the Vector Table base location at 0x08000000 */
+  NVIC_SetVectorTable(NVIC_VectTab_FLASH, 0x0);
+
+
+#ifdef PERIPHERALS_AUTO_INIT
+#ifdef USE_LED
+  led_init();
+#endif
+  /* for now this means using spektrum */
+#if defined USE_RADIO_CONTROL & defined RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT & 
defined RADIO_CONTROL_BIND_IMPL_FUNC
+  RADIO_CONTROL_BIND_IMPL_FUNC();
+#endif
+#ifdef USE_UART1
+  uart1_init();
+#endif
+#ifdef USE_UART2
+  uart2_init();
+#endif
+#ifdef USE_UART3
+  uart3_init();
+#endif
+#ifdef USE_I2C1
+  i2c1_init();
+#endif
+#ifdef USE_I2C2
+  i2c2_init();
+#endif
+#endif /* PERIPHERALS_AUTO_INIT */
+
+
+}
+
+#endif /* INIT_HW_H */

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/interrupt_hw.h (from rev 5935, 
paparazzi3/trunk/sw/airborne/stm32/interrupt_hw.h)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/interrupt_hw.h                      
        (rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/interrupt_hw.h      2010-09-23 
22:28:37 UTC (rev 5936)
@@ -0,0 +1,36 @@
+/*
+ * $Id: interrupt_hw.h 859 2006-05-03 21:32:23Z poine $
+ *  
+ * Copyright (C) 2005  Pascal Brisset, Antoine Drouin
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA. 
+ *
+ */
+/** \file interrupt_hw.h
+ *  \brief STM32 Low level interrupt handling
+ *  Empty for now, just to match what we have on LPC
+ */
+
+#ifndef INTERRUPT_HW_H
+#define INTERRUPT_HW_H
+
+#define int_enable()  {}
+#define int_disable() {}
+
+#endif /* INTERRUPT_HW_H */
+

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/led_hw.c (from rev 5935, 
paparazzi3/trunk/sw/airborne/stm32/led_hw.c)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/led_hw.c                            
(rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/led_hw.c    2010-09-23 22:28:37 UTC 
(rev 5936)
@@ -0,0 +1,6 @@
+#include "led.h"
+
+#ifdef LED_STP08
+uint8_t led_status[NB_LED];
+#endif
+

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/led_hw.h (from rev 5935, 
paparazzi3/trunk/sw/airborne/stm32/led_hw.h)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/led_hw.h                            
(rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/led_hw.h    2010-09-23 22:28:37 UTC 
(rev 5936)
@@ -0,0 +1,110 @@
+/*
+ * Paparazzi $Id$
+ *
+ * Copyright (C) 2009 Antoine Drouin <address@hidden>
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ */
+
+#ifndef LED_HW_H
+#define LED_HW_H
+
+#include <stm32/gpio.h>
+#include <stm32/rcc.h>
+
+#include BOARD_CONFIG
+
+#include "std.h"
+
+
+/*
+ *
+ *  Regular GPIO driven LEDs
+ *
+ */
+#ifndef LED_STP08
+
+#define _LED_GPIO_CLK(i)  i
+#define _LED_GPIO(i)  i
+#define _LED_GPIO_PIN(i) i
+
+#define LED_GPIO_CLK(i) _LED_GPIO_CLK(LED_ ## i ## _GPIO_CLK)
+#define LED_GPIO(i) _LED_GPIO(LED_ ## i ## _GPIO)
+#define LED_GPIO_PIN(i) _LED_GPIO_PIN(LED_ ## i ## _GPIO_PIN)
+
+/* set pin as output */
+#define LED_INIT(i) {                                  \
+    GPIO_InitTypeDef GPIO_InitStructure;               \
+    RCC_APB2PeriphClockCmd(LED_GPIO_CLK(i), ENABLE);   \
+    GPIO_InitStructure.GPIO_Pin = LED_GPIO_PIN(i);     \
+    GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;   \
+    GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;  \
+    GPIO_Init(LED_GPIO(i), &GPIO_InitStructure);       \
+  }
+
+#define LED_ON(i) { LED_GPIO(i)->BRR  = LED_GPIO_PIN(i);}
+#define LED_OFF(i) {LED_GPIO(i)->BSRR = LED_GPIO_PIN(i);}
+#define LED_TOGGLE(i) {        LED_GPIO(i)->ODR ^= LED_GPIO_PIN(i);}
+
+#define LED_PERIODIC() {}
+
+
+/*
+ *
+ * Shift register driven LEDs
+ *
+ */
+#else  /* LED_STP08 */
+#define NB_LED 8
+extern uint8_t led_status[NB_LED];
+/* Lisa/L uses a shift register for driving LEDs */
+/* PA8  led_clk  */
+/* PC15 led_data */
+
+#define LED_INIT(_i) {                                         \
+    RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);      \
+    RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE);      \
+    GPIO_InitTypeDef GPIO_InitStructure;                       \
+    GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8;                  \
+    GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;           \
+    GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;           \
+    GPIO_Init(GPIOA, &GPIO_InitStructure);                     \
+    GPIO_InitStructure.GPIO_Pin = GPIO_Pin_15;                 \
+    GPIO_Init(GPIOC, &GPIO_InitStructure);                     \
+    for(uint8_t i=0; i<NB_LED; i++)                            \
+      led_status[i] = FALSE;                                   \
+  }
+
+#define LED_ON(i)  { led_status[i] = TRUE;  }
+#define LED_OFF(i) { led_status[i] = FALSE; }
+#define LED_TOGGLE(i) {led_status[i] = !led_status[i];}
+
+#define LED_PERIODIC() {                                       \
+    for (uint8_t cnt = 0; cnt < NB_LED; cnt++) {               \
+      if (led_status[cnt])                                     \
+       GPIOC->BSRR = GPIO_Pin_15;                              \
+      else                                                     \
+       GPIOC->BRR = GPIO_Pin_15;                               \
+      GPIOA->BSRR = GPIO_Pin_8; /* clock rising edge */                \
+      GPIOA->BRR = GPIO_Pin_8;  /* clock falling edge */       \
+    }                                                          \
+  }
+
+#endif /* LED_STP08 */
+
+#endif /* LED_HW_H */

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/link_mcu_hw.h (from rev 5935, 
paparazzi3/trunk/sw/airborne/stm32/link_mcu_hw.h)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/link_mcu_hw.h                       
        (rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/link_mcu_hw.h       2010-09-23 
22:28:37 UTC (rev 5936)
@@ -0,0 +1,42 @@
+/*  $Id: link_mcu_hw.h 2064 2007-11-23 12:35:50Z hecto $
+ *
+ * Copyright (C) 2003-2005  Pascal Brisset, Antoine Drouin
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.  
+ *
+ */
+
+/** \brief handling of arm7 inter mcu link
+ *  
+ */
+
+#ifndef LINK_MCU_HW_H
+#define LINK_MCU_HW_H
+
+#define CRC_INIT 0x0    
+#define CrcLow(x) ((x)&0xff)    
+#define CrcHigh(x) ((x)>>8)     
+
+static inline uint16_t CrcUpdate(uint16_t crc, uint8_t data) {          
+  uint8_t a = ((uint8_t)CrcHigh(crc)) + data;   
+  uint8_t b = ((uint8_t)CrcLow(crc)) + a;       
+  crc = b | a << 8;     
+  return crc;   
+}
+
+#endif /* LINK_MCU_HW_H */

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/my_debug_servo.h (from rev 
5935, paparazzi3/trunk/sw/airborne/stm32/my_debug_servo.h)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/my_debug_servo.h                    
        (rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/my_debug_servo.h    2010-09-23 
22:28:37 UTC (rev 5936)
@@ -0,0 +1,71 @@
+#ifndef MY_DEBUG_SERVO_H
+#define MY_DEBUG_SERVO_H
+
+#include <stm32/gpio.h>
+#include <stm32/rcc.h>
+
+/* using servo 2 connector as debug */
+
+#define DEBUG_S1_TOGGLE() {  GPIOC->ODR ^= GPIO_Pin_6; }
+#define DEBUG_S1_ON()     {  GPIOC->BSRR = GPIO_Pin_6; }
+#define DEBUG_S1_OFF()    {  GPIOC->BRR  = GPIO_Pin_6; }
+
+#define DEBUG_S2_TOGGLE() {  GPIOC->ODR ^= GPIO_Pin_7; }
+#define DEBUG_S2_ON()     {  GPIOC->BSRR = GPIO_Pin_7; }
+#define DEBUG_S2_OFF()    {  GPIOC->BRR  = GPIO_Pin_7; }
+
+#define DEBUG_S3_TOGGLE() {  GPIOC->ODR ^= GPIO_Pin_8; }
+#define DEBUG_S3_ON()     {  GPIOC->BSRR = GPIO_Pin_8; }
+#define DEBUG_S3_OFF()    {  GPIOC->BRR  = GPIO_Pin_8; }
+
+#define DEBUG_S4_TOGGLE() {  GPIOC->ODR ^= GPIO_Pin_9; }
+#define DEBUG_S4_ON()     {  GPIOC->BSRR = GPIO_Pin_9; }
+#define DEBUG_S4_OFF()    {  GPIOC->BRR  = GPIO_Pin_9; }
+
+#define DEBUG_S5_TOGGLE() {  GPIOB->ODR ^= GPIO_Pin_8; }
+#define DEBUG_S5_ON()     {  GPIOB->BSRR = GPIO_Pin_8; }
+#define DEBUG_S5_OFF()    {  GPIOB->BRR  = GPIO_Pin_8; }
+
+#define DEBUG_S6_TOGGLE() {  GPIOB->ODR ^= GPIO_Pin_9; }
+#define DEBUG_S6_ON()     {  GPIOB->BSRR = GPIO_Pin_9; }
+#define DEBUG_S6_OFF()    {  GPIOB->BRR  = GPIO_Pin_9; }
+
+
+
+#define DEBUG_SERVO1_INIT() {                                          \
+    /* S1: PC6    S2: PC7    S3: PC8 */                                        
\
+    GPIO_InitTypeDef GPIO_InitStructure;                               \
+    GPIOC->BSRR = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8 ;               \
+    RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE);              \
+    GPIO_InitStructure.GPIO_Pin = GPIO_Pin_6 | GPIO_Pin_7 | GPIO_Pin_8;        
\
+    GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;                   \
+    GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;                  \
+    GPIO_Init(GPIOC, &GPIO_InitStructure);                             \
+    DEBUG_S1_OFF();                                                    \
+    DEBUG_S2_OFF();                                                    \
+    DEBUG_S3_OFF();                                                    \
+ }
+
+#define DEBUG_SERVO2_INIT() {                                  \
+    /* S4: PC9 */                                              \
+    GPIO_InitTypeDef GPIO_InitStructure;                       \
+    GPIOC->BSRR = GPIO_Pin_9;                                  \
+    RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE);      \
+    GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;                  \
+    GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;           \
+    GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;          \
+    GPIO_Init(GPIOC, &GPIO_InitStructure);                     \
+    /* S5: PB8 and S6: PB9 */                                  \
+    GPIOB->BSRR = GPIO_Pin_8 | GPIO_Pin_9;                     \
+    RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE);      \
+    GPIO_InitStructure.GPIO_Pin = GPIO_Pin_8 | GPIO_Pin_9;     \
+    GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;           \
+    GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;          \
+    GPIO_Init(GPIOB, &GPIO_InitStructure);                     \
+    DEBUG_S4_OFF();                                            \
+    DEBUG_S5_OFF();                                            \
+    DEBUG_S6_OFF();                                            \
+  }
+
+
+#endif /* MY_DEBUG_SERVO_H */

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/ppm_hw.c (from rev 5935, 
paparazzi3/trunk/sw/airborne/stm32/ppm_hw.c)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/ppm_hw.c                            
(rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/ppm_hw.c    2010-09-23 22:28:37 UTC 
(rev 5936)
@@ -0,0 +1,31 @@
+
+#include "ppm.h"
+#include "std.h"
+#include "sys_time.h"
+
+
+#include "radio_control/booz_radio_control_ppm.h"
+#include BOARD_CONFIG
+
+
+uint16_t ppm_pulses[PPM_NB_CHANNEL];
+volatile bool_t ppm_valid;
+
+////////////////////////////////////////////////
+// RADIO_CONTROL_NB_CHANNEL  == PPM_NB_CHANNEL ?
+
+void ppm_init ( void ) 
+{
+  booz_radio_control_ppm_arch_init();
+  ppm_valid = FALSE;
+}
+
+void ppm_copy( void )
+{
+  ppm_valid = booz_radio_control_ppm_frame_available;
+
+  for (int i=0;i<PPM_NB_CHANNEL;i++)
+  {
+    ppm_pulses[i] = booz_radio_control_ppm_pulses[i]; 
+  }
+}

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/ppm_hw.h (from rev 5935, 
paparazzi3/trunk/sw/airborne/stm32/ppm_hw.h)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/ppm_hw.h                            
(rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/ppm_hw.h    2010-09-23 22:28:37 UTC 
(rev 5936)
@@ -0,0 +1,10 @@
+#ifndef PPM_HW_H
+#define PPM_HW_H
+
+
+extern void ppm_init ( void ); 
+
+#define PPM_NB_CHANNEL PPM_NB_PULSES
+
+
+#endif /* PPM_HW_H */

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/servos_direct_hw.c (from rev 
5935, paparazzi3/trunk/sw/airborne/stm32/servos_direct_hw.c)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/servos_direct_hw.c                  
        (rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/servos_direct_hw.c  2010-09-23 
22:28:37 UTC (rev 5936)
@@ -0,0 +1,12 @@
+#include "std.h"
+#include "actuators.h"
+#include "servos_direct_hw.h"
+
+int32_t booz_actuators_pwm_values[BOOZ_ACTUATORS_PWM_NB];
+
+void actuators_init ( void ) {
+  booz_actuators_pwm_arch_init();
+}
+
+
+

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/servos_direct_hw.h (from rev 
5935, paparazzi3/trunk/sw/airborne/stm32/servos_direct_hw.h)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/servos_direct_hw.h                  
        (rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/servos_direct_hw.h  2010-09-23 
22:28:37 UTC (rev 5936)
@@ -0,0 +1,18 @@
+#ifndef SERVOS_DIRECT_HW_H
+#define SERVOS_DIRECT_HW_H
+
+
+#include "std.h"
+
+#define BOOZ_ACTUATORS_PWM_NB 6
+extern int32_t booz_actuators_pwm_values[BOOZ_ACTUATORS_PWM_NB];
+
+#include "actuators/booz_actuators_pwm_arch.h"
+
+#define SERVOS_TICS_OF_USEC(_v) (_v)
+#define Actuator(_x)  booz_actuators_pwm_values[_x]
+#define ChopServo(x,a,b) Chop(x, a, b)
+#define ActuatorsCommit  booz_actuators_pwm_commit
+
+
+#endif /* SERVOS_DIRECT_HW_H */

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/stm32_exceptions.c (from rev 
5935, paparazzi3/trunk/sw/airborne/stm32/stm32_exceptions.c)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/stm32_exceptions.c                  
        (rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/stm32_exceptions.c  2010-09-23 
22:28:37 UTC (rev 5936)
@@ -0,0 +1,43 @@
+/*
+ * $Id$
+ *  
+ * Copyright (C) 2010 Antoine Drouin <address@hidden>
+ *
+ * This file is part of Paparazzi.
+ *
+ * Paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * Paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA. 
+ */
+
+#include "stm32_exceptions.h"
+
+void nmi_exception(void){
+}
+
+void hard_fault_exception(void){
+    while(1);
+}
+
+void mem_manage_exception(void){
+    while(1);
+}
+
+void bus_fault_exception(void){
+    while(1);
+}
+
+void usage_fault_exception(void){
+    while(1);
+}

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/stm32_exceptions.h (from rev 
5935, paparazzi3/trunk/sw/airborne/stm32/stm32_exceptions.h)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/stm32_exceptions.h                  
        (rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/stm32_exceptions.h  2010-09-23 
22:28:37 UTC (rev 5936)
@@ -0,0 +1,34 @@
+/*
+ * $Id$
+ *  
+ * Copyright (C) 2010 Antoine Drouin <address@hidden>
+ *
+ * This file is part of Paparazzi.
+ *
+ * Paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * Paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA. 
+ */
+
+
+#ifndef STM32_EXCEPTIONS_H
+#define STM32_EXCEPTIONS_H
+
+void nmi_exception(void);
+void hard_fault_exception(void);
+void mem_manage_exception(void);
+void bus_fault_exception(void);
+void usage_fault_exception(void);
+
+#endif /* STM32_EXCEPTIONS_H */

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/stm32_vector_table.c (from rev 
5935, paparazzi3/trunk/sw/airborne/stm32/stm32_vector_table.c)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/stm32_vector_table.c                
                (rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/stm32_vector_table.c        
2010-09-23 22:28:37 UTC (rev 5936)
@@ -0,0 +1,321 @@
+/*
+ * $Id$
+ *  
+ * Copyright (C) 2010 Antoine Drouin <address@hidden>
+ *
+ * This file is part of Paparazzi.
+ *
+ * Paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * Paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA. 
+ */
+
+#include "stm32_vector_table.h"
+
+#include <cmsis/stm32.h>
+
+#include "stm32_exceptions.h"
+
+#ifdef USE_SYS_TIME
+#include "sys_time.h"
+#define SYS_TICK_IRQ_HANDLER sys_tick_irq_handler
+#else
+#define SYS_TICK_IRQ_HANDLER null_handler
+#endif
+
+#if defined USE_UART1 || OVERRIDE_UART1_IRQ_HANDLER
+#include "uart.h"
+#define USART1_IRQ_HANDLER usart1_irq_handler
+#else
+#define USART1_IRQ_HANDLER null_handler
+#endif
+
+#if defined USE_UART2 || OVERRIDE_UART2_IRQ_HANDLER
+#include "uart.h"
+#define USART2_IRQ_HANDLER usart2_irq_handler
+#else
+#define USART2_IRQ_HANDLER null_handler
+#endif
+
+#if defined USE_UART3 || OVERRIDE_UART3_IRQ_HANDLER
+#include "uart.h"
+#define USART3_IRQ_HANDLER usart3_irq_handler
+#else
+#define USART3_IRQ_HANDLER null_handler
+#endif
+
+#if defined USE_UART5 || OVERRIDE_UART5_IRQ_HANDLER
+#include "uart.h"
+#define USART5_IRQ_HANDLER usart5_irq_handler
+#else
+#define USART5_IRQ_HANDLER null_handler
+#endif
+
+
+#ifdef USE_I2C1
+#include "i2c_hw.h"
+#define I2C1_EV_IRQ_HANDLER i2c1_ev_irq_handler
+#define I2C1_ER_IRQ_HANDLER i2c1_er_irq_handler
+#else
+#define I2C1_EV_IRQ_HANDLER null_handler
+#define I2C1_ER_IRQ_HANDLER null_handler
+#endif
+
+#ifdef USE_I2C2
+#include "i2c_hw.h"
+#define I2C2_EV_IRQ_HANDLER i2c2_ev_irq_handler
+#define I2C2_ER_IRQ_HANDLER i2c2_er_irq_handler
+#else
+#define I2C2_EV_IRQ_HANDLER null_handler
+#define I2C2_ER_IRQ_HANDLER null_handler
+#endif
+
+#ifdef USE_SPI1_IRQ
+extern void spi1_irq_handler(void);
+#define SPI1_IRQ_HANDLER spi1_irq_handler
+#else
+#define SPI1_IRQ_HANDLER null_handler
+#endif
+
+#ifdef USE_SPI2_IRQ
+extern void spi2_irq_handler(void);
+#define SPI2_IRQ_HANDLER spi2_irq_handler
+#else
+#define SPI2_IRQ_HANDLER null_handler
+#endif
+
+#ifdef USE_EXTI0_IRQ
+extern void exti0_irq_handler(void);
+#define EXTI0_IRQ_HANDLER exti0_irq_handler
+#else
+#define EXTI0_IRQ_HANDLER null_handler
+#endif
+
+#ifdef USE_EXTI2_IRQ
+extern void exti2_irq_handler(void);
+#define EXTI2_IRQ_HANDLER exti2_irq_handler
+#else
+#define EXTI2_IRQ_HANDLER null_handler
+#endif
+
+#ifdef USE_EXTI3_IRQ
+extern void exti3_irq_handler(void);
+#define EXTI3_IRQ_HANDLER exti3_irq_handler
+#else
+#define EXTI3_IRQ_HANDLER null_handler
+#endif
+
+#ifdef USE_EXTI4_IRQ
+extern void exti4_irq_handler(void);
+#define EXTI4_IRQ_HANDLER exti4_irq_handler
+#else
+#define EXTI4_IRQ_HANDLER null_handler
+#endif
+
+#ifdef USE_EXTI9_5_IRQ
+extern void exti9_5_irq_handler(void);
+#define EXTI9_5_IRQ_HANDLER exti9_5_irq_handler
+#else
+#define EXTI9_5_IRQ_HANDLER null_handler
+#endif
+
+#ifdef USE_EXTI15_10_IRQ
+extern void exti15_10_irq_handler(void);
+#define EXTI15_10_IRQ_HANDLER exti15_10_irq_handler
+#else
+#define EXTI15_10_IRQ_HANDLER null_handler
+#endif
+
+
+#ifdef USE_DMA1_C2_IRQ
+extern void dma1_c2_irq_handler(void);
+#define DMA1_C2_IRQ_HANDLER dma1_c2_irq_handler
+#else
+#define DMA1_C2_IRQ_HANDLER null_handler
+#endif
+
+#ifdef USE_DMA1_C4_IRQ
+extern void dma1_c4_irq_handler(void);
+#define DMA1_C4_IRQ_HANDLER dma1_c4_irq_handler
+#else
+#define DMA1_C4_IRQ_HANDLER null_handler
+#endif
+
+#ifdef USE_ADC1_2_IRQ_HANDLER
+extern void adc1_2_irq_handler(void);
+#define ADC1_2_IRQ_HANDLER adc1_2_irq_handler
+#else
+#define ADC1_2_IRQ_HANDLER null_handler
+#endif
+
+#ifdef USE_TIM2_IRQ
+extern void tim2_irq_handler(void);
+#define TIM2_IRQ_HANDLER tim2_irq_handler
+#else
+#define TIM2_IRQ_HANDLER null_handler
+#endif
+
+#ifdef USE_TIM6_IRQ
+extern void tim6_irq_handler(void);
+#define TIM6_IRQ_HANDLER tim6_irq_handler
+#else
+#define TIM6_IRQ_HANDLER null_handler
+#endif
+
+#ifdef USE_USB_HP_CAN1_TX_IRQ
+extern void usb_hp_can1_tx_irq_handler(void);
+#define USB_HP_CAN1_TX_IRQ_HANDLER usb_hp_can1_tx_irq_handler
+#else
+#define USB_HP_CAN1_TX_IRQ_HANDLER null_handler
+#endif
+
+#ifdef USE_USB_LP_CAN1_RX0_IRQ
+extern void usb_lp_can1_rx0_irq_handler(void);
+#define USB_LP_CAN1_RX0_IRQ_HANDLER usb_lp_can1_rx0_irq_handler
+#else
+#define USB_LP_CAN1_RX0_IRQ_HANDLER null_handler
+#endif
+
+/* addresses defined in the linker script */
+extern unsigned long _etext;  /* end addr of .text section     */
+extern unsigned long _sidata; /* init values for .data section */
+extern unsigned long _sdata;  /* start addr of .data section   */
+extern unsigned long _edata;  /* end addr of .data section     */
+extern unsigned long _sbss;   /* start addr of .bss section    */
+extern unsigned long _ebss;   /* end addr of .bss section      */
+extern void _estack;          /* stack pointer init value      */
+
+void reset_handler_stage1(void) __attribute__((__interrupt__));
+void reset_handler_stage2(void);
+void null_handler(void);
+
+/* interrupt vector */
+__attribute__ ((section(".isr_vector")))
+void (* const vector_table[])(void) = {
+    &_estack,              /* stack pointer init value*/
+    reset_handler_stage1,  /* pc init value */
+    nmi_exception,
+    hard_fault_exception,
+    mem_manage_exception,
+    bus_fault_exception,
+    usage_fault_exception,
+    0, 0, 0, 0,               /* reserved */
+    null_handler,             /* svc_handler */
+    null_handler,             /* debug_monitor */
+    0,                        /* reserved */
+    null_handler,             /* pend_svc */
+    SYS_TICK_IRQ_HANDLER,     /* sys_tick_handler, */
+    null_handler,             /* wwdg_irq_handler */
+    null_handler,             /* pvd_irq_handler */
+    null_handler,             /* tamper_irq_handler */
+    null_handler,             /* rtc_irq_handler */
+    null_handler,             /* flash_irq_handler */
+    null_handler,             /* rcc_irq_handler */
+    EXTI0_IRQ_HANDLER,        /* exti0_irq_handler */
+    null_handler,             /* exti1_irq_handler */
+    EXTI2_IRQ_HANDLER,        /* exti2_irq_handler */
+    EXTI3_IRQ_HANDLER,        /* exti3_irq_handler */
+    EXTI4_IRQ_HANDLER,        /* exti4_irq_handler */
+    null_handler,             /* dma1_channel1_irq_handler */
+    DMA1_C2_IRQ_HANDLER,      /* dma1_channel2_irq_handler */
+    null_handler,             /* dma1_channel3_irq_handler */
+    DMA1_C4_IRQ_HANDLER,      /* dma1_channel4_irq_handler */
+    null_handler,             /* dma1_channel5_irq_handler */
+    null_handler,             /* dma1_channel6_irq_handler */
+    null_handler,             /* dma1_channel7_irq_handler */
+    ADC1_2_IRQ_HANDLER,       /* adc1_2_irq_handler */
+    USB_HP_CAN1_TX_IRQ_HANDLER, /* usb_hp_can_tx_irq_handler */
+    USB_LP_CAN1_RX0_IRQ_HANDLER, /* usb_lp_can_rx0_irq_handler */
+    null_handler,             /* can_rx1_irq_handler */
+    null_handler,             /* can_sce_irq_handler */
+    EXTI9_5_IRQ_HANDLER,      /* exti9_5_irq_handler */
+    null_handler,             /* tim1_brk_irq_handler */
+    null_handler,             /* tim1_up_irq_handler */
+    null_handler,             /* tim1_trg_com_irq_handler */
+    null_handler,             /* tim1_cc_irq_handler */
+    TIM2_IRQ_HANDLER,         /* tim2_irq_handler */
+    null_handler,             /* tim3_irq_handler */
+    null_handler,             /* tim4_irq_handler */
+    I2C1_EV_IRQ_HANDLER,      /* i2c1_ev_irq_handler */
+    I2C1_ER_IRQ_HANDLER,      /* i2c1_er_irq_handler */
+    I2C2_EV_IRQ_HANDLER,      /* i2c2_ev_irq_handler */
+    I2C2_ER_IRQ_HANDLER,      /* i2c2_er_irq_handler */
+    SPI1_IRQ_HANDLER,         /* spi1_irq_handler */
+    SPI2_IRQ_HANDLER,         /* spi2_irq_handler */
+    USART1_IRQ_HANDLER,       /* usart1_irq_handler */
+    USART2_IRQ_HANDLER,       /* usart2_irq_handler */
+    USART3_IRQ_HANDLER,       /* usart3_irq_handler */
+    EXTI15_10_IRQ_HANDLER,    /* exti15_10_irq_handler */
+    null_handler,             /* rtc_alarm_irq_handler */
+    null_handler,             /* usb_wake_up_irq_handler */
+    null_handler,             /* tim8_brk_irq_handler */
+    null_handler,             /* tim8_up_irq_handler */
+    null_handler,             /* tim8_trg_com_irq_handler */
+    null_handler,             /* tim8_cc_irq_handler */
+    null_handler,             /* adc3_irq_handler */
+    null_handler,             /* fsmc_irq_handler */
+    null_handler,             /* sdio_irq_handler */
+    null_handler,             /* tim5_irq_handler */
+    null_handler,             /* spi3_irq_handler */
+    null_handler,             /* uart4_irq_handler */
+    USART5_IRQ_HANDLER,       /* uart5_irq_handler */
+    TIM6_IRQ_HANDLER,         /* tim6_irq_handler */
+    null_handler,             /* tim7_irq_handler */
+    null_handler,             /* dma2_channel1_irq_handler */
+    null_handler,             /* dma2_channel2_irq_handler */
+    null_handler,             /* dma2_channel3_irq_handler */
+    null_handler,             /* dma2_channel4_5_irq_handler */
+};
+
+/* Get's called directly after mcu reset */
+void reset_handler_stage1(void){
+    /* set stack align */
+    SCB->CCR = SCB->CCR | SCB_CCR_STKALIGN;
+
+    reset_handler_stage2();
+}
+
+//extern int main(int argc, char** argv);
+extern void main( void);
+
+void reset_handler_stage2(void){
+    unsigned long *pul_src, *pul_dest;
+
+    /* Copy the data segment initializers from flash to SRAM */
+    pul_src = &_sidata;
+    for(pul_dest = &_sdata; pul_dest < &_edata; ){
+        *(pul_dest++) = *(pul_src++);
+    }
+    /* Zero fill the bss segment.  */
+    for(pul_dest = &_sbss; pul_dest < &_ebss; ){
+        *(pul_dest++) = 0;
+    }
+
+    /* Call the application's entry point.*/
+    main();
+}
+
+void null_handler(void){
+}
+
+/* FIXME: look deeper into what that is doing
+ * 
+ */
+
+void assert_param(void);
+
+void assert_param(void){
+
+}
+

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/stm32_vector_table.h (from rev 
5935, paparazzi3/trunk/sw/airborne/stm32/stm32_vector_table.h)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/stm32_vector_table.h                
                (rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/stm32_vector_table.h        
2010-09-23 22:28:37 UTC (rev 5936)
@@ -0,0 +1,28 @@
+/*
+ * $Id$
+ *  
+ * Copyright (C) 2010 Antoine Drouin <address@hidden>
+ *
+ * This file is part of Paparazzi.
+ *
+ * Paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * Paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA. 
+ */
+
+#ifndef STM32_VECTOR_TABLE_H
+#define STM32_VECTOR_TABLE_H
+
+
+#endif /* STM32_VECTOR_TABLE_H */

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/stm32f103rb_flash.ld (from rev 
5935, paparazzi3/trunk/sw/airborne/stm32/stm32f103rb_flash.ld)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/stm32f103rb_flash.ld                
                (rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/stm32f103rb_flash.ld        
2010-09-23 22:28:37 UTC (rev 5936)
@@ -0,0 +1,198 @@
+/*
+ * $Id$
+ *  
+ * Copyright (C) 2010 Antoine Drouin <address@hidden>
+ *
+ * This file is part of Paparazzi.
+ *
+ * Paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * Paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA. 
+ */
+
+/* Memory Spaces Definitions */
+MEMORY
+{                        
+  RAM     (xrw): ORIGIN = 0x20000000, LENGTH = 20K
+  FLASH   (rx) : ORIGIN = 0x8000000,  LENGTH = 128K
+  FLASHB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0
+}
+
+/* User mode stack top */
+_estack = 0x20005000;
+
+/* Stack size and address definitions */
+__Stack_Size = 0x1000 ;
+
+PROVIDE ( _Stack_Size = __Stack_Size ) ;
+
+__Stack_Init = _estack  - __Stack_Size ;
+
+PROVIDE ( _Stack_Init = __Stack_Init ) ;
+
+/* Enforce a linker error if there is not enough space left in ram for the 
stack */
+_Minimum_Stack_Size = 0x800 ;
+
+/* Check valid alignment for VTOR */
+ASSERT(ORIGIN(FLASH) == ALIGN(ORIGIN(FLASH), 0x80), "Start of memory region 
flash not aligned for startup vector table");
+
+/* Sections Definitions */
+
+SECTIONS
+{
+    /* for Cortex devices, the beginning of the startup code is stored in the 
.isr_vector section, which goes to FLASH */
+    .isr_vector :
+    {
+        . = ALIGN(4);
+        KEEP(*(.isr_vector)) /* Startup code */
+       . = ALIGN(4);
+    } >FLASH
+
+    /* for some STRx devices, the beginning of the startup code is stored in 
the .flashtext section, which goes to FLASH */
+    .flashtext :
+    {
+       . = ALIGN(4);
+        *(.flashtext)        /* Startup code */
+       . = ALIGN(4);
+    } >FLASH
+
+
+    /* the program code is stored in the .text section, which goes to Flash */
+    .text :
+    {
+        . = ALIGN(4);
+
+        *(.text)             /* remaining code */
+        *(.text.*)           /* remaining code */
+        *(.rodata)           /* read-only data (constants) */
+        *(.rodata*)
+        *(.glue_7)
+        *(.glue_7t)
+
+        . = ALIGN(4);
+       _etext = .;
+       /* This is used by the startup in order to initialize the .data secion 
*/
+       _sidata = _etext;
+    } >FLASH
+
+
+
+    /* This is the initialized data section
+    The program executes knowing that the data is in the RAM
+    but the loader puts the initial values in the FLASH (inidata).
+    It is one task of the startup to copy the initial values from FLASH to 
RAM. */
+    .data  : AT ( _sidata )
+    {
+        . = ALIGN(4);
+        /* This is used by the startup in order to initialize the .data secion 
*/
+        _sdata = . ;
+
+        *(.data)
+        *(.data.*)
+
+        . = ALIGN(4);
+       /* This is used by the startup in order to initialize the .data secion 
*/
+       _edata = . ;
+    } >RAM
+
+
+
+    /* This is the uninitialized data section */
+    .bss :
+    {
+        . = ALIGN(4);
+        /* This is used by the startup in order to initialize the .bss secion 
*/
+        _sbss = .;
+
+        *(.dynbss)
+        *(.bss .bss.* .gnu.linkonce.b.*)
+         /*        *(.bss) */
+        *(COMMON)
+
+        . = ALIGN(4);
+       /* This is used by the startup in order to initialize the .bss secion */
+       _ebss = . ;
+    } >RAM
+
+    PROVIDE ( end = _ebss );
+    PROVIDE ( _end = _ebss );
+
+    /* This is the user stack section
+    This is just to check that there is enough RAM left for the User mode stack
+    It should generate an error if it's full.
+     */
+    ._usrstack :
+    {
+        . = ALIGN(4);
+        _susrstack = . ;
+        . = . + _Minimum_Stack_Size ;
+        . = ALIGN(4);
+        _eusrstack = . ;
+    } >RAM
+
+   .b1text :
+    {
+        *(.b1text)                   /* remaining code */
+        *(.b1rodata)                 /* read-only data (constants) */
+        *(.b1rodata*)
+    } >FLASHB1
+
+    __exidx_start = .;
+    .ARM.exidx   : { *(.ARM.exidx* .gnu.linkonce.armexidx.*) }
+   __exidx_end = .;
+
+    /* after that it's only debugging information. */
+
+    /* remove the debugging information from the standard libraries */
+    /DISCARD/ :
+    {
+     libc.a ( * )
+     libm.a ( * )
+     libgcc.a ( * )
+     }
+
+    /* Stabs debugging sections.  */
+    .stab          0 : { *(.stab) }
+    .stabstr       0 : { *(.stabstr) }
+    .stab.excl     0 : { *(.stab.excl) }
+    .stab.exclstr  0 : { *(.stab.exclstr) }
+    .stab.index    0 : { *(.stab.index) }
+    .stab.indexstr 0 : { *(.stab.indexstr) }
+    .comment       0 : { *(.comment) }
+    /* DWARF debug sections.
+       Symbols in the DWARF debugging sections are relative to the beginning
+       of the section so we begin them at 0.*/
+    /* DWARF 1 */
+    .debug          0 : { *(.debug) }
+    .line           0 : { *(.line) }
+    /* GNU DWARF 1 extensions */
+    .debug_srcinfo  0 : { *(.debug_srcinfo) }
+    .debug_sfnames  0 : { *(.debug_sfnames) }
+    /* DWARF 1.1 and DWARF 2 */
+    .debug_aranges  0 : { *(.debug_aranges) }
+    .debug_pubnames 0 : { *(.debug_pubnames) }
+    /* DWARF 2 */
+    .debug_info     0 : { *(.debug_info .gnu.linkonce.wi.*) }
+    .debug_abbrev   0 : { *(.debug_abbrev) }
+    .debug_line     0 : { *(.debug_line) }
+    .debug_frame    0 : { *(.debug_frame) }
+    .debug_str      0 : { *(.debug_str) }
+    .debug_loc      0 : { *(.debug_loc) }
+    .debug_macinfo  0 : { *(.debug_macinfo) }
+    /* SGI/MIPS DWARF 2 extensions */
+    .debug_weaknames 0 : { *(.debug_weaknames) }
+    .debug_funcnames 0 : { *(.debug_funcnames) }
+    .debug_typenames 0 : { *(.debug_typenames) }
+    .debug_varnames  0 : { *(.debug_varnames) }
+}

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/stm32f103re_flash.ld (from rev 
5935, paparazzi3/trunk/sw/airborne/stm32/stm32f103re_flash.ld)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/stm32f103re_flash.ld                
                (rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/stm32f103re_flash.ld        
2010-09-23 22:28:37 UTC (rev 5936)
@@ -0,0 +1,198 @@
+/*
+ * $Id$
+ *  
+ * Copyright (C) 2010 Antoine Drouin <address@hidden>
+ *
+ * This file is part of Paparazzi.
+ *
+ * Paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * Paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA. 
+ */
+
+/* Memory Spaces Definitions */
+MEMORY
+{                        
+  RAM     (xrw): ORIGIN = 0x20000000, LENGTH = 64K
+  FLASH   (rx) : ORIGIN = 0x8000000,  LENGTH = 512K
+  FLASHB1 (rx) : ORIGIN = 0x00000000, LENGTH = 0
+}
+
+/* User mode stack top */
+_estack = 0x20010000;
+
+/* Stack size and address definitions */
+__Stack_Size = 0x1000 ;
+
+PROVIDE ( _Stack_Size = __Stack_Size ) ;
+
+__Stack_Init = _estack  - __Stack_Size ;
+
+PROVIDE ( _Stack_Init = __Stack_Init ) ;
+
+/* Enforce a linker error if there is not enough space left in ram for the 
stack */
+_Minimum_Stack_Size = 0x800 ;
+
+/* Check valid alignment for VTOR */
+ASSERT(ORIGIN(FLASH) == ALIGN(ORIGIN(FLASH), 0x80), "Start of memory region 
flash not aligned for startup vector table");
+
+/* Sections Definitions */
+
+SECTIONS
+{
+    /* for Cortex devices, the beginning of the startup code is stored in the 
.isr_vector section, which goes to FLASH */
+    .isr_vector :
+    {
+        . = ALIGN(4);
+        KEEP(*(.isr_vector)) /* Startup code */
+       . = ALIGN(4);
+    } >FLASH
+
+    /* for some STRx devices, the beginning of the startup code is stored in 
the .flashtext section, which goes to FLASH */
+    .flashtext :
+    {
+       . = ALIGN(4);
+        *(.flashtext)        /* Startup code */
+       . = ALIGN(4);
+    } >FLASH
+
+
+    /* the program code is stored in the .text section, which goes to Flash */
+    .text :
+    {
+        . = ALIGN(4);
+
+        *(.text)             /* remaining code */
+        *(.text.*)           /* remaining code */
+        *(.rodata)           /* read-only data (constants) */
+        *(.rodata*)
+        *(.glue_7)
+        *(.glue_7t)
+
+        . = ALIGN(4);
+       _etext = .;
+       /* This is used by the startup in order to initialize the .data secion 
*/
+       _sidata = _etext;
+    } >FLASH
+
+
+
+    /* This is the initialized data section
+    The program executes knowing that the data is in the RAM
+    but the loader puts the initial values in the FLASH (inidata).
+    It is one task of the startup to copy the initial values from FLASH to 
RAM. */
+    .data  : AT ( _sidata )
+    {
+        . = ALIGN(4);
+        /* This is used by the startup in order to initialize the .data secion 
*/
+        _sdata = . ;
+
+        *(.data)
+        *(.data.*)
+
+        . = ALIGN(4);
+       /* This is used by the startup in order to initialize the .data secion 
*/
+       _edata = . ;
+    } >RAM
+
+
+
+    /* This is the uninitialized data section */
+    .bss :
+    {
+        . = ALIGN(4);
+        /* This is used by the startup in order to initialize the .bss secion 
*/
+        _sbss = .;
+
+        *(.dynbss)
+        *(.bss .bss.* .gnu.linkonce.b.*)
+         /*        *(.bss) */
+        *(COMMON)
+
+        . = ALIGN(4);
+       /* This is used by the startup in order to initialize the .bss secion */
+       _ebss = . ;
+    } >RAM
+
+    PROVIDE ( end = _ebss );
+    PROVIDE ( _end = _ebss );
+
+    /* This is the user stack section
+    This is just to check that there is enough RAM left for the User mode stack
+    It should generate an error if it's full.
+     */
+    ._usrstack :
+    {
+        . = ALIGN(4);
+        _susrstack = . ;
+        . = . + _Minimum_Stack_Size ;
+        . = ALIGN(4);
+        _eusrstack = . ;
+    } >RAM
+
+   .b1text :
+    {
+        *(.b1text)                   /* remaining code */
+        *(.b1rodata)                 /* read-only data (constants) */
+        *(.b1rodata*)
+    } >FLASHB1
+
+    __exidx_start = .;
+    .ARM.exidx   : { *(.ARM.exidx* .gnu.linkonce.armexidx.*) }
+   __exidx_end = .;
+
+    /* after that it's only debugging information. */
+
+    /* remove the debugging information from the standard libraries */
+    /DISCARD/ :
+    {
+     libc.a ( * )
+     libm.a ( * )
+     libgcc.a ( * )
+     }
+
+    /* Stabs debugging sections.  */
+    .stab          0 : { *(.stab) }
+    .stabstr       0 : { *(.stabstr) }
+    .stab.excl     0 : { *(.stab.excl) }
+    .stab.exclstr  0 : { *(.stab.exclstr) }
+    .stab.index    0 : { *(.stab.index) }
+    .stab.indexstr 0 : { *(.stab.indexstr) }
+    .comment       0 : { *(.comment) }
+    /* DWARF debug sections.
+       Symbols in the DWARF debugging sections are relative to the beginning
+       of the section so we begin them at 0.*/
+    /* DWARF 1 */
+    .debug          0 : { *(.debug) }
+    .line           0 : { *(.line) }
+    /* GNU DWARF 1 extensions */
+    .debug_srcinfo  0 : { *(.debug_srcinfo) }
+    .debug_sfnames  0 : { *(.debug_sfnames) }
+    /* DWARF 1.1 and DWARF 2 */
+    .debug_aranges  0 : { *(.debug_aranges) }
+    .debug_pubnames 0 : { *(.debug_pubnames) }
+    /* DWARF 2 */
+    .debug_info     0 : { *(.debug_info .gnu.linkonce.wi.*) }
+    .debug_abbrev   0 : { *(.debug_abbrev) }
+    .debug_line     0 : { *(.debug_line) }
+    .debug_frame    0 : { *(.debug_frame) }
+    .debug_str      0 : { *(.debug_str) }
+    .debug_loc      0 : { *(.debug_loc) }
+    .debug_macinfo  0 : { *(.debug_macinfo) }
+    /* SGI/MIPS DWARF 2 extensions */
+    .debug_weaknames 0 : { *(.debug_weaknames) }
+    .debug_funcnames 0 : { *(.debug_funcnames) }
+    .debug_typenames 0 : { *(.debug_typenames) }
+    .debug_varnames  0 : { *(.debug_varnames) }
+}

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/sys_time_hw.c (from rev 5935, 
paparazzi3/trunk/sw/airborne/stm32/sys_time_hw.c)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/sys_time_hw.c                       
        (rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/sys_time_hw.c       2010-09-23 
22:28:37 UTC (rev 5936)
@@ -0,0 +1,47 @@
+/*
+ * Paparazzi $Id$
+ *
+ * Copyright (C) 2009 Antoine Drouin <address@hidden>
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ */
+
+#include "sys_time.h"
+
+volatile bool_t sys_time_period_elapsed;
+uint32_t cpu_time_ticks;
+
+void sys_time_init( void ) {
+  /* Generate SysTick interrupt every PERIODIC_TASK_PERIOD AHS clk */
+  if(SysTick_Config(PERIODIC_TASK_PERIOD-1)) {
+    while(1);
+  }
+  /* Set SysTick handler */
+  NVIC_SetPriority(SysTick_IRQn, 0x0);
+  sys_time_period_elapsed = FALSE;
+
+  cpu_time_sec = 0;
+  cpu_time_ticks = 0;
+}
+
+
+void sys_tick_irq_handler(void) {
+  sys_time_period_elapsed = TRUE;
+}
+
+

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/sys_time_hw.h (from rev 5935, 
paparazzi3/trunk/sw/airborne/stm32/sys_time_hw.h)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/sys_time_hw.h                       
        (rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/sys_time_hw.h       2010-09-23 
22:28:37 UTC (rev 5936)
@@ -0,0 +1,70 @@
+/*
+ * Paparazzi $Id$
+ *
+ * Copyright (C) 2009-2010 The Paparazzi Team
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ *
+ */
+
+/*
+ *\brief STM32 timing functions 
+ *
+ */
+
+#ifndef SYS_TIME_HW_H
+#define SYS_TIME_HW_H
+
+#include "sys_time.h"
+
+#include <stm32/gpio.h>
+#include <stm32/rcc.h>
+#include "std.h"
+#ifdef SYS_TIME_LED
+#include "led.h"
+#endif
+
+#define InitSysTimePeriodic() 
+
+extern void sys_time_init( void );
+extern void sys_tick_irq_handler(void);
+
+extern volatile bool_t sys_time_period_elapsed;
+extern uint32_t cpu_time_ticks;
+
+#define SYS_TICS_OF_SEC(s)        (uint32_t)((s) * AHB_CLK + 0.5)
+#define SIGNED_SYS_TICS_OF_SEC(s)  (int32_t)((s) * AHB_CLK + 0.5)
+
+static inline bool_t sys_time_periodic( void ) {
+  if (sys_time_period_elapsed) {
+    sys_time_period_elapsed = FALSE;
+    cpu_time_ticks += PERIODIC_TASK_PERIOD;
+    if (cpu_time_ticks >= TIME_TICKS_PER_SEC) {
+      cpu_time_ticks -= TIME_TICKS_PER_SEC;
+      cpu_time_sec++;
+#ifdef SYS_TIME_LED
+      LED_TOGGLE(SYS_TIME_LED);
+#endif
+    }
+    return TRUE;
+  }
+  else
+    return FALSE;
+}
+
+#endif /* SYS_TIME_HW_H */

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/uart_hw.c (from rev 5935, 
paparazzi3/trunk/sw/airborne/stm32/uart_hw.c)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/uart_hw.c                           
(rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/uart_hw.c   2010-09-23 22:28:37 UTC 
(rev 5936)
@@ -0,0 +1,413 @@
+/*
+ * Paparazzi $Id$
+ *
+ * Copyright (C) 2009 Antoine Drouin <address@hidden>
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA.
+ */
+
+#include "uart.h"
+
+#include <stm32/rcc.h>
+#include <stm32/misc.h>
+#include <stm32/usart.h>
+#include <stm32/gpio.h>
+#include "std.h"
+
+#ifdef USE_UART1 
+
+volatile uint16_t uart1_rx_insert_idx, uart1_rx_extract_idx;
+uint8_t  uart1_rx_buffer[UART1_RX_BUFFER_SIZE];
+
+volatile uint16_t uart1_tx_insert_idx, uart1_tx_extract_idx;
+volatile bool_t uart1_tx_running;
+uint8_t  uart1_tx_buffer[UART1_TX_BUFFER_SIZE];
+
+
+void uart1_init( void ) {
+  /* init RCC */
+  RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
+
+  /* Enable USART1 interrupts */
+  NVIC_InitTypeDef nvic;
+  nvic.NVIC_IRQChannel = USART1_IRQn;
+  nvic.NVIC_IRQChannelPreemptionPriority = 2;
+  nvic.NVIC_IRQChannelSubPriority = 1;
+  nvic.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&nvic);
+
+  /* Init GPIOS */
+  GPIO_InitTypeDef gpio;
+  /* GPIOA: GPIO_Pin_9 USART1 Tx push-pull */
+  gpio.GPIO_Pin   = UART1_TxPin;
+  gpio.GPIO_Mode  = GPIO_Mode_AF_PP;
+  gpio.GPIO_Speed = GPIO_Speed_50MHz;
+  GPIO_Init(UART1_TxPort, &gpio);
+  /* GPIOA: GPIO_Pin_10 USART1 Rx pin as floating input */
+  gpio.GPIO_Pin   = UART1_RxPin;
+  gpio.GPIO_Mode  = GPIO_Mode_IN_FLOATING;
+  GPIO_Init(UART1_RxPort, &gpio);
+
+  /* Configure USART1 */
+  USART_InitTypeDef usart;
+  usart.USART_BaudRate            = UART1_BAUD;
+  usart.USART_WordLength          = USART_WordLength_8b;
+  usart.USART_StopBits            = USART_StopBits_1;
+  usart.USART_Parity              = USART_Parity_No;
+  usart.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+  usart.USART_Mode                = USART_Mode_Rx | USART_Mode_Tx;
+  USART_Init(USART1, &usart);
+  /* Enable USART1 Receive interrupts */
+  USART_ITConfig(USART1, USART_IT_RXNE, ENABLE);
+  /* Enable the USART1 */
+  USART_Cmd(USART1, ENABLE);
+
+  // initialize the transmit data queue
+  uart1_tx_extract_idx = 0;
+  uart1_tx_insert_idx = 0;
+  uart1_tx_running = FALSE;
+
+  // initialize the receive data queue
+  uart1_rx_extract_idx = 0;
+  uart1_rx_insert_idx = 0;
+
+}
+
+void uart1_transmit( uint8_t data ) {
+
+  uint16_t temp = (uart1_tx_insert_idx + 1) % UART1_TX_BUFFER_SIZE;
+
+  if (temp == uart1_tx_extract_idx)
+    return;                          // no room
+
+  USART_ITConfig(USART1, USART_IT_TXE, DISABLE);
+
+  // check if in process of sending data
+  if (uart1_tx_running) { // yes, add to queue
+    uart1_tx_buffer[uart1_tx_insert_idx] = data;
+    uart1_tx_insert_idx = temp;
+  }
+  else { // no, set running flag and write to output register
+    uart1_tx_running = TRUE;
+    USART_SendData(USART1, data);
+  }
+
+  USART_ITConfig(USART1, USART_IT_TXE, ENABLE);
+
+}
+
+bool_t uart1_check_free_space( uint8_t len) {
+  int16_t space = uart1_tx_extract_idx - uart1_tx_insert_idx;
+  if (space <= 0)
+    space += UART1_TX_BUFFER_SIZE;
+  return (uint16_t)(space - 1) >= len;
+}
+
+void usart1_irq_handler(void) {
+  
+  if(USART_GetITStatus(USART1, USART_IT_TXE) != RESET){
+    // check if more data to send
+    if (uart1_tx_insert_idx != uart1_tx_extract_idx) {
+      USART_SendData(USART1,uart1_tx_buffer[uart1_tx_extract_idx]);
+      uart1_tx_extract_idx++;
+      uart1_tx_extract_idx %= UART1_TX_BUFFER_SIZE;
+    }
+    else {
+      uart1_tx_running = FALSE;   // clear running flag
+      USART_ITConfig(USART1, USART_IT_TXE, DISABLE);
+    }
+  }
+
+  if(USART_GetITStatus(USART1, USART_IT_RXNE) != RESET){
+    uint16_t temp = (uart1_rx_insert_idx + 1) % UART1_RX_BUFFER_SIZE;;
+    uart1_rx_buffer[uart1_rx_insert_idx] = USART_ReceiveData(USART1);
+    // check for more room in queue
+    if (temp != uart1_rx_extract_idx)
+      uart1_rx_insert_idx = temp; // update insert index
+  }
+
+}
+
+
+#endif /* USE_UART1 */
+
+
+
+
+
+
+
+#ifdef USE_UART2 
+
+volatile uint16_t uart2_rx_insert_idx, uart2_rx_extract_idx;
+uint8_t  uart2_rx_buffer[UART2_RX_BUFFER_SIZE];
+
+volatile uint16_t uart2_tx_insert_idx, uart2_tx_extract_idx;
+volatile bool_t uart2_tx_running;
+uint8_t  uart2_tx_buffer[UART2_TX_BUFFER_SIZE];
+
+
+void uart2_init( void ) {
+  /* init RCC */
+  RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
+
+  /* Enable USART2 interrupts */
+  NVIC_InitTypeDef nvic;
+  nvic.NVIC_IRQChannel = USART2_IRQn;
+  nvic.NVIC_IRQChannelPreemptionPriority = 2;
+  nvic.NVIC_IRQChannelSubPriority = 1;
+  nvic.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&nvic);
+
+  /* Init GPIOS */
+  GPIO_InitTypeDef gpio;
+  /* GPIOA: GPIO_Pin_2 USART2 Tx push-pull */
+  gpio.GPIO_Pin   = UART2_TxPin; // ;
+  gpio.GPIO_Mode  = GPIO_Mode_AF_PP;
+  gpio.GPIO_Speed = GPIO_Speed_50MHz;
+  GPIO_Init(UART2_TxPort, &gpio);
+  /* GPIOA: GPIO_Pin_3 USART2 Rx pin as floating input */
+  gpio.GPIO_Pin   = UART2_RxPin; // ;
+  gpio.GPIO_Mode  = GPIO_Mode_IN_FLOATING;
+  GPIO_Init(UART2_RxPort, &gpio);
+
+  /* Configure USART2 */
+  USART_InitTypeDef usart;
+  usart.USART_BaudRate            = UART2_BAUD;
+  usart.USART_WordLength          = USART_WordLength_8b;
+  usart.USART_StopBits            = USART_StopBits_1;
+  usart.USART_Parity              = USART_Parity_No;
+  usart.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+  usart.USART_Mode                = USART_Mode_Rx | USART_Mode_Tx;
+  USART_Init(USART2, &usart);
+  /* Enable USART2 Receive interrupts */
+  USART_ITConfig(USART2, USART_IT_RXNE, ENABLE);
+  /* Enable the USART2 */
+  USART_Cmd(USART2, ENABLE);
+
+  // initialize the transmit data queue
+  uart2_tx_extract_idx = 0;
+  uart2_tx_insert_idx = 0;
+  uart2_tx_running = FALSE;
+
+  // initialize the receive data queue
+  uart2_rx_extract_idx = 0;
+  uart2_rx_insert_idx = 0;
+
+}
+
+void uart2_transmit( uint8_t data ) {
+
+  uint16_t temp = (uart2_tx_insert_idx + 1) % UART2_TX_BUFFER_SIZE;
+
+  if (temp == uart2_tx_extract_idx)
+    return;                          // no room
+
+  USART_ITConfig(USART2, USART_IT_TXE, DISABLE);
+
+  // check if in process of sending data
+  if (uart2_tx_running) { // yes, add to queue
+    uart2_tx_buffer[uart2_tx_insert_idx] = data;
+    uart2_tx_insert_idx = temp;
+  }
+  else { // no, set running flag and write to output register
+    uart2_tx_running = TRUE;
+    USART_SendData(USART2, data);
+  }
+
+  USART_ITConfig(USART2, USART_IT_TXE, ENABLE);
+
+}
+
+bool_t uart2_check_free_space( uint8_t len) {
+  int16_t space = uart2_tx_extract_idx - uart2_tx_insert_idx;
+  if (space <= 0)
+    space += UART2_TX_BUFFER_SIZE;
+  return (uint16_t)(space - 1) >= len;
+}
+
+
+void usart2_irq_handler(void) {
+  
+  if(USART_GetITStatus(USART2, USART_IT_TXE) != RESET){
+    // check if more data to send
+    if (uart2_tx_insert_idx != uart2_tx_extract_idx) {
+      USART_SendData(USART2,uart2_tx_buffer[uart2_tx_extract_idx]);
+      uart2_tx_extract_idx++;
+      uart2_tx_extract_idx %= UART2_TX_BUFFER_SIZE;
+    }
+    else {
+      uart2_tx_running = FALSE;   // clear running flag
+      USART_ITConfig(USART2, USART_IT_TXE, DISABLE);
+    }
+  }
+
+  if(USART_GetITStatus(USART2, USART_IT_RXNE) != RESET){
+    uint16_t temp = (uart2_rx_insert_idx + 1) % UART2_RX_BUFFER_SIZE;;
+    uart2_rx_buffer[uart2_rx_insert_idx] = USART_ReceiveData(USART2);
+    // check for more room in queue
+    if (temp != uart2_rx_extract_idx)
+      uart2_rx_insert_idx = temp; // update insert index
+  }
+
+}
+
+
+#endif /* USE_UART2 */
+
+
+
+
+
+
+#ifdef USE_UART3 
+
+volatile uint16_t uart3_rx_insert_idx, uart3_rx_extract_idx;
+uint8_t  uart3_rx_buffer[UART3_RX_BUFFER_SIZE];
+
+volatile uint16_t uart3_tx_insert_idx, uart3_tx_extract_idx;
+volatile bool_t uart3_tx_running;
+uint8_t  uart3_tx_buffer[UART3_TX_BUFFER_SIZE];
+
+#include "led.h"
+
+
+void uart3_init( void ) {
+
+  /* init RCC */
+  RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE);
+  RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
+
+  /* Enable USART3 interrupts */
+  NVIC_InitTypeDef nvic;
+  nvic.NVIC_IRQChannel = USART3_IRQn;
+  nvic.NVIC_IRQChannelPreemptionPriority = 2;
+  nvic.NVIC_IRQChannelSubPriority = 1;
+  nvic.NVIC_IRQChannelCmd = ENABLE;
+  NVIC_Init(&nvic);
+
+  /* Init GPIOS */
+  GPIO_PinRemapConfig(GPIO_PartialRemap_USART3, ENABLE);
+  GPIO_InitTypeDef gpio;
+  /* GPIOC: GPIO_Pin_10 USART3 Tx push-pull */
+  gpio.GPIO_Pin   = UART3_TxPin; 
+  gpio.GPIO_Mode  = GPIO_Mode_AF_PP;
+  gpio.GPIO_Speed = GPIO_Speed_50MHz;
+  GPIO_Init(UART3_TxPort, &gpio);
+  /* GPIOC: GPIO_Pin_11 USART3 Rx pin as floating input */
+  gpio.GPIO_Pin   = UART3_RxPin; 
+  gpio.GPIO_Mode  = GPIO_Mode_IN_FLOATING;
+  GPIO_Init(UART3_RxPort, &gpio);
+
+  /* Configure USART3 */
+  USART_InitTypeDef usart;
+  usart.USART_BaudRate            = UART3_BAUD;
+  usart.USART_WordLength          = USART_WordLength_8b;
+  usart.USART_StopBits            = USART_StopBits_1;
+  usart.USART_Parity              = USART_Parity_No;
+  usart.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
+  usart.USART_Mode                = USART_Mode_Rx | USART_Mode_Tx;
+  USART_Init(USART3, &usart);
+  /* Enable USART3 Receive interrupts */
+  USART_ITConfig(USART3, USART_IT_RXNE, ENABLE);
+  /* Enable the USART3 */
+  USART_Cmd(USART3, ENABLE);
+
+  // initialize the transmit data queue
+  uart3_tx_extract_idx = 0;
+  uart3_tx_insert_idx = 0;
+  uart3_tx_running = FALSE;
+
+  // initialize the receive data queuenn
+  uart3_rx_extract_idx = 0;
+  uart3_rx_insert_idx = 0;
+
+}
+
+void uart3_transmit( uint8_t data ) {
+
+  uint16_t temp = (uart3_tx_insert_idx + 1) % UART3_TX_BUFFER_SIZE;
+
+  if (temp == uart3_tx_extract_idx)
+    return;                          // no room
+
+  USART_ITConfig(USART3, USART_IT_TXE, DISABLE);
+
+  // check if in process of sending data
+  if (uart3_tx_running) { // yes, add to queue
+    uart3_tx_buffer[uart3_tx_insert_idx] = data;
+    uart3_tx_insert_idx = temp;
+  }
+  else { // no, set running flag and write to output register
+    uart3_tx_running = TRUE;
+    USART_SendData(USART3, data);
+  }
+  USART_ITConfig(USART3, USART_IT_TXE, ENABLE);
+
+}
+
+bool_t uart3_check_free_space( uint8_t len) {
+  int16_t space = uart3_tx_extract_idx - uart3_tx_insert_idx;
+  if (space <= 0)
+    space += UART3_TX_BUFFER_SIZE;
+  return (uint16_t)(space - 1) >= len;
+}
+
+
+void usart3_irq_handler(void) {
+  
+  if(USART_GetITStatus(USART3, USART_IT_TXE) != RESET){
+    // check if more data to send
+    if (uart3_tx_insert_idx != uart3_tx_extract_idx) {
+      USART_SendData(USART3,uart3_tx_buffer[uart3_tx_extract_idx]);
+      uart3_tx_extract_idx++;
+      uart3_tx_extract_idx %= UART3_TX_BUFFER_SIZE;
+    }
+    else {
+      uart3_tx_running = FALSE; // clear running flag
+      USART_ITConfig(USART3, USART_IT_TXE, DISABLE);
+    }
+  }
+
+  if(USART_GetITStatus(USART3, USART_IT_RXNE) != RESET){
+    uint16_t temp = (uart3_rx_insert_idx + 1) % UART3_RX_BUFFER_SIZE;;
+    uart3_rx_buffer[uart3_rx_insert_idx] = USART_ReceiveData(USART3);
+    // check for more room in queue
+    if (temp != uart3_rx_extract_idx)
+      uart3_rx_insert_idx = temp; // update insert index
+  }
+
+}
+
+
+#endif /* USE_UART3 */
+
+void uart_init( void )
+{
+#ifdef USE_UART1 
+  uart1_init();
+#endif
+#ifdef USE_UART2 
+  uart2_init();
+#endif
+#ifdef USE_UART3 
+  uart3_init();
+#endif
+}
+
+

Copied: paparazzi3/trunk/sw/airborne/arch/stm32/uart_hw.h (from rev 5935, 
paparazzi3/trunk/sw/airborne/stm32/uart_hw.h)
===================================================================
--- paparazzi3/trunk/sw/airborne/arch/stm32/uart_hw.h                           
(rev 0)
+++ paparazzi3/trunk/sw/airborne/arch/stm32/uart_hw.h   2010-09-23 22:28:37 UTC 
(rev 5936)
@@ -0,0 +1,186 @@
+/*
+ * $Id$
+ *  
+ * Copyright (C) 2009 Antoine Drouin <address@hidden>
+ *
+ * This file is part of paparazzi.
+ *
+ * paparazzi is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2, or (at your option)
+ * any later version.
+ *
+ * paparazzi is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with paparazzi; see the file COPYING.  If not, write to
+ * the Free Software Foundation, 59 Temple Place - Suite 330,
+ * Boston, MA 02111-1307, USA. 
+ */
+
+/*
+ *\brief STM32 usart functions 
+ *
+ */
+
+#ifndef UART_HW_H
+#define UART_HW_H
+
+#include "std.h"
+
+#define B9600     9600
+#define B38400   38400
+#define B57600   57600
+#define B115200 115200
+
+
+/* sort out the problem of UART5 already defined in stm32.h */
+#define USART5               ((USART_TypeDef *) UART5_BASE)
+#undef UART5
+
+#define UART1_TxPin GPIO_Pin_9
+#define UART2_TxPin GPIO_Pin_2
+#define UART3_TxPin GPIO_Pin_10
+
+#define UART1_RxPin GPIO_Pin_10
+#define UART2_RxPin GPIO_Pin_3
+#define UART3_RxPin GPIO_Pin_11
+#define UART5_RxPin GPIO_Pin_2
+
+#define UART1_TxPort GPIOA
+#define UART2_TxPort GPIOA
+#define UART3_TxPort GPIOC
+
+#define UART1_RxPort GPIOA
+#define UART2_RxPort GPIOA
+#define UART3_RxPort GPIOC
+#define UART5_RxPort GPIOD
+
+#define UART1_Periph RCC_APB2Periph_GPIOA
+#define UART2_Periph RCC_APB2Periph_GPIOA
+#define UART3_Periph RCC_APB2Periph_GPIOC
+#define UART5_Periph RCC_APB2Periph_GPIOD
+
+#define UART1_UartPeriph RCC_APB2Periph_USART1
+#define UART2_UartPeriph RCC_APB1Periph_USART2
+#define UART3_UartPeriph RCC_APB1Periph_USART3
+#define UART5_UartPeriph RCC_APB1Periph_UART5
+
+#define UART1_remap {}
+#define UART2_remap {}
+#define UART3_remap {RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE); \
+                     GPIO_PinRemapConfig(GPIO_PartialRemap_USART3, ENABLE);}
+#define UART5_remap {}
+
+#define UART1_clk(_periph, _val) RCC_APB2PeriphClockCmd(_periph, _val)
+#define UART2_clk(_periph, _val) RCC_APB1PeriphClockCmd(_periph, _val)
+#define UART3_clk(_periph, _val) RCC_APB1PeriphClockCmd(_periph, _val);
+#define UART5_clk(_periph, _val) RCC_APB1PeriphClockCmd(_periph, _val) 
+
+#define Uart1_init uart1_init()
+#define Uart2_init uart2_init()
+#define Uart3_init uart3_init()
+#define Uart5_init uart5_init()
+
+#define UART1_irq_handler usart1_irq_handler
+#define UART2_irq_handler usart2_irq_handler
+#define UART3_irq_handler usart3_irq_handler
+#define UART5_irq_handler usart5_irq_handler 
+
+#define UART1_IRQn USART1_IRQn
+#define UART2_IRQn USART2_IRQn 
+#define UART3_IRQn USART3_IRQn
+
+#define UART1_reg USART1
+#define UART2_reg USART2
+#define UART3_reg USART3
+#define UART5_reg USART5  
+
+
+#if defined USE_UART1 || OVERRIDE_UART1_IRQ_HANDLER
+extern void usart1_irq_handler(void);
+#endif
+
+#if defined USE_UART2 || OVERRIDE_UART2_IRQ_HANDLER
+extern void usart2_irq_handler(void);
+#endif
+
+#if defined USE_UART3 || OVERRIDE_UART3_IRQ_HANDLER
+extern void usart3_irq_handler(void);
+#endif
+
+#if defined USE_UART5 || OVERRIDE_UART5_IRQ_HANDLER
+extern void usart5_irq_handler(void);
+#endif
+
+#ifdef USE_UART1
+#define UART1_RX_BUFFER_SIZE 128
+#define UART1_TX_BUFFER_SIZE 128
+
+extern volatile uint16_t uart1_rx_insert_idx, uart1_rx_extract_idx;
+extern uint8_t  uart1_rx_buffer[UART1_RX_BUFFER_SIZE];
+
+extern volatile uint16_t uart1_tx_insert_idx, uart1_tx_extract_idx;
+extern volatile bool_t   uart1_tx_running;
+extern uint8_t  uart1_tx_buffer[UART1_TX_BUFFER_SIZE];
+
+#define Uart1ChAvailable() (uart1_rx_insert_idx != uart1_rx_extract_idx)
+#define Uart1Getch() ({                                                        
\
+      uint8_t ret = uart1_rx_buffer[uart1_rx_extract_idx];             \
+      uart1_rx_extract_idx = (uart1_rx_extract_idx + 1)%UART1_RX_BUFFER_SIZE; \
+      ret;                                                             \
+    })
+
+#endif /* USE_UART1 */
+
+
+#ifdef USE_UART2
+
+#define UART2_RX_BUFFER_SIZE 128
+#define UART2_TX_BUFFER_SIZE 128
+
+extern volatile uint16_t uart2_rx_insert_idx, uart2_rx_extract_idx;
+extern uint8_t  uart2_rx_buffer[UART2_RX_BUFFER_SIZE];
+
+extern volatile uint16_t uart2_tx_insert_idx, uart2_tx_extract_idx;
+extern volatile bool_t   uart2_tx_running;
+extern uint8_t  uart2_tx_buffer[UART2_TX_BUFFER_SIZE];
+
+#define Uart2ChAvailable() (uart2_rx_insert_idx != uart2_rx_extract_idx)
+#define Uart2Getch() ({                                                        
\
+      uint8_t ret = uart2_rx_buffer[uart2_rx_extract_idx];             \
+      uart2_rx_extract_idx = (uart2_rx_extract_idx + 1)%UART2_RX_BUFFER_SIZE; \
+      ret;                                                             \
+    })
+
+#endif /* USE_UART2 */
+
+
+#ifdef USE_UART3
+
+#define UART3_RX_BUFFER_SIZE 128
+#define UART3_TX_BUFFER_SIZE 128
+
+extern volatile uint16_t uart3_rx_insert_idx, uart3_rx_extract_idx;
+extern uint8_t  uart3_rx_buffer[UART3_RX_BUFFER_SIZE];
+
+extern volatile uint16_t uart3_tx_insert_idx, uart3_tx_extract_idx;
+extern volatile bool_t   uart3_tx_running;
+extern uint8_t  uart3_tx_buffer[UART3_TX_BUFFER_SIZE];
+
+#define Uart3ChAvailable() (uart3_rx_insert_idx != uart3_rx_extract_idx)
+#define Uart3Getch() ({                                                        
\
+      uint8_t ret = uart3_rx_buffer[uart3_rx_extract_idx];             \
+      uart3_rx_extract_idx = (uart3_rx_extract_idx + 1)%UART3_RX_BUFFER_SIZE; \
+      ret;                                                             \
+    })
+
+#endif /* USE_UART3 */
+
+
+void uart_init( void );
+
+#endif /* UART_HW_H */




reply via email to

[Prev in Thread] Current Thread [Next in Thread]