aboutsummaryrefslogtreecommitdiff
path: root/nuttx/configs/px4fmu
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2012-08-04 15:12:36 -0700
committerpx4dev <px4@purgatory.org>2012-08-04 15:12:36 -0700
commit8a365179eafdf3aea98e60ab9f5882b200d4c759 (patch)
tree4f38d6d4cd80bd0b6e22e2bb534c3f117ce44e56 /nuttx/configs/px4fmu
downloadpx4-firmware-8a365179eafdf3aea98e60ab9f5882b200d4c759.tar.gz
px4-firmware-8a365179eafdf3aea98e60ab9f5882b200d4c759.tar.bz2
px4-firmware-8a365179eafdf3aea98e60ab9f5882b200d4c759.zip
Fresh import of the PX4 firmware sources.
Diffstat (limited to 'nuttx/configs/px4fmu')
-rwxr-xr-xnuttx/configs/px4fmu/README.txt601
-rw-r--r--nuttx/configs/px4fmu/common/Make.defs216
-rw-r--r--nuttx/configs/px4fmu/common/ld.script133
-rwxr-xr-xnuttx/configs/px4fmu/include/board.h392
-rw-r--r--nuttx/configs/px4fmu/include/drv_bma180.h99
-rw-r--r--nuttx/configs/px4fmu/include/drv_eeprom.h73
-rw-r--r--nuttx/configs/px4fmu/include/drv_gpio.h107
-rw-r--r--nuttx/configs/px4fmu/include/drv_hmc5883l.h100
-rw-r--r--nuttx/configs/px4fmu/include/drv_l3gd20.h108
-rw-r--r--nuttx/configs/px4fmu/include/drv_led.h51
-rw-r--r--nuttx/configs/px4fmu/include/drv_lis331.h83
-rw-r--r--nuttx/configs/px4fmu/include/drv_mpu6000.h92
-rw-r--r--nuttx/configs/px4fmu/include/drv_ms5611.h76
-rw-r--r--nuttx/configs/px4fmu/include/drv_tone_alarm.h130
-rw-r--r--nuttx/configs/px4fmu/include/nsh_romfsimg.h601
-rw-r--r--nuttx/configs/px4fmu/include/rcS.template39
-rw-r--r--nuttx/configs/px4fmu/include/up_adc.h60
-rw-r--r--nuttx/configs/px4fmu/include/up_cpuload.h62
-rw-r--r--nuttx/configs/px4fmu/include/up_hrt.h130
-rw-r--r--nuttx/configs/px4fmu/include/up_pwm_servo.h117
-rw-r--r--nuttx/configs/px4fmu/nsh/Make.defs3
-rw-r--r--nuttx/configs/px4fmu/nsh/appconfig92
-rwxr-xr-xnuttx/configs/px4fmu/nsh/defconfig1053
-rwxr-xr-xnuttx/configs/px4fmu/nsh/setenv.sh67
-rw-r--r--nuttx/configs/px4fmu/src/Makefile102
-rw-r--r--nuttx/configs/px4fmu/src/drv_bma180.c341
-rw-r--r--nuttx/configs/px4fmu/src/drv_eeprom.c522
-rw-r--r--nuttx/configs/px4fmu/src/drv_gpio.c195
-rw-r--r--nuttx/configs/px4fmu/src/drv_hmc5833l.c352
-rw-r--r--nuttx/configs/px4fmu/src/drv_l3gd20.c364
-rw-r--r--nuttx/configs/px4fmu/src/drv_led.c113
-rw-r--r--nuttx/configs/px4fmu/src/drv_lis331.c272
-rw-r--r--nuttx/configs/px4fmu/src/drv_mpu6000.c411
-rw-r--r--nuttx/configs/px4fmu/src/drv_ms5611.c493
-rw-r--r--nuttx/configs/px4fmu/src/drv_tone_alarm.c511
-rw-r--r--nuttx/configs/px4fmu/src/px4fmu-internal.h166
-rw-r--r--nuttx/configs/px4fmu/src/up_adc.c173
-rw-r--r--nuttx/configs/px4fmu/src/up_boot.c76
-rw-r--r--nuttx/configs/px4fmu/src/up_can.c142
-rw-r--r--nuttx/configs/px4fmu/src/up_cpuload.c182
-rw-r--r--nuttx/configs/px4fmu/src/up_hrt.c801
-rw-r--r--nuttx/configs/px4fmu/src/up_leds.c127
-rw-r--r--nuttx/configs/px4fmu/src/up_nsh.c392
-rw-r--r--nuttx/configs/px4fmu/src/up_pwm_servo.c344
-rw-r--r--nuttx/configs/px4fmu/src/up_spi.c192
-rw-r--r--nuttx/configs/px4fmu/src/up_usbdev.c105
46 files changed, 10861 insertions, 0 deletions
diff --git a/nuttx/configs/px4fmu/README.txt b/nuttx/configs/px4fmu/README.txt
new file mode 100755
index 000000000..c92169206
--- /dev/null
+++ b/nuttx/configs/px4fmu/README.txt
@@ -0,0 +1,601 @@
+README
+======
+
+This README discusses issues unique to NuttX configurations for the
+PX4FMU development board.
+
+Or, it will once those are established. For now, this is a copy of the file
+as presented for the STMicro STM32F407 evaluation board. Read with caution.
+
+Contents
+========
+
+ - Development Environment
+ - GNU Toolchain Options
+ - IDEs
+ - NuttX buildroot Toolchain
+ - STM3240G-EVAL-specific Configuration Options
+ - LEDs
+ - Ethernet
+ - PWM
+ - CAN
+ - Configurations
+
+Development Environment
+=======================
+
+ Either Linux or Cygwin on Windows can be used for the development environment.
+ The source has been built only using the GNU toolchain (see below). Other
+ toolchains will likely cause problems. Testing was performed using the Cygwin
+ environment because the Raisonance R-Link emulatator and some RIDE7 development tools
+ were used and those tools works only under Windows.
+
+GNU Toolchain Options
+=====================
+
+ The NuttX make system has been modified to support the following different
+ toolchain options.
+
+ 1. The CodeSourcery GNU toolchain,
+ 2. The devkitARM GNU toolchain,
+ 3. Raisonance GNU toolchain, or
+ 4. The NuttX buildroot Toolchain (see below).
+
+ All testing has been conducted using the CodeSourcery toolchain for Windows. To use
+ the devkitARM, Raisonance GNU, or NuttX buildroot toolchain, you simply need to
+ add one of the following configuration options to your .config (or defconfig)
+ file:
+
+ CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows
+ CONFIG_STM32_CODESOURCERYL=y : CodeSourcery under Linux
+ CONFIG_STM32_DEVKITARM=y : devkitARM under Windows
+ CONFIG_STM32_RAISONANCE=y : Raisonance RIDE7 under Windows
+ CONFIG_STM32_BUILDROOT=y : NuttX buildroot under Linux or Cygwin (default)
+
+ If you change the default toolchain, then you may also have to modify the PATH in
+ the setenv.h file if your make cannot find the tools.
+
+ NOTE: the CodeSourcery (for Windows), devkitARM, and Raisonance toolchains are
+ Windows native toolchains. The CodeSourcey (for Linux) and NuttX buildroot
+ toolchains are Cygwin and/or Linux native toolchains. There are several limitations
+ to using a Windows based toolchain in a Cygwin environment. The three biggest are:
+
+ 1. The Windows toolchain cannot follow Cygwin paths. Path conversions are
+ performed automatically in the Cygwin makefiles using the 'cygpath' utility
+ but you might easily find some new path problems. If so, check out 'cygpath -w'
+
+ 2. Windows toolchains cannot follow Cygwin symbolic links. Many symbolic links
+ are used in Nuttx (e.g., include/arch). The make system works around these
+ problems for the Windows tools by copying directories instead of linking them.
+ But this can also cause some confusion for you: For example, you may edit
+ a file in a "linked" directory and find that your changes had no effect.
+ That is because you are building the copy of the file in the "fake" symbolic
+ directory. If you use a Windows toolchain, you should get in the habit of
+ making like this:
+
+ make clean_context all
+
+ An alias in your .bashrc file might make that less painful.
+
+ 3. Dependencies are not made when using Windows versions of the GCC. This is
+ because the dependencies are generated using Windows pathes which do not
+ work with the Cygwin make.
+
+ Support has been added for making dependencies with the windows-native toolchains.
+ That support can be enabled by modifying your Make.defs file as follows:
+
+ - MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ + MKDEP = $(TOPDIR)/tools/mkdeps.sh --winpaths "$(TOPDIR)"
+
+ If you have problems with the dependency build (for example, if you are not
+ building on C:), then you may need to modify tools/mkdeps.sh
+
+ NOTE 1: The CodeSourcery toolchain (2009q1) does not work with default optimization
+ level of -Os (See Make.defs). It will work with -O0, -O1, or -O2, but not with
+ -Os.
+
+ NOTE 2: The devkitARM toolchain includes a version of MSYS make. Make sure that
+ the paths to Cygwin's /bin and /usr/bin directories appear BEFORE the devkitARM
+ path or will get the wrong version of make.
+
+IDEs
+====
+
+ NuttX is built using command-line make. It can be used with an IDE, but some
+ effort will be required to create the project.
+
+ Makefile Build
+ --------------
+ Under Eclipse, it is pretty easy to set up an "empty makefile project" and
+ simply use the NuttX makefile to build the system. That is almost for free
+ under Linux. Under Windows, you will need to set up the "Cygwin GCC" empty
+ makefile project in order to work with Windows (Google for "Eclipse Cygwin" -
+ there is a lot of help on the internet).
+
+ Native Build
+ ------------
+ Here are a few tips before you start that effort:
+
+ 1) Select the toolchain that you will be using in your .config file
+ 2) Start the NuttX build at least one time from the Cygwin command line
+ before trying to create your project. This is necessary to create
+ certain auto-generated files and directories that will be needed.
+ 3) Set up include pathes: You will need include/, arch/arm/src/stm32,
+ arch/arm/src/common, arch/arm/src/armv7-m, and sched/.
+ 4) All assembly files need to have the definition option -D __ASSEMBLY__
+ on the command line.
+
+ Startup files will probably cause you some headaches. The NuttX startup file
+ is arch/arm/src/stm32/stm32_vectors.S. With RIDE, I have to build NuttX
+ one time from the Cygwin command line in order to obtain the pre-built
+ startup object needed by RIDE.
+
+NuttX buildroot Toolchain
+=========================
+
+ A GNU GCC-based toolchain is assumed. The files */setenv.sh should
+ be modified to point to the correct path to the Cortex-M3 GCC toolchain (if
+ different from the default in your PATH variable).
+
+ If you have no Cortex-M3 toolchain, one can be downloaded from the NuttX
+ SourceForge download site (https://sourceforge.net/project/showfiles.php?group_id=189573).
+ This GNU toolchain builds and executes in the Linux or Cygwin environment.
+
+ 1. You must have already configured Nuttx in <some-dir>/nuttx.
+
+ cd tools
+ ./configure.sh stm3240g-eval/<sub-dir>
+
+ 2. Download the latest buildroot package into <some-dir>
+
+ 3. unpack the buildroot tarball. The resulting directory may
+ have versioning information on it like buildroot-x.y.z. If so,
+ rename <some-dir>/buildroot-x.y.z to <some-dir>/buildroot.
+
+ 4. cd <some-dir>/buildroot
+
+ 5. cp configs/cortexm3-defconfig-4.3.3 .config
+
+ 6. make oldconfig
+
+ 7. make
+
+ 8. Edit setenv.h, if necessary, so that the PATH variable includes
+ the path to the newly built binaries.
+
+ See the file configs/README.txt in the buildroot source tree. That has more
+ detailed PLUS some special instructions that you will need to follow if you are
+ building a Cortex-M3 toolchain for Cygwin under Windows.
+
+Ethernet
+========
+
+The Ethernet driver is configured to use the MII interface:
+
+ Board Jumper Settings:
+
+ Jumper Description
+ JP8 To enable MII, JP8 should not be fitted.
+ JP6 2-3: Enable MII interface mode
+ JP5 2-3: Provide 25 MHz clock for MII or 50 MHz clock for RMII by MCO at PA8
+ SB1 Not used with MII
+
+LEDs
+====
+
+The STM3240G-EVAL board has four LEDs labeled LD1, LD2, LD3 and LD4 on the
+board.. These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is
+defined. In that case, the usage by the board port is defined in
+include/board.h and src/up_leds.c. The LEDs are used to encode OS-related\
+events as follows:
+
+ SYMBOL Meaning LED1* LED2 LED3 LED4
+ ------------------- ----------------------- ------- ------- ------- ------
+ LED_STARTED NuttX has been started ON OFF OFF OFF
+ LED_HEAPALLOCATE Heap has been allocated OFF ON OFF OFF
+ LED_IRQSENABLED Interrupts enabled ON ON OFF OFF
+ LED_STACKCREATED Idle stack created OFF OFF ON OFF
+ LED_INIRQ In an interrupt** ON N/C N/C OFF
+ LED_SIGNAL In a signal handler*** N/C ON N/C OFF
+ LED_ASSERTION An assertion failed ON ON N/C OFF
+ LED_PANIC The system has crashed N/C N/C N/C ON
+ LED_IDLE STM32 is is sleep mode (Optional, not used)
+
+ * If LED1, LED2, LED3 are statically on, then NuttX probably failed to boot
+ and these LEDs will give you some indication of where the failure was
+ ** The normal state is LED3 ON and LED1 faintly glowing. This faint glow
+ is because of timer interupts that result in the LED being illuminated
+ on a small proportion of the time.
+*** LED2 may also flicker normally if signals are processed.
+
+PWM
+===
+
+The STM3240G-Eval has no real on-board PWM devices, but the board can be
+configured to output a pulse train using TIM4 CH2. This pin is used by
+FSMC is but is also connected to the Motor Control Connector (CN5) just
+for this purpose:
+
+ PD13 FSMC_A18 / MC_TIM4_CH2 pin 33 (EnB)
+
+FSMC must be disabled in this case! PD13 is available at:
+
+ Daughterboard Extension Connector, CN3, pin 32 - available
+ TFT LCD Connector, CN19, pin 17 -- not available without removing the LCD.
+ Motor Control Connector CN15, pin 33 -- not available unless you bridge SB14.
+
+CAN
+===
+
+Connector 10 (CN10) is DB-9 male connector that can be used with CAN1 or CAN2.
+
+ JP10 connects CAN1_RX or CAN2_RX to the CAN transceiver
+ JP3 connects CAN1_TX or CAN2_TX to the CAN transceiver
+
+CAN signals are then available on CN10 pins:
+
+ CN10 Pin 7 = CANH
+ CN10 Pin 2 = CANL
+
+Mapping to STM32 GPIO pins:
+
+ PD0 = FSMC_D2 & CAN1_RX
+ PD1 = FSMC_D3 & CAN1_TX
+ PB13 = ULPI_D6 & CAN2_TX
+ PB5 = ULPI_D7 & CAN2_RX
+
+Configuration Options:
+
+ CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
+ CONFIG_STM32_CAN2 must also be defined)
+ CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
+ Default: 8
+ CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
+ Default: 4
+
+ CONFIG_STM32_CAN1 - Enable support for CAN1
+ CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
+ CONFIG_STM32_CAN2 - Enable support for CAN1
+ CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
+ CONFIG_CAN_REGDEBUG - If CONFIG_DEBUG is set, this will generate an
+ dump of all CAN registers.
+
+STM3240G-EVAL-specific Configuration Options
+============================================
+
+ CONFIG_ARCH - Identifies the arch/ subdirectory. This should
+ be set to:
+
+ CONFIG_ARCH=arm
+
+ CONFIG_ARCH_family - For use in C code:
+
+ CONFIG_ARCH_ARM=y
+
+ CONFIG_ARCH_architecture - For use in C code:
+
+ CONFIG_ARCH_CORTEXM4=y
+
+ CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
+
+ CONFIG_ARCH_CHIP=stm32
+
+ CONFIG_ARCH_CHIP_name - For use in C code to identify the exact
+ chip:
+
+ CONFIG_ARCH_CHIP_STM32F407IG=y
+
+ CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG - Enables special STM32 clock
+ configuration features.
+
+ CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=n
+
+ CONFIG_ARCH_BOARD - Identifies the configs subdirectory and
+ hence, the board that supports the particular chip or SoC.
+
+ CONFIG_ARCH_BOARD=stm3240g_eval (for the STM3240G-EVAL development board)
+
+ CONFIG_ARCH_BOARD_name - For use in C code
+
+ CONFIG_ARCH_BOARD_STM3240G_EVAL=y
+
+ CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation
+ of delay loops
+
+ CONFIG_ENDIAN_BIG - define if big endian (default is little
+ endian)
+
+ CONFIG_DRAM_SIZE - Describes the installed DRAM (SRAM in this case):
+
+ CONFIG_DRAM_SIZE=0x00010000 (64Kb)
+
+ CONFIG_DRAM_START - The start address of installed DRAM
+
+ CONFIG_DRAM_START=0x20000000
+
+ CONFIG_DRAM_END - Last address+1 of installed RAM
+
+ CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
+
+ CONFIG_ARCH_IRQPRIO - The STM3240xxx supports interrupt prioritization
+
+ CONFIG_ARCH_IRQPRIO=y
+
+ CONFIG_ARCH_FPU - The STM3240xxx supports a floating point unit (FPU)
+
+ CONFIG_ARCH_FPU=y
+
+ CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to boards that
+ have LEDs
+
+ CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
+ stack. If defined, this symbol is the size of the interrupt
+ stack in bytes. If not defined, the user task stacks will be
+ used during interrupt handling.
+
+ CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
+
+ CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture.
+
+ CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
+ cause a 100 second delay during boot-up. This 100 second delay
+ serves no purpose other than it allows you to calibratre
+ CONFIG_ARCH_LOOPSPERMSEC. You simply use a stop watch to measure
+ the 100 second delay then adjust CONFIG_ARCH_LOOPSPERMSEC until
+ the delay actually is 100 seconds.
+
+ Individual subsystems can be enabled:
+
+ AHB1
+ ----
+ CONFIG_STM32_CRC
+ CONFIG_STM32_BKPSRAM
+ CONFIG_STM32_CCMDATARAM
+ CONFIG_STM32_DMA1
+ CONFIG_STM32_DMA2
+ CONFIG_STM32_ETHMAC
+ CONFIG_STM32_OTGHS
+
+ AHB2
+ ----
+ CONFIG_STM32_DCMI
+ CONFIG_STM32_CRYP
+ CONFIG_STM32_HASH
+ CONFIG_STM32_RNG
+ CONFIG_STM32_OTGFS
+
+ AHB3
+ ----
+ CONFIG_STM32_FSMC
+
+ APB1
+ ----
+ CONFIG_STM32_TIM2
+ CONFIG_STM32_TIM3
+ CONFIG_STM32_TIM4
+ CONFIG_STM32_TIM5
+ CONFIG_STM32_TIM6
+ CONFIG_STM32_TIM7
+ CONFIG_STM32_TIM12
+ CONFIG_STM32_TIM13
+ CONFIG_STM32_TIM14
+ CONFIG_STM32_WWDG
+ CONFIG_STM32_SPI2
+ CONFIG_STM32_SPI3
+ CONFIG_STM32_USART2
+ CONFIG_STM32_USART3
+ CONFIG_STM32_UART4
+ CONFIG_STM32_UART5
+ CONFIG_STM32_I2C1
+ CONFIG_STM32_I2C2
+ CONFIG_STM32_I2C3
+ CONFIG_STM32_CAN1
+ CONFIG_STM32_CAN2
+ CONFIG_STM32_DAC1
+ CONFIG_STM32_DAC2
+ CONFIG_STM32_PWR -- Required for RTC
+
+ APB2
+ ----
+ CONFIG_STM32_TIM1
+ CONFIG_STM32_TIM8
+ CONFIG_STM32_USART1
+ CONFIG_STM32_USART6
+ CONFIG_STM32_ADC1
+ CONFIG_STM32_ADC2
+ CONFIG_STM32_ADC3
+ CONFIG_STM32_SDIO
+ CONFIG_STM32_SPI1
+ CONFIG_STM32_SYSCFG
+ CONFIG_STM32_TIM9
+ CONFIG_STM32_TIM10
+ CONFIG_STM32_TIM11
+
+ Timer and I2C devices may need to the following to force power to be applied
+ unconditionally at power up. (Otherwise, the device is powered when it is
+ initialized).
+
+ CONFIG_STM32_FORCEPOWER
+
+ Timer devices may be used for different purposes. One special purpose is
+ to generate modulated outputs for such things as motor control. If CONFIG_STM32_TIMn
+ is defined (as above) then the following may also be defined to indicate that
+ the timer is intended to be used for pulsed output modulation, ADC conversion,
+ or DAC conversion.
+
+ CONFIG_STM32_TIM1_PWM
+ CONFIG_STM32_TIM2_PWM
+ CONFIG_STM32_TIM3_PWM
+ CONFIG_STM32_TIM4_PWM
+ CONFIG_STM32_TIM5_PWM
+ CONFIG_STM32_TIM8_PWM
+ CONFIG_STM32_TIM9_PWM
+ CONFIG_STM32_TIM10_PWM
+ CONFIG_STM32_TIM11_PWM
+ CONFIG_STM32_TIM12_PWM
+ CONFIG_STM32_TIM13_PWM
+ CONFIG_STM32_TIM14_PWM
+
+ CONFIG_STM32_TIM1_ADC
+ CONFIG_STM32_TIM2_ADC
+ CONFIG_STM32_TIM3_ADC
+ CONFIG_STM32_TIM4_ADC
+ CONFIG_STM32_TIM5_ADC
+ CONFIG_STM32_TIM6_ADC
+ CONFIG_STM32_TIM7_ADC
+ CONFIG_STM32_TIM8_ADC
+
+ CONFIG_STM32_TIM1_DAC
+ CONFIG_STM32_TIM2_DAC
+ CONFIG_STM32_TIM3_DAC
+ CONFIG_STM32_TIM4_DAC
+ CONFIG_STM32_TIM5_DAC
+ CONFIG_STM32_TIM6_DAC
+ CONFIG_STM32_TIM7_DAC
+ CONFIG_STM32_TIM8_DAC
+
+ For each timer that is enabled for PWM usage, we need the following additional
+ configuration settings:
+
+ CONFIG_STM32_TIMx_CHANNEL - Specifies the timer output channel {1,..,4}
+
+ NOTE: The STM32 timers are each capable of generating different signals on
+ each of the four channels with different duty cycles. That capability is
+ not supported by this driver: Only one output channel per timer.
+
+ JTAG Enable settings (by default JTAG-DP and SW-DP are disabled):
+
+ CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
+ CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
+ but without JNTRST.
+ CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled
+
+ STM3240xxx specific device driver settings
+
+ CONFIG_U[S]ARTn_SERIAL_CONSOLE - selects the USARTn (n=1,2,3) or UART
+ m (m=4,5) for the console and ttys0 (default is the USART1).
+ CONFIG_U[S]ARTn_RXBUFSIZE - Characters are buffered as received.
+ This specific the size of the receive buffer
+ CONFIG_U[S]ARTn_TXBUFSIZE - Characters are buffered before
+ being sent. This specific the size of the transmit buffer
+ CONFIG_U[S]ARTn_BAUD - The configure BAUD of the UART. Must be
+ CONFIG_U[S]ARTn_BITS - The number of bits. Must be either 7 or 8.
+ CONFIG_U[S]ARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
+ CONFIG_U[S]ARTn_2STOP - Two stop bits
+
+ CONFIG_STM32_SPI_INTERRUPTS - Select to enable interrupt driven SPI
+ support. Non-interrupt-driven, poll-waiting is recommended if the
+ interrupt rate would be to high in the interrupt driven case.
+ CONFIG_STM32_SPI_DMA - Use DMA to improve SPI transfer performance.
+ Cannot be used with CONFIG_STM32_SPI_INTERRUPT.
+
+ CONFIG_SDIO_DMA - Support DMA data transfers. Requires CONFIG_STM32_SDIO
+ and CONFIG_STM32_DMA2.
+ CONFIG_SDIO_PRI - Select SDIO interrupt prority. Default: 128
+ CONFIG_SDIO_DMAPRIO - Select SDIO DMA interrupt priority.
+ Default: Medium
+ CONFIG_SDIO_WIDTH_D1_ONLY - Select 1-bit transfer mode. Default:
+ 4-bit transfer mode.
+
+ CONFIG_STM32_PHYADDR - The 5-bit address of the PHY on the board
+ CONFIG_STM32_MII - Support Ethernet MII interface
+ CONFIG_STM32_MII_MCO1 - Use MCO1 to clock the MII interface
+ CONFIG_STM32_MII_MCO2 - Use MCO2 to clock the MII interface
+ CONFIG_STM32_RMII - Support Ethernet RMII interface
+ CONFIG_STM32_AUTONEG - Use PHY autonegotion to determine speed and mode
+ CONFIG_STM32_ETHFD - If CONFIG_STM32_AUTONEG is not defined, then this
+ may be defined to select full duplex mode. Default: half-duplex
+ CONFIG_STM32_ETH100MBPS - If CONFIG_STM32_AUTONEG is not defined, then this
+ may be defined to select 100 MBps speed. Default: 10 Mbps
+ CONFIG_STM32_PHYSR - This must be provided if CONFIG_STM32_AUTONEG is
+ defined. The PHY status register address may diff from PHY to PHY. This
+ configuration sets the address of the PHY status register.
+ CONFIG_STM32_PHYSR_SPEED - This must be provided if CONFIG_STM32_AUTONEG is
+ defined. This provides bit mask indicating 10 or 100MBps speed.
+ CONFIG_STM32_PHYSR_100MBPS - This must be provided if CONFIG_STM32_AUTONEG is
+ defined. This provides the value of the speed bit(s) indicating 100MBps speed.
+ CONFIG_STM32_PHYSR_MODE - This must be provided if CONFIG_STM32_AUTONEG is
+ defined. This provide bit mask indicating full or half duplex modes.
+ CONFIG_STM32_PHYSR_FULLDUPLEX - This must be provided if CONFIG_STM32_AUTONEG is
+ defined. This provides the value of the mode bits indicating full duplex mode.
+ CONFIG_STM32_ETH_PTP - Precision Time Protocol (PTP). Not supported
+ but some hooks are indicated with this condition.
+
+ STM3240G-EVAL CAN Configuration
+
+ CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
+ CONFIG_STM32_CAN2 must also be defined)
+ CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
+ Default: 8
+ CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
+ Default: 4
+ CONFIG_CAN_LOOPBACK - A CAN driver may or may not support a loopback
+ mode for testing. The STM32 CAN driver does support loopback mode.
+ CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
+ CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
+ CONFIG_CAN_REGDEBUG - If CONFIG_DEBUG is set, this will generate an
+ dump of all CAN registers.
+
+ STM3240G-EVAL LCD Hardware Configuration
+
+Configurations
+==============
+
+Each STM3240G-EVAL configuration is maintained in a sudirectory and
+can be selected as follow:
+
+ cd tools
+ ./configure.sh stm3240g-eval/<subdir>
+ cd -
+ . ./setenv.sh
+
+Where <subdir> is one of the following:
+
+ dhcpd:
+ -----
+
+ This builds the DCHP server using the apps/examples/dhcpd application
+ (for execution from FLASH.) See apps/examples/README.txt for information
+ about the dhcpd example. The server address is 10.0.0.1 and it serves
+ IP addresses in the range 10.0.0.2 through 10.0.0.17 (all of which, of
+ course, are configurable).
+
+ CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows
+
+ nettest:
+ -------
+
+ This configuration directory may be used to verify networking performance
+ using the STM32's Ethernet controller. It uses apps/examples/nettest to excercise the
+ TCP/IP network.
+
+ CONFIG_EXAMPLE_NETTEST_SERVER=n : Target is configured as the client
+ CONFIG_EXAMPLE_NETTEST_PERFORMANCE=y : Only network performance is verified.
+ CONFIG_EXAMPLE_NETTEST_IPADDR=(10<<24|0<<16|0<<8|2) : Target side is IP: 10.0.0.2
+ CONFIG_EXAMPLE_NETTEST_DRIPADDR=(10<<24|0<<16|0<<8|1) : Host side is IP: 10.0.0.1
+ CONFIG_EXAMPLE_NETTEST_CLIENTIP=(10<<24|0<<16|0<<8|1) : Server address used by which ever is client.
+
+ ostest:
+ ------
+ This configuration directory, performs a simple OS test using
+ examples/ostest. By default, this project assumes that you are
+ using the DFU bootloader.
+
+ CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows
+
+ nsh:
+ ---
+ Configures the NuttShell (nsh) located at apps/examples/nsh. The
+ Configuration enables both the serial and telnet NSH interfaces.
+
+ CONFIG_STM32_CODESOURCERYW=y : CodeSourcery under Windows
+ CONFIG_NSH_DHCPC=n : DHCP is disabled
+ CONFIG_NSH_IPADDR=(10<<24|0<<16|0<<8|2) : Target IP address 10.0.0.2
+ CONFIG_NSH_DRIPADDR=(10<<24|0<<16|0<<8|1) : Host IP address 10.0.0.1
+
+ NOTE: This example assumes that a network is connected. During its
+ initialization, it will try to negotiate the link speed. If you have
+ no network connected when you reset the board, there will be a long
+ delay (maybe 30 seconds?) before anything happens. That is the timeout
+ before the networking finally gives up and decides that no network is
+ available.
diff --git a/nuttx/configs/px4fmu/common/Make.defs b/nuttx/configs/px4fmu/common/Make.defs
new file mode 100644
index 000000000..00a489eab
--- /dev/null
+++ b/nuttx/configs/px4fmu/common/Make.defs
@@ -0,0 +1,216 @@
+############################################################################
+# configs/px4fmu/common/Make.defs
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+#
+# Generic Make.defs for the PX4FMU
+# Do not specify/use this file directly - it is included by config-specific
+# Make.defs in the per-config directories.
+#
+
+#
+# We only support building with the ARM bare-metal toolchain from
+# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
+#
+
+CROSSDEV = arm-none-eabi-
+
+CC = $(CROSSDEV)gcc
+CXX = $(CROSSDEV)g++
+CPP = $(CROSSDEV)gcc -E
+LD = $(CROSSDEV)ld
+AR = $(CROSSDEV)ar rcs
+NM = $(CROSSDEV)nm
+OBJCOPY = $(CROSSDEV)objcopy
+OBJDUMP = $(CROSSDEV)objdump
+
+MAXOPTIMIZATION = -O3
+ARCHCPUFLAGS = -mcpu=cortex-m4 \
+ -mthumb \
+ -march=armv7e-m \
+ -mfpu=fpv4-sp-d16 \
+ -mfloat-abi=hard
+
+
+# enable precise stack overflow tracking
+INSTRUMENTATIONDEFINES = -finstrument-functions \
+ -ffixed-r10
+
+# pull in *just* libm from the toolchain ... this is grody
+LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}"
+EXTRA_LIBS += $(LIBM)
+
+# use our linker script
+LDSCRIPT = ld.script
+
+ifeq ($(WINTOOL),y)
+ # Windows-native toolchains
+ DIRLINK = $(TOPDIR)/tools/winlink.sh
+ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
+ MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
+ ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
+ ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT)}"
+else
+ ifeq ($(PX4_WINTOOL),y)
+ # Windows-native toolchains (MSYS)
+ DIRLINK = $(TOPDIR)/tools/winlink.sh
+ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
+ MKDEP = $(TOPDIR)/tools/mknulldeps.sh
+ ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
+ ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT)
+ else
+ # Linux/Cygwin-native toolchain
+ MKDEP = $(TOPDIR)/tools/mkdeps.sh
+ ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
+ ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
+ ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT)
+ endif
+endif
+
+# tool versions
+ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
+ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
+
+# optimisation flags
+ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
+ -fno-strict-aliasing \
+ -fno-strength-reduce \
+ -fomit-frame-pointer \
+ -funsafe-math-optimizations \
+ -fno-builtin-printf \
+ -ffunction-sections \
+ -fdata-sections
+
+ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
+ARCHOPTIMIZATION += -g
+ARCHSCRIPT += -g
+endif
+
+ARCHCFLAGS = -std=gnu99
+ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
+ARCHWARNINGS = -Wall \
+ -Wextra \
+ -Wdouble-promotion \
+ -Wshadow \
+ -Wfloat-equal \
+ -Wframe-larger-than=1024 \
+ -Wpointer-arith \
+ -Wlogical-op \
+ -Wmissing-declarations \
+ -Wpacked \
+ -Wno-unused-parameter
+# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
+# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
+# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
+
+ARCHCWARNINGS = $(ARCHWARNINGS) \
+ -Wbad-function-cast \
+ -Wstrict-prototypes \
+ -Wold-style-declaration \
+ -Wmissing-parameter-type \
+ -Wmissing-prototypes \
+ -Wnested-externs \
+ -Wunsuffixed-float-constants
+ARCHWARNINGSXX = $(ARCHWARNINGS)
+ARCHDEFINES =
+ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
+
+# this seems to be the only way to add linker flags
+ARCHSCRIPT += --warn-common \
+ --gc-sections
+
+CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
+CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
+CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
+CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
+CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
+AFLAGS = $(CFLAGS) -D__ASSEMBLY__
+
+NXFLATLDFLAGS1 = -r -d -warn-common
+NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
+LDNXFLATFLAGS = -e main -s 2048
+
+OBJEXT = .o
+LIBEXT = .a
+EXEEXT =
+
+# If VERBOSE is set, don't hide the compiler invocations.
+ifeq ($(VERBOSE),YES)
+_v =
+else
+_v = @
+endif
+
+define PREPROCESS
+ @echo "CPP: $1->$2"
+ @$(CPP) $(CPPFLAGS) $(abspath $1) -o $2
+endef
+
+define COMPILE
+ @echo "CC: $1"
+ $(_v)$(CC) -c $(CFLAGS) $(abspath $1) -o $2
+endef
+
+define COMPILEXX
+ @echo "CXX: $1"
+ $(_v)$(CXX) -c $(CXXFLAGS) $(abspath $1) -o $2
+endef
+
+define ASSEMBLE
+ @echo "AS: $1"
+ $(_v)$(CC) -c $(AFLAGS) $(abspath $1) -o $2
+endef
+
+# produce partially-linked $1 from files in $2
+define PRELINK
+ @echo "PRELINK: $1"
+ @$(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
+endef
+
+define ARCHIVE
+ echo "AR: $2"; \
+ $(AR) $1 $2 || { echo "$(AR) $1 $2 FAILED!" ; exit 1 ; }
+endef
+
+define CLEAN
+ @rm -f *.o *.a
+endef
+
+HOSTCC = gcc
+HOSTINCLUDES = -I.
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
+HOSTLDFLAGS =
+
diff --git a/nuttx/configs/px4fmu/common/ld.script b/nuttx/configs/px4fmu/common/ld.script
new file mode 100644
index 000000000..e3ca771b1
--- /dev/null
+++ b/nuttx/configs/px4fmu/common/ld.script
@@ -0,0 +1,133 @@
+/****************************************************************************
+ * configs/px4fmu/common/ld.script
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/* The STM32F405 has 1024Kb of FLASH beginning at address 0x0800:0000 and
+ * 192Kb of SRAM. SRAM is split up into three blocks:
+ *
+ * 1) 112Kb of SRAM beginning at address 0x2000:0000
+ * 2) 16Kb of SRAM beginning at address 0x2001:c000
+ * 3) 64Kb of TCM SRAM beginning at address 0x1000:0000
+ *
+ * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
+ * where the code expects to begin execution by jumping to the entry point in
+ * the 0x0800:0000 address range.
+ *
+ * The first 0x4000 of flash is reserved for the bootloader.
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x08004000, LENGTH = 1008K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
+ ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K
+}
+
+OUTPUT_ARCH(arm)
+
+ENTRY(__start) /* treat __start as the anchor for dead code stripping */
+EXTERN(_vectors) /* force the vectors to be included in the output */
+
+/*
+ * Ensure that abort() is present in the final object. The exception handling
+ * code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
+ */
+EXTERN(abort)
+
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+
+ /*
+ * This is a hack to make the newlib libm __errno() call
+ * use the NuttX get_errno_ptr() function.
+ */
+ __errno = get_errno_ptr;
+ } > flash
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > flash
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > flash
+ __exidx_end = ABSOLUTE(.);
+
+ _eronly = ABSOLUTE(.);
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* 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) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/nuttx/configs/px4fmu/include/board.h b/nuttx/configs/px4fmu/include/board.h
new file mode 100755
index 000000000..0db8580ba
--- /dev/null
+++ b/nuttx/configs/px4fmu/include/board.h
@@ -0,0 +1,392 @@
+/************************************************************************************
+ * configs/px4fmu/include/board.h
+ * include/arch/board/board.h
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_BOARD_BOARD_H
+#define __ARCH_BOARD_BOARD_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+#endif
+//#include "stm32_rcc.h"
+//#include "stm32_sdio.h"
+//#include "stm32_internal.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Clocking *************************************************************************/
+/* The PX4FMU uses a 24MHz crystal connected to the HSE.
+ *
+ * This is the "standard" configuration as set up by arch/arm/src/stm32f40xx_rcc.c:
+ * System Clock source : PLL (HSE)
+ * SYSCLK(Hz) : 168000000 Determined by PLL configuration
+ * HCLK(Hz) : 168000000 (STM32_RCC_CFGR_HPRE)
+ * AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE)
+ * APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1)
+ * APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2)
+ * HSE Frequency(Hz) : 24000000 (STM32_BOARD_XTAL)
+ * PLLM : 24 (STM32_PLLCFG_PLLM)
+ * PLLN : 336 (STM32_PLLCFG_PLLN)
+ * PLLP : 2 (STM32_PLLCFG_PLLP)
+ * PLLQ : 7 (STM32_PLLCFG_PPQ)
+ * Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK
+ * Flash Latency(WS) : 5
+ * Prefetch Buffer : OFF
+ * Instruction cache : ON
+ * Data cache : ON
+ * Require 48MHz for USB OTG FS, : Enabled
+ * SDIO and RNG clock
+ */
+
+/* HSI - 16 MHz RC factory-trimmed
+ * LSI - 32 KHz RC
+ * HSE - On-board crystal frequency is 24MHz
+ * LSE - not installed
+ */
+
+#define STM32_BOARD_XTAL 24000000ul
+
+#define STM32_HSI_FREQUENCY 16000000ul
+#define STM32_LSI_FREQUENCY 32000
+#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
+//#define STM32_LSE_FREQUENCY 32768
+
+/* Main PLL Configuration.
+ *
+ * PLL source is HSE
+ * PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN
+ * = (25,000,000 / 25) * 336
+ * = 336,000,000
+ * SYSCLK = PLL_VCO / PLLP
+ * = 336,000,000 / 2 = 168,000,000
+ * USB OTG FS, SDIO and RNG Clock
+ * = PLL_VCO / PLLQ
+ * = 48,000,000
+ */
+
+#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(24)
+#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336)
+#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2
+#define STM32_PLLCFG_PPQ RCC_PLLCFG_PLLQ(7)
+
+#define STM32_SYSCLK_FREQUENCY 168000000ul
+
+/* AHB clock (HCLK) is SYSCLK (168MHz) */
+
+#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */
+#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY
+#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
+
+/* APB1 clock (PCLK1) is HCLK/4 (42MHz) */
+
+#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */
+#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4)
+
+/* Timers driven from APB1 will be twice PCLK1 */
+
+#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY)
+
+/* APB2 clock (PCLK2) is HCLK/2 (84MHz) */
+
+#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */
+#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2)
+
+/* Timers driven from APB2 will be twice PCLK2 */
+
+#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK1_FREQUENCY)
+
+/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx
+ * otherwise frequency is 2xAPBx.
+ * Note: TIM1,8 are on APB2, others on APB1
+ */
+
+#define STM32_TIM18_FREQUENCY (2*STM32_PCLK2_FREQUENCY)
+#define STM32_TIM27_FREQUENCY (2*STM32_PCLK1_FREQUENCY)
+
+/* SDIO dividers. Note that slower clocking is required when DMA is disabled
+ * in order to avoid RX overrun/TX underrun errors due to delayed responses
+ * to service FIFOs in interrupt driven mode. These values have not been
+ * tuned!!!
+ *
+ * HCLK=72MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(178+2)=400 KHz
+ */
+
+#define SDIO_INIT_CLKDIV (178 << SDIO_CLKCR_CLKDIV_SHIFT)
+
+/* DMA ON: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(2+2)=18 MHz
+ * DMA OFF: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(3+2)=14.4 MHz
+ */
+
+#ifdef CONFIG_SDIO_DMA
+# define SDIO_MMCXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT)
+#else
+# define SDIO_MMCXFR_CLKDIV (3 << SDIO_CLKCR_CLKDIV_SHIFT)
+#endif
+
+/* DMA ON: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(1+2)=24 MHz
+ * DMA OFF: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(3+2)=14.4 MHz
+ */
+
+#ifdef CONFIG_SDIO_DMA
+# define SDIO_SDXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT)
+#else
+# define SDIO_SDXFR_CLKDIV (3 << SDIO_CLKCR_CLKDIV_SHIFT)
+#endif
+
+/* High-resolution timer
+ */
+#ifdef CONFIG_HRT_TIMER
+# define HRT_TIMER 1 /* use timer1 for the HRT */
+# define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
+#endif
+
+/* LED definitions ******************************************************************/
+/* PX4 has two LEDs that we will encode as: */
+
+#define LED_STARTED 0 /* LED? */
+#define LED_HEAPALLOCATE 1 /* LED? */
+#define LED_IRQSENABLED 2 /* LED? + LED? */
+#define LED_STACKCREATED 3 /* LED? */
+#define LED_INIRQ 4 /* LED? + LED? */
+#define LED_SIGNAL 5 /* LED? + LED? */
+#define LED_ASSERTION 6 /* LED? + LED? + LED? */
+#define LED_PANIC 7 /* N/C + N/C + N/C + LED? */
+
+/* Alternate function pin selections ************************************************/
+
+/*
+ * UARTs.
+ *
+ * Note that UART5 has no optional pinout.
+ */
+#define GPIO_USART1_RX GPIO_USART1_RX_2
+#define GPIO_USART1_TX GPIO_USART1_TX_2
+
+#define GPIO_USART2_RX GPIO_USART2_RX_1
+#define GPIO_USART2_TX GPIO_USART2_TX_1
+#define GPIO_USART2_RTS GPIO_USART2_RTS_1
+#define GPIO_USART2_CTS GPIO_USART2_CTS_1
+
+#define GPIO_USART6_RX GPIO_USART6_RX_1
+#define GPIO_USART6_TX GPIO_USART6_TX_1
+
+/* UART DMA configuration for USART1/6 */
+#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2
+#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2
+
+/*
+ * PWM
+ *
+ * Four PWM outputs can be configured on pins otherwise shared with
+ * USART2; two can take the flow control pins if they are not being used.
+ *
+ * Pins:
+ *
+ * CTS - PA0 - TIM2CH1
+ * RTS - PA1 - TIM2CH2
+ * TX - PA2 - TIM2CH3
+ * RX - PA3 - TIM2CH4
+ *
+ */
+#define GPIO_TIM2_CH1OUT GPIO_TIM2_CH1OUT_1
+#define GPIO_TIM2_CH2OUT GPIO_TIM2_CH2OUT_1
+#define GPIO_TIM2_CH3OUT GPIO_TIM2_CH3OUT_1
+#define GPIO_TIM2_CH4OUT GPIO_TIM2_CH4OUT_1
+
+/*
+ * PPM
+ *
+ * PPM input is handled by the HRT timer.
+ */
+#if defined(CONFIG_HRT_TIMER) && defined (CONFIG_HRT_PPM)
+# define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */
+# define GPIO_PPM_IN (GPIO_ALT|GPIO_AF1|GPIO_SPEED_50MHz|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN10)
+#endif
+
+/*
+ * CAN
+ *
+ * CAN2 is routed to the expansion connector.
+ */
+
+#define GPIO_CAN2_RX GPIO_CAN2_RX_2
+#define GPIO_CAN2_TX GPIO_CAN2_TX_2
+
+/*
+ * I2C
+ */
+#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2
+#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2
+
+#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1
+#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1
+
+#define GPIO_I2C3_SCL GPIO_I2C3_SCL_1
+#define GPIO_I2C3_SDA GPIO_I2C3_SDA_1
+
+/*
+ * I2C busses
+ */
+#define PX4_I2C_BUS_ESC 1
+#define PX4_I2C_BUS_ONBOARD 2
+#define PX4_I2C_BUS_EXPANSION 3
+
+/*
+ * Devices on the onboard bus.
+ *
+ * Note that these are unshifted addresses.
+ */
+#define PX4_I2C_OBDEV_HMC5883 0x1e
+#define PX4_I2C_OBDEV_MS5611 NOTDEFINED
+#define PX4_I2C_OBDEV_EEPROM 0x50
+
+#define PX4_I2C_OBDEV_PX4IO_BL 0x18
+#define PX4_I2C_OBDEV_PX4IO 0x19
+
+/*
+ * SPI
+ */
+#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1
+#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1
+#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1
+
+#define GPIO_SPI3_MISO GPIO_SPI3_MISO_2
+#define GPIO_SPI3_MOSI GPIO_SPI3_MOSI_1
+#define GPIO_SPI3_SCK GPIO_SPI3_SCK_2
+#define GPIO_SPI3_NSS GPIO_SPI3_NSS_2
+
+/*
+ * Use these in place of the spi_dev_e enumeration to
+ * select a specific SPI device on SPI1
+ */
+#define PX4_SPIDEV_GYRO 1
+#define PX4_SPIDEV_ACCEL 2
+#define PX4_SPIDEV_MPU 3
+
+/*
+ * Tone alarm output
+ */
+#ifdef CONFIG_TONE_ALARM
+# define TONE_ALARM_TIMER 3 /* timer 3 */
+# define TONE_ALARM_CHANNEL 3 /* channel 3 */
+# define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN8)
+#endif
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+EXTERN void stm32_boardinitialize(void);
+
+/************************************************************************************
+ * Button support.
+ *
+ * Description:
+ * up_buttoninit() must be called to initialize button resources. After
+ * that, up_buttons() may be called to collect the current state of all
+ * buttons or up_irqbutton() may be called to register button interrupt
+ * handlers.
+ *
+ * After up_buttoninit() has been called, up_buttons() may be called to
+ * collect the state of all buttons. up_buttons() returns an 8-bit bit set
+ * with each bit associated with a button. See the BUTTON_*_BIT
+ * definitions in board.h for the meaning of each bit.
+ *
+ * up_irqbutton() may be called to register an interrupt handler that will
+ * be called when a button is depressed or released. The ID value is a
+ * button enumeration value that uniquely identifies a button resource. See the
+ * BUTTON_* definitions in board.h for the meaning of enumeration
+ * value. The previous interrupt handler address is returned (so that it may
+ * restored, if so desired).
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_ARCH_BUTTONS
+EXTERN void up_buttoninit(void);
+EXTERN uint8_t up_buttons(void);
+#ifdef CONFIG_ARCH_IRQBUTTONS
+EXTERN xcpt_t up_irqbutton(int id, xcpt_t irqhandler);
+#endif
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_BOARD_BOARD_H */
diff --git a/nuttx/configs/px4fmu/include/drv_bma180.h b/nuttx/configs/px4fmu/include/drv_bma180.h
new file mode 100644
index 000000000..a403415e4
--- /dev/null
+++ b/nuttx/configs/px4fmu/include/drv_bma180.h
@@ -0,0 +1,99 @@
+/*
+ * Copyright (C) 2012 Lorenz Meier. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name of the author or the names of contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/*
+ * Driver for the BOSCH BMA180 MEMS accelerometer
+ */
+
+/* IMPORTANT NOTES:
+ *
+ * SPI max. clock frequency: 25 Mhz
+ * CS has to be high before transfer,
+ * go low right before transfer and
+ * go high again right after transfer
+ *
+ */
+
+#include <sys/ioctl.h>
+
+#define _BMA180BASE 0x6300
+#define BMA180C(_x) _IOC(_BMA180BASE, _x)
+
+/*
+ * Sets the sensor internal sampling rate, and if a buffer
+ * has been configured, the rate at which entries will be
+ * added to the buffer.
+ */
+#define BMA180_SETRATE BMA180C(1)
+
+#define BMA180_RATE_LP_10HZ (0<<4)
+#define BMA180_RATE_LP_20HZ (1<<4)
+#define BMA180_RATE_LP_40HZ (2<<4)
+#define BMA180_RATE_LP_75HZ (3<<4)
+#define BMA180_RATE_LP_150HZ (4<<4)
+#define BMA180_RATE_LP_300HZ (5<<4)
+#define BMA180_RATE_LP_600HZ (6<<4)
+#define BMA180_RATE_LP_1200HZ (7<<4)
+
+/*
+ * Sets the sensor internal range.
+ */
+#define BMA180_SETRANGE BMA180C(2)
+
+#define BMA180_RANGE_1G (0<<1)
+#define BMA180_RANGE_1_5G (1<<1)
+#define BMA180_RANGE_2G (2<<1)
+#define BMA180_RANGE_3G (3<<1)
+#define BMA180_RANGE_4G (4<<1)
+#define BMA180_RANGE_8G (5<<1)
+#define BMA180_RANGE_16G (6<<1)
+
+/*
+ * Sets the address of a shared BMA180_buffer
+ * structure that is maintained by the driver.
+ *
+ * If zero is passed as the address, disables
+ * the buffer updating.
+ */
+#define BMA180_SETBUFFER BMA180C(3)
+
+struct bma180_buffer {
+ uint32_t size; /* number of entries in the samples[] array */
+ uint32_t next; /* the next entry that will be populated */
+ struct {
+ uint16_t x;
+ uint16_t y;
+ uint16_t z;
+ uint8_t temp;
+ } samples[];
+};
+
+extern int bma180_attach(struct spi_dev_s *spi, int spi_id);
diff --git a/nuttx/configs/px4fmu/include/drv_eeprom.h b/nuttx/configs/px4fmu/include/drv_eeprom.h
new file mode 100644
index 000000000..e6801f6c4
--- /dev/null
+++ b/nuttx/configs/px4fmu/include/drv_eeprom.h
@@ -0,0 +1,73 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * Driver for the ST MS5611 gyroscope
+ */
+
+/* IMPORTANT NOTES:
+ *
+ * SPI max. clock frequency: 10 Mhz
+ * CS has to be high before transfer,
+ * go low right before transfer and
+ * go high again right after transfer
+ *
+ */
+
+/* IMPORTANT: Adjust this number! */
+#define MAX_EEPROMS 2
+
+/* FMU onboard */
+#define FMU_ONBOARD_EEPROM_ADDRESS 0x50
+#define FMU_ONBOARD_EEPROM_TOTAL_SIZE_BYTES 16000
+#define FMU_ONBOARD_EEPROM_PAGE_SIZE_BYTES 64
+#define FMU_ONBOARD_EEPROM_PAGE_WRITE_TIME_US 5500
+#define FMU_ONBOARD_EEPROM_BUS_CLOCK 1000000 ///< 1 Mhz max. clock
+
+#define FMU_BASEBOARD_EEPROM_ADDRESS 0x57
+#define FMU_BASEBOARD_EEPROM_TOTAL_SIZE_BYTES 128
+#define FMU_BASEBOARD_EEPROM_PAGE_SIZE_BYTES 8
+#define FMU_BASEBOARD_EEPROM_PAGE_WRITE_TIME_US 3300
+#define FMU_BASEBOARD_EEPROM_BUS_CLOCK 400000 ///< 400 KHz max. clock
+
+/**
+ * @brief i2c I2C bus struct
+ * @brief device_address The device address as stated in the datasheet, e.g. for a Microchip 24XX128 0x50 with all ID pins tied to GND
+ * @brief total_size_bytes The total size in bytes, e.g. 16K = 16000 bytes for the Microchip 24XX128
+ * @brief page_size_bytes The size of one page, e.g. 64 bytes for the Microchip 24XX128
+ * @brief device_name The device name to register this device to, e.g. /dev/eeprom
+ * @brief fail_if_missing Returns error if the EEPROM was not found. This is helpful if the EEPROM might be attached later when the board is running
+ */
+extern int
+eeprom_attach(struct i2c_dev_s *i2c, uint8_t device_address, uint16_t total_size_bytes, uint16_t page_size_bytes, uint16_t page_write_time_us, const char* device_name, uint8_t fail_if_missing);
+
diff --git a/nuttx/configs/px4fmu/include/drv_gpio.h b/nuttx/configs/px4fmu/include/drv_gpio.h
new file mode 100644
index 000000000..22f80d038
--- /dev/null
+++ b/nuttx/configs/px4fmu/include/drv_gpio.h
@@ -0,0 +1,107 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file GPIO driver interface.
+ *
+ * This header defines the basic interface to platform-specific GPIOs.
+ */
+
+#ifndef _BOARD_DRV_GPIO_H
+#define _BOARD_DRV_GPIO_H
+
+/*
+ * PX4FMU GPIO numbers.
+ *
+ * For shared pins, alternate function 1 selects the non-GPIO mode
+ * (USART2, CAN2, etc.)
+ */
+#define GPIO_EXT_1 (1<<0) /**< high-power GPIO 1 */
+#define GPIO_EXT_2 (1<<1) /**< high-power GPIO 1 */
+#define GPIO_MULTI_1 (1<<2) /**< USART2 CTS */
+#define GPIO_MULTI_2 (1<<3) /**< USART2 RTS */
+#define GPIO_MULTI_3 (1<<4) /**< USART2 TX */
+#define GPIO_MULTI_4 (1<<5) /**< USART2 RX */
+#define GPIO_CAN_TX (1<<6) /**< CAN2 TX */
+#define GPIO_CAN_RX (1<<7) /**< CAN2 RX */
+
+/**
+ * Default GPIO device - other devices may also support this protocol if
+ * they also export GPIO-like things. This is always the GPIOs on the
+ * main board.
+ */
+#define GPIO_DEVICE_PATH "/dev/gpio"
+
+/*
+ * IOCTL definitions.
+ *
+ * For all ioctls, the (arg) argument is a bitmask of GPIOs to be affected
+ * by the operation, with the LSB being the lowest-numbered GPIO.
+ *
+ * Note that there may be board-specific relationships between GPIOs;
+ * applications using GPIOs should be aware of this.
+ */
+#define _GPIOCBASE 0x6700
+#define GPIOC(_x) _IOC(_GPIOCBASE, _x)
+
+/** reset all board GPIOs to their default state */
+#define GPIO_RESET GPIOC(0)
+
+/** configure the board GPIOs in (arg) as outputs */
+#define GPIO_SET_OUTPUT GPIOC(1)
+
+/** configure the board GPIOs in (arg) as inputs */
+#define GPIO_SET_INPUT GPIOC(2)
+
+/** configure the board GPIOs in (arg) for the first alternate function (if supported) */
+#define GPIO_SET_ALT_1 GPIOC(3)
+
+/** configure the board GPIO (arg) for the second alternate function (if supported) */
+#define GPIO_SET_ALT_2 GPIOC(4)
+
+/** configure the board GPIO (arg) for the third alternate function (if supported) */
+#define GPIO_SET_ALT_3 GPIOC(5)
+
+/** configure the board GPIO (arg) for the fourth alternate function (if supported) */
+#define GPIO_SET_ALT_4 GPIOC(6)
+
+/** set the GPIOs in (arg) */
+#define GPIO_SET GPIOC(10)
+
+/** clear the GPIOs in (arg) */
+#define GPIO_CLEAR GPIOC(11)
+
+/** read all the GPIOs and return their values in *(uint32_t *)arg */
+#define GPIO_GET GPIOC(12)
+
+#endif /* _DRV_GPIO_H */
diff --git a/nuttx/configs/px4fmu/include/drv_hmc5883l.h b/nuttx/configs/px4fmu/include/drv_hmc5883l.h
new file mode 100644
index 000000000..8dc9b8a93
--- /dev/null
+++ b/nuttx/configs/px4fmu/include/drv_hmc5883l.h
@@ -0,0 +1,100 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * Driver for the ST HMC5883L gyroscope
+ */
+
+/* IMPORTANT NOTES:
+ *
+ * SPI max. clock frequency: 10 Mhz
+ * CS has to be high before transfer,
+ * go low right before transfer and
+ * go high again right after transfer
+ *
+ */
+
+#include <sys/ioctl.h>
+
+#define _HMC5883LBASE 0x6100
+#define HMC5883LC(_x) _IOC(_HMC5883LBASE, _x)
+
+/*
+ * Sets the sensor internal sampling rate, and if a buffer
+ * has been configured, the rate at which entries will be
+ * added to the buffer.
+ */
+#define HMC5883L_SETRATE HMC5883LC(1)
+
+/* set rate (configuration A register */
+#define HMC5883L_RATE_0_75HZ (0 << 2) /* 0.75 Hz */
+#define HMC5883L_RATE_1_50HZ (1 << 2) /* 1.5 Hz */
+#define HMC5883L_RATE_3_00HZ (2 << 2) /* 3 Hz */
+#define HMC5883L_RATE_7_50HZ (3 << 2) /* 7.5 Hz */
+#define HMC5883L_RATE_15HZ (4 << 2) /* 15 Hz (default) */
+#define HMC5883L_RATE_30HZ (5 << 2) /* 30 Hz */
+#define HMC5883L_RATE_75HZ (6 << 2) /* 75 Hz */
+
+/*
+ * Sets the sensor internal range.
+ */
+#define HMC5883L_SETRANGE HMC5883LC(2)
+
+#define HMC5883L_RANGE_0_88GA (0 << 5)
+#define HMC5883L_RANGE_1_33GA (1 << 5)
+#define HMC5883L_RANGE_1_90GA (2 << 5)
+#define HMC5883L_RANGE_2_50GA (3 << 5)
+#define HMC5883L_RANGE_4_00GA (4 << 5)
+
+/*
+ * Sets the address of a shared HMC5883L_buffer
+ * structure that is maintained by the driver.
+ *
+ * If zero is passed as the address, disables
+ * the buffer updating.
+ */
+#define HMC5883L_SETBUFFER HMC5883LC(3)
+
+struct hmc5883l_buffer {
+ uint32_t size; /* number of entries in the samples[] array */
+ uint32_t next; /* the next entry that will be populated */
+ struct {
+ int16_t x;
+ int16_t y;
+ int16_t z;
+ } samples[];
+};
+
+#define HMC5883L_RESET HMC5883LC(4)
+
+extern int hmc5883l_attach(struct i2c_dev_s *i2c);
diff --git a/nuttx/configs/px4fmu/include/drv_l3gd20.h b/nuttx/configs/px4fmu/include/drv_l3gd20.h
new file mode 100644
index 000000000..3b284d60d
--- /dev/null
+++ b/nuttx/configs/px4fmu/include/drv_l3gd20.h
@@ -0,0 +1,108 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+/*
+ * Driver for the ST L3GD20 gyroscope
+ */
+
+/* IMPORTANT NOTES:
+ *
+ * SPI max. clock frequency: 10 Mhz
+ * CS has to be high before transfer,
+ * go low right before transfer and
+ * go high again right after transfer
+ *
+ */
+
+#include <sys/ioctl.h>
+
+#define _L3GD20BASE 0x6200
+#define L3GD20C(_x) _IOC(_L3GD20BASE, _x)
+
+/*
+ * Sets the sensor internal sampling rate, and if a buffer
+ * has been configured, the rate at which entries will be
+ * added to the buffer.
+ */
+#define L3GD20_SETRATE L3GD20C(1)
+
+#define L3GD20_RATE_95HZ_LP_12_5HZ ((0<<7) | (0<<6) | (0<<5) | (0<<4))
+#define L3GD20_RATE_95HZ_LP_25HZ ((0<<7) | (0<<6) | (0<<5) | (1<<4))
+#define L3GD20_RATE_190HZ_LP_12_5HZ ((0<<7) | (1<<6) | (0<<5) | (0<<4))
+#define L3GD20_RATE_190HZ_LP_25HZ ((0<<7) | (1<<6) | (0<<5) | (1<<4))
+#define L3GD20_RATE_190HZ_LP_50HZ ((0<<7) | (1<<6) | (1<<5) | (0<<4))
+#define L3GD20_RATE_190HZ_LP_70HZ ((0<<7) | (1<<6) | (1<<5) | (1<<4))
+#define L3GD20_RATE_380HZ_LP_20HZ ((1<<7) | (0<<6) | (0<<5) | (0<<4))
+#define L3GD20_RATE_380HZ_LP_25HZ ((1<<7) | (0<<6) | (0<<5) | (1<<4))
+#define L3GD20_RATE_380HZ_LP_50HZ ((1<<7) | (0<<6) | (1<<5) | (0<<4))
+#define L3GD20_RATE_380HZ_LP_100HZ ((1<<7) | (0<<6) | (1<<5) | (1<<4))
+#define L3GD20_RATE_760HZ_LP_30HZ ((1<<7) | (1<<6) | (0<<5) | (0<<4))
+#define L3GD20_RATE_760HZ_LP_35HZ ((1<<7) | (1<<6) | (0<<5) | (1<<4))
+#define L3GD20_RATE_760HZ_LP_50HZ ((1<<7) | (1<<6) | (1<<5) | (0<<4))
+#define L3GD20_RATE_760HZ_LP_100HZ ((1<<7) | (1<<6) | (1<<5) | (1<<4))
+
+/*
+ * Sets the sensor internal range.
+ */
+#define L3GD20_SETRANGE L3GD20C(2)
+
+#define L3GD20_RANGE_250DPS (0<<4)
+#define L3GD20_RANGE_500DPS (1<<4)
+#define L3GD20_RANGE_2000DPS (3<<4)
+
+#define L3GD20_RATE_95HZ ((0<<6) | (0<<4))
+#define L3GD20_RATE_190HZ ((1<<6) | (0<<4))
+#define L3GD20_RATE_380HZ ((2<<6) | (1<<4))
+#define L3GD20_RATE_760HZ ((3<<6) | (2<<4))
+
+
+
+/*
+ * Sets the address of a shared l3gd20_buffer
+ * structure that is maintained by the driver.
+ *
+ * If zero is passed as the address, disables
+ * the buffer updating.
+ */
+#define L3GD20_SETBUFFER L3GD20C(3)
+
+struct l3gd20_buffer {
+ uint32_t size; /* number of entries in the samples[] array */
+ uint32_t next; /* the next entry that will be populated */
+ struct {
+ int16_t x;
+ int16_t y;
+ int16_t z;
+ } samples[];
+};
+
+extern int l3gd20_attach(struct spi_dev_s *spi, int spi_id);
diff --git a/nuttx/configs/px4fmu/include/drv_led.h b/nuttx/configs/px4fmu/include/drv_led.h
new file mode 100644
index 000000000..4b7093346
--- /dev/null
+++ b/nuttx/configs/px4fmu/include/drv_led.h
@@ -0,0 +1,51 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#include <sys/ioctl.h>
+
+#define _LEDCBASE 0x6800
+#define LEDC(_x) _IOC(_LEDCBASE, _x)
+
+/* set the LED identified by the argument */
+#define LED_ON LEDC(1)
+
+/* clear the LED identified by the argument */
+#define LED_OFF LEDC(2)
+
+///* toggle the LED identified by the argument */
+//#define LED_TOGGLE LEDC(3)
+
+#define LED_BLUE 0 /* Led on first port */
+#define LED_AMBER 1 /* Led on second port */
+
+extern int px4fmu_led_init(void);
diff --git a/nuttx/configs/px4fmu/include/drv_lis331.h b/nuttx/configs/px4fmu/include/drv_lis331.h
new file mode 100644
index 000000000..f4699cda0
--- /dev/null
+++ b/nuttx/configs/px4fmu/include/drv_lis331.h
@@ -0,0 +1,83 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * Driver for the ST LIS331 MEMS accelerometer
+ */
+
+#include <sys/ioctl.h>
+
+#define _LIS331BASE 0x6900
+#define LIS331C(_x) _IOC(_LIS331BASE, _x)
+
+/*
+ * Sets the sensor internal sampling rate, and if a buffer
+ * has been configured, the rate at which entries will be
+ * added to the buffer.
+ */
+#define LIS331_SETRATE LIS331C(1)
+
+#define LIS331_RATE_50Hz (0<<3)
+#define LIS331_RATE_100Hz (1<<3)
+#define LIS331_RATE_400Hz (2<<3)
+#define LIS331_RATE_1000Hz (3<<3)
+
+/*
+ * Sets the sensor internal range.
+ */
+#define LIS331_SETRANGE LIS331C(2)
+
+#define LIS331_RANGE_2G (0<<4)
+#define LIS331_RANGE_4G (1<<4)
+#define LIS331_RANGE_8G (3<<4)
+
+/*
+ * Sets the address of a shared lis331_buffer
+ * structure that is maintained by the driver.
+ *
+ * If zero is passed as the address, disables
+ * the buffer updating.
+ */
+#define LIS331_SETBUFFER LIS331C(3)
+
+struct lis331_buffer {
+ uint32_t size; /* number of entries in the samples[] array */
+ uint32_t next; /* the next entry that will be populated */
+ struct {
+ uint16_t x;
+ uint16_t y;
+ uint16_t z;
+ } samples[];
+};
+
+extern int lis331_attach(struct spi_dev_s *spi, int spi_id);
diff --git a/nuttx/configs/px4fmu/include/drv_mpu6000.h b/nuttx/configs/px4fmu/include/drv_mpu6000.h
new file mode 100644
index 000000000..0a5a48b70
--- /dev/null
+++ b/nuttx/configs/px4fmu/include/drv_mpu6000.h
@@ -0,0 +1,92 @@
+/*
+ * Copyright (C) 2012 Lorenz Meier. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name of the author or the names of contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/*
+ * Driver for the Invense MPU-6000 gyroscope
+ */
+
+/* IMPORTANT NOTES:
+ *
+ * SPI max. clock frequency: 10 Mhz
+ * CS has to be high before transfer,
+ * go low right before transfer and
+ * go high again right after transfer
+ *
+ */
+
+#include <sys/ioctl.h>
+
+#define _MPU6000BASE 0x7600
+#define MPU6000C(_x) _IOC(_MPU6000BASE, _x)
+
+/*
+ * Sets the sensor internal sampling rate, and if a buffer
+ * has been configured, the rate at which entries will be
+ * added to the buffer.
+ */
+#define MPU6000_SETRATE MPU6000C(1)
+
+#define MPU6000_RATE_95HZ_LP_12_5HZ ((0<<7) | (0<<6) | (0<<5) | (0<<4))
+
+/*
+ * Sets the sensor internal range.
+ */
+#define MPU6000_SETRANGE MPU6000C(2)
+
+#define MPU6000_RANGE_250DPS (0<<4)
+
+#define MPU6000_RATE_95HZ ((0<<6) | (0<<4))
+
+
+
+/*
+ * Sets the address of a shared MPU6000_buffer
+ * structure that is maintained by the driver.
+ *
+ * If zero is passed as the address, disables
+ * the buffer updating.
+ */
+#define MPU6000_SETBUFFER MPU6000C(3)
+
+struct MPU6000_buffer {
+ uint32_t size; /* number of entries in the samples[] array */
+ uint32_t next; /* the next entry that will be populated */
+ struct {
+ uint16_t x;
+ uint16_t y;
+ uint16_t z;
+ uint16_t roll;
+ uint16_t pitch;
+ uint16_t yaw;
+ } samples[];
+};
+
+extern int mpu6000_attach(struct spi_dev_s *spi, int spi_id);
diff --git a/nuttx/configs/px4fmu/include/drv_ms5611.h b/nuttx/configs/px4fmu/include/drv_ms5611.h
new file mode 100644
index 000000000..922a11219
--- /dev/null
+++ b/nuttx/configs/px4fmu/include/drv_ms5611.h
@@ -0,0 +1,76 @@
+/*
+ * Copyright (C) 2012 Lorenz Meier. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name of the author or the names of contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/*
+ * Driver for the Meas Spec MS5611 barometric pressure sensor
+ */
+
+#include <sys/ioctl.h>
+
+#define _MS5611BASE 0x6A00
+#define MS5611C(_x) _IOC(_MS5611BASE, _x)
+
+/*
+ * Sets the sensor internal sampling rate, and if a buffer
+ * has been configured, the rate at which entries will be
+ * added to the buffer.
+ */
+#define MS5611_SETRATE MS5611C(1)
+
+/* set rate (configuration A register */
+#define MS5611_RATE_0_75HZ (0 << 2) /* 0.75 Hz */
+
+/*
+ * Sets the sensor internal range.
+ */
+#define MS5611_SETRANGE MS5611C(2)
+
+#define MS5611_RANGE_0_88GA (0 << 5)
+
+/*
+ * Sets the address of a shared MS5611_buffer
+ * structure that is maintained by the driver.
+ *
+ * If zero is passed as the address, disables
+ * the buffer updating.
+ */
+#define MS5611_SETBUFFER MS5611C(3)
+
+struct ms5611_buffer {
+ uint32_t size; /* number of entries in the samples[] array */
+ uint32_t next; /* the next entry that will be populated */
+ struct {
+ uint32_t pressure;
+ uint16_t temperature;
+ } samples[];
+};
+
+extern int ms5611_attach(struct i2c_dev_s *i2c);
diff --git a/nuttx/configs/px4fmu/include/drv_tone_alarm.h b/nuttx/configs/px4fmu/include/drv_tone_alarm.h
new file mode 100644
index 000000000..b24c85c8d
--- /dev/null
+++ b/nuttx/configs/px4fmu/include/drv_tone_alarm.h
@@ -0,0 +1,130 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * Driver for the PX4 audio alarm port, /dev/tone_alarm.
+ *
+ * The tone_alarm driver supports a set of predefined "alarm"
+ * patterns and one user-supplied pattern. Patterns are ordered by
+ * priority, with a higher-priority pattern interrupting any
+ * lower-priority pattern that might be playing.
+ *
+ * The TONE_SET_ALARM ioctl can be used to select a predefined
+ * alarm pattern, from 1 - <TBD>. Selecting pattern zero silences
+ * the alarm.
+ *
+ * To supply a custom pattern, write an array of 1 - <TBD> tone_note
+ * structures to /dev/tone_alarm. The custom pattern has a priority
+ * of zero.
+ *
+ * Patterns will normally play once and then silence (if a pattern
+ * was overridden it will not resume). A pattern may be made to
+ * repeat by inserting a note with the duration set to
+ * DURATION_REPEAT. This pattern will loop until either a
+ * higher-priority pattern is started or pattern zero is requested
+ * via the ioctl.
+ */
+
+#ifndef DRV_TONE_ALARM_H_
+#define DRV_TONE_ALARM_H_
+
+#include <sys/ioctl.h>
+
+#define _TONE_ALARM_BASE 0x7400
+#define TONE_SET_ALARM _IOC(_TONE_ALARM_BASE, 1)
+
+extern int tone_alarm_init(void);
+
+/* structure describing one note in a tone pattern */
+struct tone_note {
+ uint8_t pitch;
+ uint8_t duration; /* duration in multiples of 10ms */
+#define DURATION_END 0 /* ends the pattern */
+#define DURATION_REPEAT 255 /* resets the note counter to zero */
+};
+
+enum tone_pitch {
+ TONE_NOTE_E4, /* E4 */
+ TONE_NOTE_F4, /* F4 */
+ TONE_NOTE_F4S, /* F#4/Gb4 */
+ TONE_NOTE_G4, /* G4 */
+ TONE_NOTE_G4S, /* G#4/Ab4 */
+ TONE_NOTE_A4, /* A4 */
+ TONE_NOTE_A4S, /* A#4/Bb4 */
+ TONE_NOTE_B4, /* B4 */
+ TONE_NOTE_C5, /* C5 */
+ TONE_NOTE_C5S, /* C#5/Db5 */
+ TONE_NOTE_D5, /* D5 */
+ TONE_NOTE_D5S, /* D#5/Eb5 */
+ TONE_NOTE_E5, /* E5 */
+ TONE_NOTE_F5, /* F5 */
+ TONE_NOTE_F5S, /* F#5/Gb5 */
+ TONE_NOTE_G5, /* G5 */
+ TONE_NOTE_G5S, /* G#5/Ab5 */
+ TONE_NOTE_A5, /* A5 */
+ TONE_NOTE_A5S, /* A#5/Bb5 */
+ TONE_NOTE_B5, /* B5 */
+ TONE_NOTE_C6, /* C6 */
+ TONE_NOTE_C6S, /* C#6/Db6 */
+ TONE_NOTE_D6, /* D6 */
+ TONE_NOTE_D6S, /* D#6/Eb6 */
+ TONE_NOTE_E6, /* E6 */
+ TONE_NOTE_F6, /* F6 */
+ TONE_NOTE_F6S, /* F#6/Gb6 */
+ TONE_NOTE_G6, /* G6 */
+ TONE_NOTE_G6S, /* G#6/Ab6 */
+ TONE_NOTE_A6, /* A6 */
+ TONE_NOTE_A6S, /* A#6/Bb6 */
+ TONE_NOTE_B6, /* B6 */
+ TONE_NOTE_C7, /* C7 */
+ TONE_NOTE_C7S, /* C#7/Db7 */
+ TONE_NOTE_D7, /* D7 */
+ TONE_NOTE_D7S, /* D#7/Eb7 */
+ TONE_NOTE_E7, /* E7 */
+ TONE_NOTE_F7, /* F7 */
+ TONE_NOTE_F7S, /* F#7/Gb7 */
+ TONE_NOTE_G7, /* G7 */
+ TONE_NOTE_G7S, /* G#7/Ab7 */
+ TONE_NOTE_A7, /* A7 */
+ TONE_NOTE_A7S, /* A#7/Bb7 */
+ TONE_NOTE_B7, /* B7 */
+ TONE_NOTE_C8, /* C8 */
+ TONE_NOTE_C8S, /* C#8/Db8 */
+ TONE_NOTE_D8, /* D8 */
+ TONE_NOTE_D8S, /* D#8/Eb8 */
+
+ TONE_NOTE_SILENCE,
+ TONE_NOTE_MAX
+};
+
+#endif /* DRV_TONE_ALARM_H_ */ \ No newline at end of file
diff --git a/nuttx/configs/px4fmu/include/nsh_romfsimg.h b/nuttx/configs/px4fmu/include/nsh_romfsimg.h
new file mode 100644
index 000000000..799670c4d
--- /dev/null
+++ b/nuttx/configs/px4fmu/include/nsh_romfsimg.h
@@ -0,0 +1,601 @@
+unsigned char romfs_img[] = {
+ 0x2d, 0x72, 0x6f, 0x6d, 0x31, 0x66, 0x73, 0x2d, 0x00, 0x00, 0x18, 0x90,
+ 0xc0, 0x84, 0x3c, 0x72, 0x4e, 0x53, 0x48, 0x49, 0x6e, 0x69, 0x74, 0x56,
+ 0x6f, 0x6c, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x49,
+ 0x00, 0x00, 0x00, 0x20, 0x00, 0x00, 0x00, 0x00, 0xd1, 0xff, 0xff, 0x97,
+ 0x2e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, 0x20,
+ 0x00, 0x00, 0x00, 0x00, 0xd1, 0xd1, 0xff, 0x80, 0x2e, 0x2e, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x09, 0x00, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x00,
+ 0x68, 0x2d, 0x96, 0x03, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xa0,
+ 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, 0x00, 0xd1, 0xff, 0xff, 0x00,
+ 0x2e, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xc0, 0x00, 0x00, 0x00, 0x20,
+ 0x00, 0x00, 0x00, 0x00, 0xd1, 0xd1, 0xff, 0x20, 0x2e, 0x2e, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x01, 0x62, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7c,
+ 0xaf, 0xce, 0x68, 0x4d, 0x72, 0x63, 0x2e, 0x6c, 0x6f, 0x67, 0x67, 0x69,
+ 0x6e, 0x67, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x23, 0x21, 0x6e, 0x73,
+ 0x68, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x49, 0x6e, 0x69, 0x74, 0x69, 0x61,
+ 0x6c, 0x69, 0x73, 0x65, 0x20, 0x6c, 0x6f, 0x67, 0x67, 0x69, 0x6e, 0x67,
+ 0x20, 0x73, 0x65, 0x72, 0x76, 0x69, 0x63, 0x65, 0x73, 0x2e, 0x0a, 0x23,
+ 0x0a, 0x0a, 0x69, 0x66, 0x20, 0x5b, 0x20, 0x2d, 0x64, 0x20, 0x2f, 0x66,
+ 0x73, 0x2f, 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x73, 0x64, 0x20, 0x5d, 0x0a,
+ 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x09, 0x23, 0x20, 0x58, 0x58, 0x58, 0x20,
+ 0x74, 0x68, 0x69, 0x73, 0x20, 0x73, 0x68, 0x6f, 0x75, 0x6c, 0x64, 0x20,
+ 0x62, 0x65, 0x20, 0x27, 0x3c, 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e, 0x64,
+ 0x3e, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x27, 0x2e, 0x0a, 0x09, 0x23,
+ 0x20, 0x73, 0x64, 0x6c, 0x6f, 0x67, 0x20, 0x26, 0x0a, 0x66, 0x69, 0x0a,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x05, 0x72, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x03, 0xe9, 0x35, 0x68, 0x7f, 0x06, 0x72, 0x63, 0x2e, 0x50,
+ 0x58, 0x34, 0x49, 0x4f, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x23, 0x21, 0x6e, 0x73, 0x68, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x46, 0x6c,
+ 0x69, 0x67, 0x68, 0x74, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x75, 0x70,
+ 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x20, 0x66, 0x6f, 0x72, 0x20,
+ 0x50, 0x58, 0x34, 0x46, 0x4d, 0x55, 0x20, 0x77, 0x69, 0x74, 0x68, 0x20,
+ 0x50, 0x58, 0x34, 0x49, 0x4f, 0x20, 0x63, 0x61, 0x72, 0x72, 0x69, 0x65,
+ 0x72, 0x20, 0x62, 0x6f, 0x61, 0x72, 0x64, 0x2e, 0x0a, 0x23, 0x0a, 0x0a,
+ 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d,
+ 0x20, 0x64, 0x6f, 0x69, 0x6e, 0x67, 0x20, 0x50, 0x58, 0x34, 0x49, 0x4f,
+ 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, 0x2e, 0x2e, 0x2e, 0x22,
+ 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20,
+ 0x74, 0x68, 0x65, 0x20, 0x4f, 0x52, 0x42, 0x0a, 0x23, 0x0a, 0x75, 0x6f,
+ 0x72, 0x62, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x0a, 0x0a, 0x23, 0x0a,
+ 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20,
+ 0x73, 0x65, 0x6e, 0x73, 0x6f, 0x72, 0x73, 0x2e, 0x0a, 0x23, 0x0a, 0x73,
+ 0x68, 0x20, 0x2f, 0x65, 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e,
+ 0x64, 0x2f, 0x72, 0x63, 0x2e, 0x73, 0x65, 0x6e, 0x73, 0x6f, 0x72, 0x73,
+ 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20,
+ 0x4d, 0x41, 0x56, 0x4c, 0x69, 0x6e, 0x6b, 0x0a, 0x23, 0x0a, 0x6d, 0x61,
+ 0x76, 0x6c, 0x69, 0x6e, 0x6b, 0x20, 0x2d, 0x64, 0x20, 0x2f, 0x64, 0x65,
+ 0x76, 0x2f, 0x74, 0x74, 0x79, 0x53, 0x30, 0x20, 0x2d, 0x62, 0x20, 0x35,
+ 0x37, 0x36, 0x30, 0x30, 0x20, 0x26, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20,
+ 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x63, 0x6f,
+ 0x6d, 0x6d, 0x61, 0x6e, 0x64, 0x65, 0x72, 0x2e, 0x0a, 0x23, 0x0a, 0x23,
+ 0x20, 0x58, 0x58, 0x58, 0x20, 0x74, 0x68, 0x69, 0x73, 0x20, 0x73, 0x68,
+ 0x6f, 0x75, 0x6c, 0x64, 0x20, 0x62, 0x65, 0x20, 0x27, 0x3c, 0x63, 0x6f,
+ 0x6d, 0x6d, 0x61, 0x6e, 0x64, 0x3e, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74,
+ 0x27, 0x2e, 0x0a, 0x23, 0x0a, 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e, 0x64,
+ 0x65, 0x72, 0x20, 0x26, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74,
+ 0x61, 0x72, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x61, 0x74, 0x74, 0x69,
+ 0x74, 0x75, 0x64, 0x65, 0x20, 0x65, 0x73, 0x74, 0x69, 0x6d, 0x61, 0x74,
+ 0x6f, 0x72, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58, 0x58, 0x58, 0x20, 0x74,
+ 0x68, 0x69, 0x73, 0x20, 0x73, 0x68, 0x6f, 0x75, 0x6c, 0x64, 0x20, 0x62,
+ 0x65, 0x20, 0x27, 0x3c, 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e, 0x64, 0x3e,
+ 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x27, 0x2e, 0x0a, 0x23, 0x0a, 0x61,
+ 0x74, 0x74, 0x69, 0x74, 0x75, 0x64, 0x65, 0x5f, 0x65, 0x73, 0x74, 0x69,
+ 0x6d, 0x61, 0x74, 0x6f, 0x72, 0x5f, 0x62, 0x6d, 0x20, 0x26, 0x0a, 0x23,
+ 0x70, 0x6f, 0x73, 0x69, 0x74, 0x69, 0x6f, 0x6e, 0x5f, 0x65, 0x73, 0x74,
+ 0x69, 0x6d, 0x61, 0x74, 0x6f, 0x72, 0x20, 0x26, 0x0a, 0x0a, 0x23, 0x0a,
+ 0x23, 0x20, 0x43, 0x6f, 0x6e, 0x66, 0x69, 0x67, 0x75, 0x72, 0x65, 0x20,
+ 0x50, 0x58, 0x34, 0x46, 0x4d, 0x55, 0x20, 0x66, 0x6f, 0x72, 0x20, 0x6f,
+ 0x70, 0x65, 0x72, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x20, 0x77, 0x69, 0x74,
+ 0x68, 0x20, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x0a, 0x23, 0x0a, 0x23, 0x20,
+ 0x58, 0x58, 0x58, 0x20, 0x61, 0x72, 0x67, 0x75, 0x6d, 0x65, 0x6e, 0x74,
+ 0x73, 0x3f, 0x0a, 0x23, 0x0a, 0x70, 0x78, 0x34, 0x66, 0x6d, 0x75, 0x20,
+ 0x73, 0x74, 0x61, 0x72, 0x74, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53,
+ 0x74, 0x61, 0x72, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x66, 0x69, 0x78,
+ 0x65, 0x64, 0x2d, 0x77, 0x69, 0x6e, 0x67, 0x20, 0x63, 0x6f, 0x6e, 0x74,
+ 0x72, 0x6f, 0x6c, 0x6c, 0x65, 0x72, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58,
+ 0x58, 0x58, 0x20, 0x74, 0x68, 0x69, 0x73, 0x20, 0x73, 0x68, 0x6f, 0x75,
+ 0x6c, 0x64, 0x20, 0x62, 0x65, 0x20, 0x27, 0x3c, 0x63, 0x6f, 0x6d, 0x6d,
+ 0x61, 0x6e, 0x64, 0x3e, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x27, 0x2e,
+ 0x0a, 0x23, 0x0a, 0x66, 0x69, 0x78, 0x65, 0x64, 0x77, 0x69, 0x6e, 0x67,
+ 0x5f, 0x63, 0x6f, 0x6e, 0x74, 0x72, 0x6f, 0x6c, 0x20, 0x26, 0x0a, 0x0a,
+ 0x23, 0x0a, 0x23, 0x20, 0x46, 0x69, 0x72, 0x65, 0x20, 0x75, 0x70, 0x20,
+ 0x74, 0x68, 0x65, 0x20, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x20, 0x69, 0x6e,
+ 0x74, 0x65, 0x72, 0x66, 0x61, 0x63, 0x65, 0x2e, 0x0a, 0x23, 0x0a, 0x70,
+ 0x78, 0x34, 0x69, 0x6f, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x0a, 0x0a,
+ 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x6c, 0x6f,
+ 0x6f, 0x6b, 0x69, 0x6e, 0x67, 0x20, 0x66, 0x6f, 0x72, 0x20, 0x61, 0x20,
+ 0x47, 0x50, 0x53, 0x2e, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58, 0x58, 0x58,
+ 0x20, 0x74, 0x68, 0x69, 0x73, 0x20, 0x73, 0x68, 0x6f, 0x75, 0x6c, 0x64,
+ 0x20, 0x6e, 0x6f, 0x74, 0x20, 0x6e, 0x65, 0x65, 0x64, 0x20, 0x74, 0x6f,
+ 0x20, 0x62, 0x65, 0x20, 0x62, 0x61, 0x63, 0x6b, 0x67, 0x72, 0x6f, 0x75,
+ 0x6e, 0x64, 0x65, 0x64, 0x0a, 0x23, 0x0a, 0x67, 0x70, 0x73, 0x20, 0x2d,
+ 0x64, 0x20, 0x2f, 0x64, 0x65, 0x76, 0x2f, 0x74, 0x74, 0x79, 0x53, 0x33,
+ 0x20, 0x2d, 0x6d, 0x20, 0x61, 0x6c, 0x6c, 0x20, 0x26, 0x0a, 0x0a, 0x23,
+ 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x6c, 0x6f, 0x67,
+ 0x67, 0x69, 0x6e, 0x67, 0x20, 0x74, 0x6f, 0x20, 0x6d, 0x69, 0x63, 0x72,
+ 0x6f, 0x53, 0x44, 0x20, 0x69, 0x66, 0x20, 0x77, 0x65, 0x20, 0x63, 0x61,
+ 0x6e, 0x0a, 0x23, 0x0a, 0x73, 0x68, 0x20, 0x2f, 0x65, 0x74, 0x63, 0x2f,
+ 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f, 0x72, 0x63, 0x2e, 0x6c, 0x6f,
+ 0x67, 0x67, 0x69, 0x6e, 0x67, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x73,
+ 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, 0x20, 0x69, 0x73, 0x20, 0x64, 0x6f,
+ 0x6e, 0x65, 0x3b, 0x20, 0x77, 0x65, 0x20, 0x64, 0x6f, 0x6e, 0x27, 0x74,
+ 0x20, 0x77, 0x61, 0x6e, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x73, 0x68,
+ 0x65, 0x6c, 0x6c, 0x20, 0x62, 0x65, 0x63, 0x61, 0x75, 0x73, 0x65, 0x20,
+ 0x77, 0x65, 0x0a, 0x23, 0x20, 0x75, 0x73, 0x65, 0x20, 0x74, 0x68, 0x65,
+ 0x20, 0x73, 0x61, 0x6d, 0x65, 0x20, 0x55, 0x41, 0x52, 0x54, 0x20, 0x66,
+ 0x6f, 0x72, 0x20, 0x74, 0x65, 0x6c, 0x65, 0x6d, 0x65, 0x74, 0x72, 0x79,
+ 0x20, 0x28, 0x64, 0x75, 0x6d, 0x62, 0x29, 0x2e, 0x0a, 0x23, 0x0a, 0x65,
+ 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, 0x20,
+ 0x73, 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, 0x20, 0x64, 0x6f, 0x6e, 0x65,
+ 0x2c, 0x20, 0x65, 0x78, 0x69, 0x74, 0x69, 0x6e, 0x67, 0x2e, 0x22, 0x0a,
+ 0x65, 0x78, 0x69, 0x74, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x09, 0x72, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xd6,
+ 0xf4, 0x16, 0x7b, 0x19, 0x72, 0x63, 0x2e, 0x50, 0x58, 0x34, 0x49, 0x4f,
+ 0x41, 0x52, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x23, 0x21, 0x6e, 0x73,
+ 0x68, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x46, 0x6c, 0x69, 0x67, 0x68, 0x74,
+ 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, 0x20, 0x73, 0x63, 0x72,
+ 0x69, 0x70, 0x74, 0x20, 0x66, 0x6f, 0x72, 0x20, 0x50, 0x58, 0x34, 0x46,
+ 0x4d, 0x55, 0x20, 0x6f, 0x6e, 0x20, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x41,
+ 0x52, 0x20, 0x63, 0x61, 0x72, 0x72, 0x69, 0x65, 0x72, 0x20, 0x62, 0x6f,
+ 0x61, 0x72, 0x64, 0x2e, 0x0a, 0x23, 0x0a, 0x0a, 0x65, 0x63, 0x68, 0x6f,
+ 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x64, 0x6f, 0x69,
+ 0x6e, 0x67, 0x20, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x41, 0x52, 0x20, 0x73,
+ 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, 0x2e, 0x2e, 0x2e, 0x22, 0x0a, 0x0a,
+ 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x74, 0x68,
+ 0x65, 0x20, 0x4f, 0x52, 0x42, 0x0a, 0x23, 0x0a, 0x75, 0x6f, 0x72, 0x62,
+ 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20,
+ 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x73, 0x65,
+ 0x6e, 0x73, 0x6f, 0x72, 0x73, 0x2e, 0x0a, 0x23, 0x0a, 0x73, 0x68, 0x20,
+ 0x2f, 0x65, 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f,
+ 0x72, 0x63, 0x2e, 0x73, 0x65, 0x6e, 0x73, 0x6f, 0x72, 0x73, 0x0a, 0x0a,
+ 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x4d, 0x41,
+ 0x56, 0x4c, 0x69, 0x6e, 0x6b, 0x0a, 0x23, 0x0a, 0x6d, 0x61, 0x76, 0x6c,
+ 0x69, 0x6e, 0x6b, 0x20, 0x2d, 0x64, 0x20, 0x2f, 0x64, 0x65, 0x76, 0x2f,
+ 0x74, 0x74, 0x79, 0x53, 0x30, 0x20, 0x2d, 0x62, 0x20, 0x35, 0x37, 0x36,
+ 0x30, 0x30, 0x20, 0x26, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74,
+ 0x61, 0x72, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x63, 0x6f, 0x6d, 0x6d,
+ 0x61, 0x6e, 0x64, 0x65, 0x72, 0x2e, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58,
+ 0x58, 0x58, 0x20, 0x74, 0x68, 0x69, 0x73, 0x20, 0x73, 0x68, 0x6f, 0x75,
+ 0x6c, 0x64, 0x20, 0x62, 0x65, 0x20, 0x27, 0x3c, 0x63, 0x6f, 0x6d, 0x6d,
+ 0x61, 0x6e, 0x64, 0x3e, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x27, 0x2e,
+ 0x0a, 0x23, 0x0a, 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e, 0x64, 0x65, 0x72,
+ 0x20, 0x26, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72,
+ 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x61, 0x74, 0x74, 0x69, 0x74, 0x75,
+ 0x64, 0x65, 0x20, 0x65, 0x73, 0x74, 0x69, 0x6d, 0x61, 0x74, 0x6f, 0x72,
+ 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58, 0x58, 0x58, 0x20, 0x74, 0x68, 0x69,
+ 0x73, 0x20, 0x73, 0x68, 0x6f, 0x75, 0x6c, 0x64, 0x20, 0x62, 0x65, 0x20,
+ 0x27, 0x3c, 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e, 0x64, 0x3e, 0x20, 0x73,
+ 0x74, 0x61, 0x72, 0x74, 0x27, 0x2e, 0x0a, 0x23, 0x0a, 0x61, 0x74, 0x74,
+ 0x69, 0x74, 0x75, 0x64, 0x65, 0x5f, 0x65, 0x73, 0x74, 0x69, 0x6d, 0x61,
+ 0x74, 0x6f, 0x72, 0x5f, 0x62, 0x6d, 0x20, 0x26, 0x0a, 0x23, 0x70, 0x6f,
+ 0x73, 0x69, 0x74, 0x69, 0x6f, 0x6e, 0x5f, 0x65, 0x73, 0x74, 0x69, 0x6d,
+ 0x61, 0x74, 0x6f, 0x72, 0x20, 0x26, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20,
+ 0x43, 0x6f, 0x6e, 0x66, 0x69, 0x67, 0x75, 0x72, 0x65, 0x20, 0x50, 0x58,
+ 0x34, 0x46, 0x4d, 0x55, 0x20, 0x66, 0x6f, 0x72, 0x20, 0x6f, 0x70, 0x65,
+ 0x72, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x20, 0x77, 0x69, 0x74, 0x68, 0x20,
+ 0x50, 0x58, 0x34, 0x49, 0x4f, 0x41, 0x52, 0x0a, 0x23, 0x0a, 0x23, 0x20,
+ 0x58, 0x58, 0x58, 0x20, 0x61, 0x72, 0x67, 0x75, 0x6d, 0x65, 0x6e, 0x74,
+ 0x73, 0x3f, 0x0a, 0x23, 0x0a, 0x70, 0x78, 0x34, 0x66, 0x6d, 0x75, 0x20,
+ 0x73, 0x74, 0x61, 0x72, 0x74, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x46,
+ 0x69, 0x72, 0x65, 0x20, 0x75, 0x70, 0x20, 0x74, 0x68, 0x65, 0x20, 0x41,
+ 0x52, 0x2e, 0x44, 0x72, 0x6f, 0x6e, 0x65, 0x20, 0x63, 0x6f, 0x6e, 0x74,
+ 0x72, 0x6f, 0x6c, 0x6c, 0x65, 0x72, 0x2e, 0x0a, 0x23, 0x0a, 0x23, 0x20,
+ 0x58, 0x58, 0x58, 0x20, 0x74, 0x68, 0x69, 0x73, 0x20, 0x73, 0x68, 0x6f,
+ 0x75, 0x6c, 0x64, 0x20, 0x62, 0x65, 0x20, 0x27, 0x3c, 0x63, 0x6f, 0x6d,
+ 0x6d, 0x61, 0x6e, 0x64, 0x3e, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x27,
+ 0x2e, 0x0a, 0x23, 0x0a, 0x61, 0x72, 0x64, 0x72, 0x6f, 0x6e, 0x65, 0x5f,
+ 0x63, 0x6f, 0x6e, 0x74, 0x72, 0x6f, 0x6c, 0x20, 0x2d, 0x64, 0x20, 0x2f,
+ 0x64, 0x65, 0x76, 0x2f, 0x74, 0x74, 0x79, 0x53, 0x31, 0x20, 0x2d, 0x6d,
+ 0x20, 0x61, 0x74, 0x74, 0x69, 0x74, 0x75, 0x64, 0x65, 0x20, 0x26, 0x0a,
+ 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x6c,
+ 0x6f, 0x6f, 0x6b, 0x69, 0x6e, 0x67, 0x20, 0x66, 0x6f, 0x72, 0x20, 0x61,
+ 0x20, 0x47, 0x50, 0x53, 0x2e, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58, 0x58,
+ 0x58, 0x20, 0x74, 0x68, 0x69, 0x73, 0x20, 0x73, 0x68, 0x6f, 0x75, 0x6c,
+ 0x64, 0x20, 0x6e, 0x6f, 0x74, 0x20, 0x6e, 0x65, 0x65, 0x64, 0x20, 0x74,
+ 0x6f, 0x20, 0x62, 0x65, 0x20, 0x62, 0x61, 0x63, 0x6b, 0x67, 0x72, 0x6f,
+ 0x75, 0x6e, 0x64, 0x65, 0x64, 0x0a, 0x23, 0x0a, 0x67, 0x70, 0x73, 0x20,
+ 0x2d, 0x64, 0x20, 0x2f, 0x64, 0x65, 0x76, 0x2f, 0x74, 0x74, 0x79, 0x53,
+ 0x33, 0x20, 0x2d, 0x6d, 0x20, 0x61, 0x6c, 0x6c, 0x20, 0x26, 0x0a, 0x0a,
+ 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x6c, 0x6f,
+ 0x67, 0x67, 0x69, 0x6e, 0x67, 0x20, 0x74, 0x6f, 0x20, 0x6d, 0x69, 0x63,
+ 0x72, 0x6f, 0x53, 0x44, 0x20, 0x69, 0x66, 0x20, 0x77, 0x65, 0x20, 0x63,
+ 0x61, 0x6e, 0x0a, 0x23, 0x0a, 0x73, 0x68, 0x20, 0x2f, 0x65, 0x74, 0x63,
+ 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f, 0x72, 0x63, 0x2e, 0x6c,
+ 0x6f, 0x67, 0x67, 0x69, 0x6e, 0x67, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20,
+ 0x73, 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, 0x20, 0x69, 0x73, 0x20, 0x64,
+ 0x6f, 0x6e, 0x65, 0x3b, 0x20, 0x77, 0x65, 0x20, 0x64, 0x6f, 0x6e, 0x27,
+ 0x74, 0x20, 0x77, 0x61, 0x6e, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x73,
+ 0x68, 0x65, 0x6c, 0x6c, 0x20, 0x62, 0x65, 0x63, 0x61, 0x75, 0x73, 0x65,
+ 0x20, 0x77, 0x65, 0x0a, 0x23, 0x20, 0x75, 0x73, 0x65, 0x20, 0x74, 0x68,
+ 0x65, 0x20, 0x73, 0x61, 0x6d, 0x65, 0x20, 0x55, 0x41, 0x52, 0x54, 0x20,
+ 0x66, 0x6f, 0x72, 0x20, 0x74, 0x65, 0x6c, 0x65, 0x6d, 0x65, 0x74, 0x72,
+ 0x79, 0x20, 0x28, 0x64, 0x75, 0x6d, 0x62, 0x29, 0x2e, 0x0a, 0x23, 0x0a,
+ 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d,
+ 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, 0x20, 0x64, 0x6f, 0x6e,
+ 0x65, 0x2c, 0x20, 0x65, 0x78, 0x69, 0x74, 0x69, 0x6e, 0x67, 0x2e, 0x22,
+ 0x0a, 0x65, 0x78, 0x69, 0x74, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0b, 0x02, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x01, 0x6e, 0xb5, 0xbb, 0x51, 0xae, 0x72, 0x63, 0x2e, 0x73,
+ 0x65, 0x6e, 0x73, 0x6f, 0x72, 0x73, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x23, 0x21, 0x6e, 0x73, 0x68, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74,
+ 0x61, 0x6e, 0x64, 0x61, 0x72, 0x64, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74,
+ 0x75, 0x70, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x20, 0x66, 0x6f,
+ 0x72, 0x20, 0x50, 0x58, 0x34, 0x46, 0x4d, 0x55, 0x20, 0x6f, 0x6e, 0x62,
+ 0x6f, 0x61, 0x72, 0x64, 0x20, 0x73, 0x65, 0x6e, 0x73, 0x6f, 0x72, 0x20,
+ 0x64, 0x72, 0x69, 0x76, 0x65, 0x72, 0x73, 0x2e, 0x0a, 0x23, 0x0a, 0x0a,
+ 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x73, 0x65,
+ 0x6e, 0x73, 0x6f, 0x72, 0x20, 0x64, 0x72, 0x69, 0x76, 0x65, 0x72, 0x73,
+ 0x20, 0x68, 0x65, 0x72, 0x65, 0x2e, 0x0a, 0x23, 0x0a, 0x0a, 0x23, 0x6d,
+ 0x73, 0x35, 0x36, 0x31, 0x31, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x0a,
+ 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x74,
+ 0x68, 0x65, 0x20, 0x73, 0x65, 0x6e, 0x73, 0x6f, 0x72, 0x20, 0x63, 0x6f,
+ 0x6c, 0x6c, 0x65, 0x63, 0x74, 0x69, 0x6f, 0x6e, 0x20, 0x74, 0x61, 0x73,
+ 0x6b, 0x2e, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58, 0x58, 0x58, 0x20, 0x73,
+ 0x68, 0x6f, 0x75, 0x6c, 0x64, 0x20, 0x62, 0x65, 0x20, 0x27, 0x73, 0x65,
+ 0x6e, 0x73, 0x6f, 0x72, 0x73, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x27,
+ 0x0a, 0x23, 0x0a, 0x73, 0x65, 0x6e, 0x73, 0x6f, 0x72, 0x73, 0x20, 0x26,
+ 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x54, 0x65, 0x73, 0x74, 0x20, 0x73,
+ 0x65, 0x6e, 0x73, 0x6f, 0x72, 0x20, 0x66, 0x75, 0x6e, 0x63, 0x74, 0x69,
+ 0x6f, 0x6e, 0x61, 0x6c, 0x69, 0x74, 0x79, 0x0a, 0x23, 0x0a, 0x23, 0x20,
+ 0x58, 0x58, 0x58, 0x20, 0x69, 0x6e, 0x74, 0x65, 0x67, 0x72, 0x61, 0x74,
+ 0x65, 0x20, 0x77, 0x69, 0x74, 0x68, 0x20, 0x27, 0x73, 0x65, 0x6e, 0x73,
+ 0x6f, 0x72, 0x73, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x27, 0x20, 0x3f,
+ 0x0a, 0x23, 0x0a, 0x23, 0x69, 0x66, 0x20, 0x73, 0x65, 0x6e, 0x73, 0x6f,
+ 0x72, 0x73, 0x20, 0x71, 0x75, 0x69, 0x63, 0x6b, 0x74, 0x65, 0x73, 0x74,
+ 0x0a, 0x23, 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x23, 0x09, 0x65, 0x63, 0x68,
+ 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x73, 0x65,
+ 0x6e, 0x73, 0x6f, 0x72, 0x20, 0x69, 0x6e, 0x69, 0x74, 0x69, 0x61, 0x6c,
+ 0x69, 0x73, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x20, 0x46, 0x41, 0x49, 0x4c,
+ 0x45, 0x44, 0x2e, 0x22, 0x0a, 0x23, 0x09, 0x72, 0x65, 0x62, 0x6f, 0x6f,
+ 0x74, 0x0a, 0x23, 0x66, 0x69, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x0e, 0xf2,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xcd, 0x52, 0xce, 0xe0, 0xfc,
+ 0x72, 0x63, 0x2e, 0x73, 0x74, 0x61, 0x6e, 0x64, 0x61, 0x6c, 0x6f, 0x6e,
+ 0x65, 0x00, 0x00, 0x00, 0x23, 0x21, 0x6e, 0x73, 0x68, 0x0a, 0x23, 0x0a,
+ 0x23, 0x20, 0x46, 0x6c, 0x69, 0x67, 0x68, 0x74, 0x20, 0x73, 0x74, 0x61,
+ 0x72, 0x74, 0x75, 0x70, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x20,
+ 0x66, 0x6f, 0x72, 0x20, 0x50, 0x58, 0x34, 0x46, 0x4d, 0x55, 0x20, 0x73,
+ 0x74, 0x61, 0x6e, 0x64, 0x61, 0x6c, 0x6f, 0x6e, 0x65, 0x20, 0x63, 0x6f,
+ 0x6e, 0x66, 0x69, 0x67, 0x75, 0x72, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x2e,
+ 0x0a, 0x23, 0x0a, 0x0a, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69,
+ 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x64, 0x6f, 0x69, 0x6e, 0x67, 0x20, 0x73,
+ 0x74, 0x61, 0x6e, 0x64, 0x61, 0x6c, 0x6f, 0x6e, 0x65, 0x20, 0x50, 0x58,
+ 0x34, 0x46, 0x4d, 0x55, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x75, 0x70,
+ 0x2e, 0x2e, 0x2e, 0x22, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74,
+ 0x61, 0x72, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x4f, 0x52, 0x42, 0x0a,
+ 0x23, 0x0a, 0x23, 0x75, 0x6f, 0x72, 0x62, 0x20, 0x73, 0x74, 0x61, 0x72,
+ 0x74, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74,
+ 0x20, 0x74, 0x68, 0x65, 0x20, 0x73, 0x65, 0x6e, 0x73, 0x6f, 0x72, 0x73,
+ 0x2e, 0x0a, 0x23, 0x0a, 0x23, 0x73, 0x68, 0x20, 0x2f, 0x65, 0x74, 0x63,
+ 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f, 0x72, 0x63, 0x2e, 0x73,
+ 0x65, 0x6e, 0x73, 0x6f, 0x72, 0x73, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20,
+ 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x4d, 0x41, 0x56, 0x4c, 0x69, 0x6e,
+ 0x6b, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x6d, 0x61, 0x76, 0x6c, 0x69, 0x6e,
+ 0x6b, 0x20, 0x2d, 0x64, 0x20, 0x2f, 0x64, 0x65, 0x76, 0x2f, 0x74, 0x74,
+ 0x79, 0x53, 0x30, 0x20, 0x2d, 0x62, 0x20, 0x35, 0x37, 0x36, 0x30, 0x30,
+ 0x20, 0x26, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72,
+ 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e,
+ 0x64, 0x65, 0x72, 0x2e, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58, 0x58, 0x58,
+ 0x20, 0x74, 0x68, 0x69, 0x73, 0x20, 0x73, 0x68, 0x6f, 0x75, 0x6c, 0x64,
+ 0x20, 0x62, 0x65, 0x20, 0x27, 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e, 0x64,
+ 0x65, 0x72, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x27, 0x2e, 0x0a, 0x23,
+ 0x0a, 0x23, 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e, 0x64, 0x65, 0x72, 0x20,
+ 0x26, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74, 0x61, 0x72, 0x74,
+ 0x20, 0x74, 0x68, 0x65, 0x20, 0x61, 0x74, 0x74, 0x69, 0x74, 0x75, 0x64,
+ 0x65, 0x20, 0x65, 0x73, 0x74, 0x69, 0x6d, 0x61, 0x74, 0x6f, 0x72, 0x0a,
+ 0x23, 0x0a, 0x23, 0x20, 0x58, 0x58, 0x58, 0x20, 0x74, 0x68, 0x69, 0x73,
+ 0x20, 0x73, 0x68, 0x6f, 0x75, 0x6c, 0x64, 0x20, 0x62, 0x65, 0x20, 0x27,
+ 0x3c, 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e, 0x64, 0x3e, 0x20, 0x73, 0x74,
+ 0x61, 0x72, 0x74, 0x27, 0x2e, 0x0a, 0x23, 0x0a, 0x23, 0x61, 0x74, 0x74,
+ 0x69, 0x74, 0x75, 0x64, 0x65, 0x5f, 0x65, 0x73, 0x74, 0x69, 0x6d, 0x61,
+ 0x74, 0x6f, 0x72, 0x5f, 0x62, 0x6d, 0x20, 0x26, 0x0a, 0x23, 0x70, 0x6f,
+ 0x73, 0x69, 0x74, 0x69, 0x6f, 0x6e, 0x5f, 0x65, 0x73, 0x74, 0x69, 0x6d,
+ 0x61, 0x74, 0x6f, 0x72, 0x20, 0x26, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20,
+ 0x53, 0x74, 0x61, 0x72, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20, 0x66, 0x69,
+ 0x78, 0x65, 0x64, 0x2d, 0x77, 0x69, 0x6e, 0x67, 0x20, 0x63, 0x6f, 0x6e,
+ 0x74, 0x72, 0x6f, 0x6c, 0x6c, 0x65, 0x72, 0x2e, 0x0a, 0x23, 0x0a, 0x23,
+ 0x20, 0x58, 0x58, 0x58, 0x20, 0x73, 0x68, 0x6f, 0x75, 0x6c, 0x64, 0x20,
+ 0x74, 0x68, 0x69, 0x73, 0x20, 0x62, 0x65, 0x20, 0x6c, 0x6f, 0x6f, 0x6b,
+ 0x69, 0x6e, 0x67, 0x20, 0x66, 0x6f, 0x72, 0x20, 0x63, 0x6f, 0x6e, 0x66,
+ 0x69, 0x67, 0x75, 0x72, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x20, 0x74, 0x6f,
+ 0x20, 0x64, 0x65, 0x63, 0x69, 0x64, 0x65, 0x0a, 0x23, 0x20, 0x77, 0x68,
+ 0x65, 0x74, 0x68, 0x65, 0x72, 0x20, 0x74, 0x68, 0x65, 0x20, 0x62, 0x6f,
+ 0x61, 0x72, 0x64, 0x20, 0x69, 0x73, 0x20, 0x63, 0x6f, 0x6e, 0x66, 0x69,
+ 0x67, 0x75, 0x72, 0x65, 0x64, 0x20, 0x66, 0x6f, 0x72, 0x20, 0x66, 0x69,
+ 0x78, 0x65, 0x64, 0x2d, 0x77, 0x69, 0x6e, 0x67, 0x20, 0x75, 0x73, 0x65,
+ 0x3f, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58, 0x58, 0x58, 0x20, 0x74, 0x68,
+ 0x69, 0x73, 0x20, 0x73, 0x68, 0x6f, 0x75, 0x6c, 0x64, 0x20, 0x62, 0x65,
+ 0x20, 0x27, 0x66, 0x69, 0x78, 0x65, 0x64, 0x77, 0x69, 0x6e, 0x67, 0x5f,
+ 0x63, 0x6f, 0x6e, 0x74, 0x72, 0x6f, 0x6c, 0x20, 0x73, 0x74, 0x61, 0x72,
+ 0x74, 0x27, 0x2e, 0x0a, 0x23, 0x0a, 0x23, 0x66, 0x69, 0x78, 0x65, 0x64,
+ 0x77, 0x69, 0x6e, 0x67, 0x5f, 0x63, 0x6f, 0x6e, 0x74, 0x72, 0x6f, 0x6c,
+ 0x20, 0x26, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x43, 0x6f, 0x6e, 0x66,
+ 0x69, 0x67, 0x75, 0x72, 0x65, 0x20, 0x46, 0x4d, 0x55, 0x20, 0x66, 0x6f,
+ 0x72, 0x20, 0x73, 0x74, 0x61, 0x6e, 0x64, 0x61, 0x6c, 0x6f, 0x6e, 0x65,
+ 0x20, 0x6d, 0x6f, 0x64, 0x65, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x58, 0x58,
+ 0x58, 0x20, 0x61, 0x72, 0x67, 0x75, 0x6d, 0x65, 0x6e, 0x74, 0x73, 0x3f,
+ 0x0a, 0x23, 0x0a, 0x23, 0x70, 0x78, 0x34, 0x66, 0x6d, 0x75, 0x20, 0x73,
+ 0x74, 0x61, 0x72, 0x74, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74,
+ 0x61, 0x72, 0x74, 0x20, 0x6c, 0x6f, 0x6f, 0x6b, 0x69, 0x6e, 0x67, 0x20,
+ 0x66, 0x6f, 0x72, 0x20, 0x61, 0x20, 0x47, 0x50, 0x53, 0x2e, 0x0a, 0x23,
+ 0x0a, 0x23, 0x20, 0x58, 0x58, 0x58, 0x20, 0x74, 0x68, 0x69, 0x73, 0x20,
+ 0x73, 0x68, 0x6f, 0x75, 0x6c, 0x64, 0x20, 0x6e, 0x6f, 0x74, 0x20, 0x6e,
+ 0x65, 0x65, 0x64, 0x20, 0x74, 0x6f, 0x20, 0x62, 0x65, 0x20, 0x62, 0x61,
+ 0x63, 0x6b, 0x67, 0x72, 0x6f, 0x75, 0x6e, 0x64, 0x65, 0x64, 0x0a, 0x23,
+ 0x0a, 0x23, 0x67, 0x70, 0x73, 0x20, 0x2d, 0x64, 0x20, 0x2f, 0x64, 0x65,
+ 0x76, 0x2f, 0x74, 0x74, 0x79, 0x53, 0x33, 0x20, 0x2d, 0x6d, 0x20, 0x61,
+ 0x6c, 0x6c, 0x20, 0x26, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x53, 0x74,
+ 0x61, 0x72, 0x74, 0x20, 0x6c, 0x6f, 0x67, 0x67, 0x69, 0x6e, 0x67, 0x20,
+ 0x74, 0x6f, 0x20, 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x53, 0x44, 0x20, 0x69,
+ 0x66, 0x20, 0x77, 0x65, 0x20, 0x63, 0x61, 0x6e, 0x0a, 0x23, 0x0a, 0x73,
+ 0x68, 0x20, 0x2f, 0x65, 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e,
+ 0x64, 0x2f, 0x72, 0x63, 0x2e, 0x6c, 0x6f, 0x67, 0x67, 0x69, 0x6e, 0x67,
+ 0x0a, 0x0a, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69,
+ 0x74, 0x5d, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, 0x20, 0x64,
+ 0x6f, 0x6e, 0x65, 0x22, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0a,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x09, 0x76, 0x8d, 0x9c, 0xa3, 0x80,
+ 0x72, 0x63, 0x53, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x23, 0x21, 0x6e, 0x73, 0x68, 0x0a, 0x23, 0x0a,
+ 0x23, 0x20, 0x50, 0x58, 0x34, 0x46, 0x4d, 0x55, 0x20, 0x73, 0x74, 0x61,
+ 0x72, 0x74, 0x75, 0x70, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x2e,
+ 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x54, 0x68, 0x69, 0x73, 0x20, 0x73, 0x63,
+ 0x72, 0x69, 0x70, 0x74, 0x20, 0x69, 0x73, 0x20, 0x72, 0x65, 0x73, 0x70,
+ 0x6f, 0x6e, 0x73, 0x69, 0x62, 0x6c, 0x65, 0x20, 0x66, 0x6f, 0x72, 0x3a,
+ 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x2d, 0x20, 0x6d, 0x6f, 0x75, 0x6e, 0x74,
+ 0x69, 0x6e, 0x67, 0x20, 0x74, 0x68, 0x65, 0x20, 0x6d, 0x69, 0x63, 0x72,
+ 0x6f, 0x53, 0x44, 0x20, 0x63, 0x61, 0x72, 0x64, 0x20, 0x28, 0x69, 0x66,
+ 0x20, 0x70, 0x72, 0x65, 0x73, 0x65, 0x6e, 0x74, 0x29, 0x0a, 0x23, 0x20,
+ 0x2d, 0x20, 0x72, 0x75, 0x6e, 0x6e, 0x69, 0x6e, 0x67, 0x20, 0x74, 0x68,
+ 0x65, 0x20, 0x75, 0x73, 0x65, 0x72, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74,
+ 0x75, 0x70, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x20, 0x66, 0x72,
+ 0x6f, 0x6d, 0x20, 0x74, 0x68, 0x65, 0x20, 0x6d, 0x69, 0x63, 0x72, 0x6f,
+ 0x53, 0x44, 0x20, 0x63, 0x61, 0x72, 0x64, 0x20, 0x28, 0x69, 0x66, 0x20,
+ 0x70, 0x72, 0x65, 0x73, 0x65, 0x6e, 0x74, 0x29, 0x0a, 0x23, 0x20, 0x2d,
+ 0x20, 0x64, 0x65, 0x74, 0x65, 0x63, 0x74, 0x69, 0x6e, 0x67, 0x20, 0x74,
+ 0x68, 0x65, 0x20, 0x63, 0x6f, 0x6e, 0x66, 0x69, 0x67, 0x75, 0x72, 0x61,
+ 0x74, 0x69, 0x6f, 0x6e, 0x20, 0x6f, 0x66, 0x20, 0x74, 0x68, 0x65, 0x20,
+ 0x73, 0x79, 0x73, 0x74, 0x65, 0x6d, 0x20, 0x61, 0x6e, 0x64, 0x20, 0x70,
+ 0x69, 0x63, 0x6b, 0x69, 0x6e, 0x67, 0x20, 0x61, 0x20, 0x73, 0x75, 0x69,
+ 0x74, 0x61, 0x62, 0x6c, 0x65, 0x0a, 0x23, 0x20, 0x20, 0x20, 0x73, 0x74,
+ 0x61, 0x72, 0x74, 0x75, 0x70, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74,
+ 0x20, 0x74, 0x6f, 0x20, 0x63, 0x6f, 0x6e, 0x74, 0x69, 0x6e, 0x75, 0x65,
+ 0x20, 0x77, 0x69, 0x74, 0x68, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x4e, 0x6f,
+ 0x74, 0x65, 0x3a, 0x20, 0x44, 0x4f, 0x20, 0x4e, 0x4f, 0x54, 0x20, 0x61,
+ 0x64, 0x64, 0x20, 0x63, 0x6f, 0x6e, 0x66, 0x69, 0x67, 0x75, 0x72, 0x61,
+ 0x74, 0x69, 0x6f, 0x6e, 0x2d, 0x73, 0x70, 0x65, 0x63, 0x69, 0x66, 0x69,
+ 0x63, 0x20, 0x63, 0x6f, 0x6d, 0x6d, 0x61, 0x6e, 0x64, 0x73, 0x20, 0x74,
+ 0x6f, 0x20, 0x74, 0x68, 0x69, 0x73, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70,
+ 0x74, 0x3b, 0x0a, 0x23, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x20, 0x61,
+ 0x64, 0x64, 0x20, 0x74, 0x68, 0x65, 0x6d, 0x20, 0x74, 0x6f, 0x20, 0x74,
+ 0x68, 0x65, 0x20, 0x70, 0x65, 0x72, 0x2d, 0x63, 0x6f, 0x6e, 0x66, 0x69,
+ 0x67, 0x75, 0x72, 0x61, 0x74, 0x69, 0x6f, 0x6e, 0x20, 0x73, 0x63, 0x72,
+ 0x69, 0x70, 0x74, 0x73, 0x20, 0x69, 0x6e, 0x73, 0x74, 0x65, 0x61, 0x64,
+ 0x2e, 0x0a, 0x23, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x44, 0x65, 0x66,
+ 0x61, 0x75, 0x6c, 0x74, 0x20, 0x74, 0x6f, 0x20, 0x61, 0x75, 0x74, 0x6f,
+ 0x2d, 0x73, 0x74, 0x61, 0x72, 0x74, 0x20, 0x6d, 0x6f, 0x64, 0x65, 0x2e,
+ 0x20, 0x20, 0x41, 0x6e, 0x20, 0x69, 0x6e, 0x69, 0x74, 0x20, 0x73, 0x63,
+ 0x72, 0x69, 0x70, 0x74, 0x20, 0x6f, 0x6e, 0x20, 0x74, 0x68, 0x65, 0x20,
+ 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x53, 0x44, 0x20, 0x63, 0x61, 0x72, 0x64,
+ 0x0a, 0x23, 0x20, 0x63, 0x61, 0x6e, 0x20, 0x63, 0x68, 0x61, 0x6e, 0x67,
+ 0x65, 0x20, 0x74, 0x68, 0x69, 0x73, 0x20, 0x74, 0x6f, 0x20, 0x70, 0x72,
+ 0x65, 0x76, 0x65, 0x6e, 0x74, 0x20, 0x61, 0x75, 0x74, 0x6f, 0x6d, 0x61,
+ 0x74, 0x69, 0x63, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x75, 0x70, 0x20,
+ 0x6f, 0x66, 0x20, 0x74, 0x68, 0x65, 0x20, 0x66, 0x6c, 0x69, 0x67, 0x68,
+ 0x74, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x2e, 0x0a, 0x23, 0x0a,
+ 0x73, 0x65, 0x74, 0x20, 0x4d, 0x4f, 0x44, 0x45, 0x20, 0x61, 0x75, 0x74,
+ 0x6f, 0x73, 0x74, 0x61, 0x72, 0x74, 0x0a, 0x73, 0x65, 0x74, 0x20, 0x55,
+ 0x53, 0x42, 0x5f, 0x41, 0x4c, 0x4c, 0x4f, 0x57, 0x45, 0x44, 0x20, 0x79,
+ 0x65, 0x73, 0x0a, 0x73, 0x65, 0x74, 0x20, 0x55, 0x53, 0x42, 0x20, 0x6e,
+ 0x6f, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20, 0x54, 0x72, 0x79, 0x20, 0x74,
+ 0x6f, 0x20, 0x6d, 0x6f, 0x75, 0x6e, 0x74, 0x20, 0x74, 0x68, 0x65, 0x20,
+ 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x53, 0x44, 0x20, 0x63, 0x61, 0x72, 0x64,
+ 0x2e, 0x0a, 0x23, 0x0a, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69,
+ 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x6c, 0x6f, 0x6f, 0x6b, 0x69, 0x6e, 0x67,
+ 0x20, 0x66, 0x6f, 0x72, 0x20, 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x53, 0x44,
+ 0x2e, 0x2e, 0x2e, 0x22, 0x0a, 0x69, 0x66, 0x20, 0x6d, 0x6f, 0x75, 0x6e,
+ 0x74, 0x20, 0x2d, 0x74, 0x20, 0x76, 0x66, 0x61, 0x74, 0x20, 0x2f, 0x64,
+ 0x65, 0x76, 0x2f, 0x6d, 0x6d, 0x63, 0x73, 0x64, 0x30, 0x20, 0x2f, 0x66,
+ 0x73, 0x2f, 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x73, 0x64, 0x0a, 0x74, 0x68,
+ 0x65, 0x6e, 0x0a, 0x09, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69,
+ 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x63, 0x61, 0x72, 0x64, 0x20, 0x6d, 0x6f,
+ 0x75, 0x6e, 0x74, 0x65, 0x64, 0x20, 0x61, 0x74, 0x20, 0x2f, 0x66, 0x73,
+ 0x2f, 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x73, 0x64, 0x22, 0x0a, 0x65, 0x6c,
+ 0x73, 0x65, 0x0a, 0x09, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69,
+ 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x6e, 0x6f, 0x20, 0x6d, 0x69, 0x63, 0x72,
+ 0x6f, 0x53, 0x44, 0x20, 0x63, 0x61, 0x72, 0x64, 0x20, 0x66, 0x6f, 0x75,
+ 0x6e, 0x64, 0x22, 0x0a, 0x66, 0x69, 0x0a, 0x0a, 0x23, 0x0a, 0x23, 0x20,
+ 0x4c, 0x6f, 0x6f, 0x6b, 0x20, 0x66, 0x6f, 0x72, 0x20, 0x61, 0x6e, 0x20,
+ 0x69, 0x6e, 0x69, 0x74, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x20,
+ 0x6f, 0x6e, 0x20, 0x74, 0x68, 0x65, 0x20, 0x6d, 0x69, 0x63, 0x72, 0x6f,
+ 0x53, 0x44, 0x20, 0x63, 0x61, 0x72, 0x64, 0x2e, 0x0a, 0x23, 0x0a, 0x23,
+ 0x20, 0x54, 0x6f, 0x20, 0x70, 0x72, 0x65, 0x76, 0x65, 0x6e, 0x74, 0x20,
+ 0x61, 0x75, 0x74, 0x6f, 0x6d, 0x61, 0x74, 0x69, 0x63, 0x20, 0x73, 0x74,
+ 0x61, 0x72, 0x74, 0x75, 0x70, 0x20, 0x69, 0x6e, 0x20, 0x74, 0x68, 0x65,
+ 0x20, 0x63, 0x75, 0x72, 0x72, 0x65, 0x6e, 0x74, 0x20, 0x66, 0x6c, 0x69,
+ 0x67, 0x68, 0x74, 0x20, 0x6d, 0x6f, 0x64, 0x65, 0x2c, 0x0a, 0x23, 0x20,
+ 0x74, 0x68, 0x65, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x20, 0x73,
+ 0x68, 0x6f, 0x75, 0x6c, 0x64, 0x20, 0x73, 0x65, 0x74, 0x20, 0x4d, 0x4f,
+ 0x44, 0x45, 0x20, 0x74, 0x6f, 0x20, 0x73, 0x6f, 0x6d, 0x65, 0x20, 0x6f,
+ 0x74, 0x68, 0x65, 0x72, 0x20, 0x76, 0x61, 0x6c, 0x75, 0x65, 0x2e, 0x0a,
+ 0x23, 0x0a, 0x69, 0x66, 0x20, 0x5b, 0x20, 0x2d, 0x66, 0x20, 0x2f, 0x66,
+ 0x73, 0x2f, 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x73, 0x64, 0x2f, 0x65, 0x74,
+ 0x63, 0x2f, 0x72, 0x63, 0x20, 0x5d, 0x0a, 0x74, 0x68, 0x65, 0x6e, 0x0a,
+ 0x09, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74,
+ 0x5d, 0x20, 0x72, 0x65, 0x61, 0x64, 0x69, 0x6e, 0x67, 0x20, 0x2f, 0x66,
+ 0x73, 0x2f, 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x73, 0x64, 0x2f, 0x65, 0x74,
+ 0x63, 0x2f, 0x72, 0x63, 0x22, 0x0a, 0x09, 0x73, 0x68, 0x20, 0x2f, 0x66,
+ 0x73, 0x2f, 0x6d, 0x69, 0x63, 0x72, 0x6f, 0x73, 0x64, 0x2f, 0x65, 0x74,
+ 0x63, 0x2f, 0x72, 0x63, 0x0a, 0x66, 0x69, 0x0a, 0x0a, 0x23, 0x0a, 0x23,
+ 0x20, 0x43, 0x68, 0x65, 0x63, 0x6b, 0x20, 0x66, 0x6f, 0x72, 0x20, 0x55,
+ 0x53, 0x42, 0x20, 0x68, 0x6f, 0x73, 0x74, 0x0a, 0x23, 0x0a, 0x69, 0x66,
+ 0x20, 0x5b, 0x20, 0x24, 0x55, 0x53, 0x42, 0x5f, 0x41, 0x4c, 0x4c, 0x4f,
+ 0x57, 0x45, 0x44, 0x20, 0x3d, 0x3d, 0x20, 0x79, 0x65, 0x73, 0x20, 0x5d,
+ 0x0a, 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x09, 0x69, 0x66, 0x20, 0x73, 0x65,
+ 0x72, 0x63, 0x6f, 0x6e, 0x0a, 0x09, 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x09,
+ 0x09, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74,
+ 0x5d, 0x20, 0x55, 0x53, 0x42, 0x20, 0x69, 0x6e, 0x74, 0x65, 0x72, 0x66,
+ 0x61, 0x63, 0x65, 0x20, 0x63, 0x6f, 0x6e, 0x6e, 0x65, 0x63, 0x74, 0x65,
+ 0x64, 0x22, 0x0a, 0x09, 0x66, 0x69, 0x0a, 0x66, 0x69, 0x0a, 0x0a, 0x23,
+ 0x0a, 0x23, 0x20, 0x49, 0x66, 0x20, 0x77, 0x65, 0x20, 0x61, 0x72, 0x65,
+ 0x20, 0x73, 0x74, 0x69, 0x6c, 0x6c, 0x20, 0x69, 0x6e, 0x20, 0x66, 0x6c,
+ 0x69, 0x67, 0x68, 0x74, 0x20, 0x6d, 0x6f, 0x64, 0x65, 0x2c, 0x20, 0x77,
+ 0x6f, 0x72, 0x6b, 0x20, 0x6f, 0x75, 0x74, 0x20, 0x77, 0x68, 0x61, 0x74,
+ 0x20, 0x61, 0x69, 0x72, 0x66, 0x72, 0x61, 0x6d, 0x65, 0x20, 0x0a, 0x23,
+ 0x20, 0x63, 0x6f, 0x6e, 0x66, 0x69, 0x67, 0x75, 0x72, 0x61, 0x74, 0x69,
+ 0x6f, 0x6e, 0x20, 0x77, 0x65, 0x20, 0x68, 0x61, 0x76, 0x65, 0x20, 0x61,
+ 0x6e, 0x64, 0x20, 0x73, 0x74, 0x61, 0x72, 0x74, 0x20, 0x75, 0x70, 0x20,
+ 0x61, 0x63, 0x63, 0x6f, 0x72, 0x64, 0x69, 0x6e, 0x67, 0x6c, 0x79, 0x2e,
+ 0x0a, 0x23, 0x0a, 0x69, 0x66, 0x20, 0x5b, 0x20, 0x24, 0x4d, 0x4f, 0x44,
+ 0x45, 0x20, 0x21, 0x3d, 0x20, 0x61, 0x75, 0x74, 0x6f, 0x73, 0x74, 0x61,
+ 0x72, 0x74, 0x20, 0x5d, 0x0a, 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x09, 0x65,
+ 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, 0x20,
+ 0x61, 0x75, 0x74, 0x6f, 0x6d, 0x61, 0x74, 0x69, 0x63, 0x20, 0x73, 0x74,
+ 0x61, 0x72, 0x74, 0x75, 0x70, 0x20, 0x63, 0x61, 0x6e, 0x63, 0x65, 0x6c,
+ 0x6c, 0x65, 0x64, 0x20, 0x62, 0x79, 0x20, 0x75, 0x73, 0x65, 0x72, 0x20,
+ 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x22, 0x0a, 0x65, 0x6c, 0x73, 0x65,
+ 0x0a, 0x09, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69,
+ 0x74, 0x5d, 0x20, 0x64, 0x65, 0x74, 0x65, 0x63, 0x74, 0x69, 0x6e, 0x67,
+ 0x20, 0x61, 0x74, 0x74, 0x61, 0x63, 0x68, 0x65, 0x64, 0x20, 0x68, 0x61,
+ 0x72, 0x64, 0x77, 0x61, 0x72, 0x65, 0x2e, 0x2e, 0x2e, 0x22, 0x0a, 0x0a,
+ 0x09, 0x23, 0x0a, 0x09, 0x23, 0x20, 0x41, 0x73, 0x73, 0x75, 0x6d, 0x65,
+ 0x20, 0x74, 0x68, 0x61, 0x74, 0x20, 0x77, 0x65, 0x20, 0x61, 0x72, 0x65,
+ 0x20, 0x50, 0x58, 0x34, 0x46, 0x4d, 0x55, 0x20, 0x69, 0x6e, 0x20, 0x73,
+ 0x74, 0x61, 0x6e, 0x64, 0x61, 0x6c, 0x6f, 0x6e, 0x65, 0x20, 0x6d, 0x6f,
+ 0x64, 0x65, 0x0a, 0x09, 0x23, 0x0a, 0x09, 0x73, 0x65, 0x74, 0x20, 0x42,
+ 0x4f, 0x41, 0x52, 0x44, 0x20, 0x50, 0x58, 0x34, 0x46, 0x4d, 0x55, 0x0a,
+ 0x0a, 0x09, 0x23, 0x0a, 0x09, 0x23, 0x20, 0x41, 0x72, 0x65, 0x20, 0x77,
+ 0x65, 0x20, 0x61, 0x74, 0x74, 0x61, 0x63, 0x68, 0x65, 0x64, 0x20, 0x74,
+ 0x6f, 0x20, 0x61, 0x20, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x41, 0x52, 0x20,
+ 0x28, 0x41, 0x52, 0x2e, 0x44, 0x72, 0x6f, 0x6e, 0x65, 0x20, 0x63, 0x61,
+ 0x72, 0x72, 0x69, 0x65, 0x72, 0x20, 0x62, 0x6f, 0x61, 0x72, 0x64, 0x29,
+ 0x3f, 0x0a, 0x09, 0x23, 0x0a, 0x09, 0x69, 0x66, 0x20, 0x62, 0x6f, 0x61,
+ 0x72, 0x64, 0x69, 0x6e, 0x66, 0x6f, 0x20, 0x2d, 0x74, 0x20, 0x37, 0x0a,
+ 0x09, 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x09, 0x09, 0x73, 0x65, 0x74, 0x20,
+ 0x42, 0x4f, 0x41, 0x52, 0x44, 0x20, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x41,
+ 0x52, 0x0a, 0x09, 0x09, 0x69, 0x66, 0x20, 0x5b, 0x20, 0x2d, 0x66, 0x20,
+ 0x2f, 0x65, 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f,
+ 0x72, 0x63, 0x2e, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x41, 0x52, 0x20, 0x5d,
+ 0x0a, 0x09, 0x09, 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x09, 0x09, 0x09, 0x65,
+ 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, 0x20,
+ 0x72, 0x65, 0x61, 0x64, 0x69, 0x6e, 0x67, 0x20, 0x2f, 0x65, 0x74, 0x63,
+ 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f, 0x72, 0x63, 0x2e, 0x50,
+ 0x58, 0x34, 0x49, 0x4f, 0x41, 0x52, 0x22, 0x0a, 0x09, 0x09, 0x09, 0x73,
+ 0x68, 0x20, 0x2f, 0x65, 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e,
+ 0x64, 0x2f, 0x72, 0x63, 0x2e, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x41, 0x52,
+ 0x0a, 0x09, 0x09, 0x66, 0x69, 0x0a, 0x09, 0x65, 0x6c, 0x73, 0x65, 0x0a,
+ 0x09, 0x09, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69,
+ 0x74, 0x5d, 0x20, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x41, 0x52, 0x20, 0x6e,
+ 0x6f, 0x74, 0x20, 0x64, 0x65, 0x74, 0x65, 0x63, 0x74, 0x65, 0x64, 0x22,
+ 0x0a, 0x09, 0x66, 0x69, 0x0a, 0x0a, 0x09, 0x23, 0x0a, 0x09, 0x23, 0x20,
+ 0x41, 0x72, 0x65, 0x20, 0x77, 0x65, 0x20, 0x61, 0x74, 0x74, 0x61, 0x63,
+ 0x68, 0x65, 0x64, 0x20, 0x74, 0x6f, 0x20, 0x61, 0x20, 0x50, 0x58, 0x34,
+ 0x49, 0x4f, 0x3f, 0x0a, 0x09, 0x23, 0x0a, 0x09, 0x69, 0x66, 0x20, 0x62,
+ 0x6f, 0x61, 0x72, 0x64, 0x69, 0x6e, 0x66, 0x6f, 0x20, 0x2d, 0x74, 0x20,
+ 0x36, 0x0a, 0x09, 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x09, 0x09, 0x73, 0x65,
+ 0x74, 0x20, 0x42, 0x4f, 0x41, 0x52, 0x44, 0x20, 0x50, 0x58, 0x34, 0x49,
+ 0x4f, 0x0a, 0x09, 0x09, 0x69, 0x66, 0x20, 0x5b, 0x20, 0x2d, 0x66, 0x20,
+ 0x2f, 0x65, 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f,
+ 0x72, 0x63, 0x2e, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x20, 0x5d, 0x0a, 0x09,
+ 0x09, 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x09, 0x09, 0x09, 0x65, 0x63, 0x68,
+ 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x72, 0x65,
+ 0x61, 0x64, 0x69, 0x6e, 0x67, 0x20, 0x2f, 0x65, 0x74, 0x63, 0x2f, 0x69,
+ 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f, 0x72, 0x63, 0x2e, 0x50, 0x58, 0x34,
+ 0x49, 0x4f, 0x22, 0x0a, 0x09, 0x09, 0x09, 0x73, 0x68, 0x20, 0x2f, 0x65,
+ 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f, 0x72, 0x63,
+ 0x2e, 0x50, 0x58, 0x34, 0x49, 0x4f, 0x0a, 0x09, 0x09, 0x66, 0x69, 0x0a,
+ 0x09, 0x65, 0x6c, 0x73, 0x65, 0x0a, 0x09, 0x09, 0x65, 0x63, 0x68, 0x6f,
+ 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x50, 0x58, 0x34,
+ 0x49, 0x4f, 0x20, 0x6e, 0x6f, 0x74, 0x20, 0x64, 0x65, 0x74, 0x65, 0x63,
+ 0x74, 0x65, 0x64, 0x22, 0x0a, 0x09, 0x66, 0x69, 0x0a, 0x0a, 0x09, 0x23,
+ 0x0a, 0x09, 0x23, 0x20, 0x4c, 0x6f, 0x6f, 0x6b, 0x73, 0x20, 0x6c, 0x69,
+ 0x6b, 0x65, 0x20, 0x77, 0x65, 0x20, 0x61, 0x72, 0x65, 0x20, 0x73, 0x74,
+ 0x61, 0x6e, 0x64, 0x2d, 0x61, 0x6c, 0x6f, 0x6e, 0x65, 0x0a, 0x09, 0x23,
+ 0x0a, 0x09, 0x69, 0x66, 0x20, 0x5b, 0x20, 0x24, 0x42, 0x4f, 0x41, 0x52,
+ 0x44, 0x20, 0x3d, 0x3d, 0x20, 0x50, 0x58, 0x34, 0x46, 0x4d, 0x55, 0x20,
+ 0x5d, 0x0a, 0x09, 0x74, 0x68, 0x65, 0x6e, 0x0a, 0x09, 0x09, 0x65, 0x63,
+ 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x6e,
+ 0x6f, 0x20, 0x65, 0x78, 0x70, 0x61, 0x6e, 0x73, 0x69, 0x6f, 0x6e, 0x20,
+ 0x62, 0x6f, 0x61, 0x72, 0x64, 0x20, 0x64, 0x65, 0x74, 0x65, 0x63, 0x74,
+ 0x65, 0x64, 0x22, 0x0a, 0x09, 0x09, 0x69, 0x66, 0x20, 0x5b, 0x20, 0x2d,
+ 0x66, 0x20, 0x2f, 0x65, 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e,
+ 0x64, 0x2f, 0x72, 0x63, 0x2e, 0x73, 0x74, 0x61, 0x6e, 0x64, 0x61, 0x6c,
+ 0x6f, 0x6e, 0x65, 0x20, 0x5d, 0x0a, 0x09, 0x09, 0x74, 0x68, 0x65, 0x6e,
+ 0x0a, 0x09, 0x09, 0x09, 0x65, 0x63, 0x68, 0x6f, 0x20, 0x22, 0x5b, 0x69,
+ 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x72, 0x65, 0x61, 0x64, 0x69, 0x6e, 0x67,
+ 0x20, 0x2f, 0x65, 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64,
+ 0x2f, 0x72, 0x63, 0x2e, 0x73, 0x74, 0x61, 0x6e, 0x64, 0x61, 0x6c, 0x6f,
+ 0x6e, 0x65, 0x22, 0x0a, 0x09, 0x09, 0x09, 0x73, 0x68, 0x20, 0x2f, 0x65,
+ 0x74, 0x63, 0x2f, 0x69, 0x6e, 0x69, 0x74, 0x2e, 0x64, 0x2f, 0x72, 0x63,
+ 0x2e, 0x73, 0x74, 0x61, 0x6e, 0x64, 0x61, 0x6c, 0x6f, 0x6e, 0x65, 0x0a,
+ 0x09, 0x09, 0x66, 0x69, 0x0a, 0x09, 0x66, 0x69, 0x0a, 0x0a, 0x09, 0x23,
+ 0x0a, 0x09, 0x23, 0x20, 0x57, 0x65, 0x20, 0x6d, 0x61, 0x79, 0x20, 0x6e,
+ 0x6f, 0x74, 0x20, 0x72, 0x65, 0x61, 0x63, 0x68, 0x20, 0x68, 0x65, 0x72,
+ 0x65, 0x20, 0x69, 0x66, 0x20, 0x74, 0x68, 0x65, 0x20, 0x61, 0x69, 0x72,
+ 0x66, 0x72, 0x61, 0x6d, 0x65, 0x2d, 0x73, 0x70, 0x65, 0x63, 0x69, 0x66,
+ 0x69, 0x63, 0x20, 0x73, 0x63, 0x72, 0x69, 0x70, 0x74, 0x20, 0x65, 0x78,
+ 0x69, 0x74, 0x73, 0x20, 0x74, 0x68, 0x65, 0x20, 0x73, 0x68, 0x65, 0x6c,
+ 0x6c, 0x2e, 0x0a, 0x09, 0x23, 0x0a, 0x09, 0x65, 0x63, 0x68, 0x6f, 0x20,
+ 0x22, 0x5b, 0x69, 0x6e, 0x69, 0x74, 0x5d, 0x20, 0x73, 0x74, 0x61, 0x72,
+ 0x74, 0x75, 0x70, 0x20, 0x64, 0x6f, 0x6e, 0x65, 0x2e, 0x22, 0x0a, 0x66,
+ 0x69, 0x0a, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ 0x00, 0x00, 0x00, 0x00
+};
+unsigned int romfs_img_len = 7168;
diff --git a/nuttx/configs/px4fmu/include/rcS.template b/nuttx/configs/px4fmu/include/rcS.template
new file mode 100644
index 000000000..2f97a7223
--- /dev/null
+++ b/nuttx/configs/px4fmu/include/rcS.template
@@ -0,0 +1,39 @@
+#echo "---------------------------"
+# Start apps
+echo "init: Starting applications.."
+echo "---------------------------"
+# WARNING:
+# ttyS0 is ALWAYS the NSH UART
+# ttyS1..SN are enumerated according to HW
+# uart indices (ttyS1 is the first UART NOT
+# configured for NSH, e.g. UART2)
+# ttyS0: UART1
+# ttyS1: UART2
+# ttyS2: UART5
+# ttyS3: UART6
+uorb start
+mavlink -d /dev/ttyS0 -b 57600 &
+echo "Trying to mount microSD card to /fs/microsd.."
+if mount -t vfat /dev/mmcsd0 /fs/microsd
+then
+echo "Successfully mounted SD card."
+else
+echo "FAILED mounting SD card."
+fi
+commander &
+sensors &
+attitude_estimator_bm &
+#position_estimator &
+ardrone_control -d /dev/ttyS1 -m attitude &
+gps -d /dev/ttyS3 -m all &
+#sdlog &
+#fixedwing_control &
+echo "---------------------------"
+echo "init: All applications started"
+echo "INIT DONE, RUNNING SYSTEM.."
+
+
+# WARNING! USE EXIT ONLY ON AR.DRONE
+# NO NSH COMMANDS CAN BE USED AFTER
+
+exit
diff --git a/nuttx/configs/px4fmu/include/up_adc.h b/nuttx/configs/px4fmu/include/up_adc.h
new file mode 100644
index 000000000..699c6a59a
--- /dev/null
+++ b/nuttx/configs/px4fmu/include/up_adc.h
@@ -0,0 +1,60 @@
+/************************************************************************************
+ * configs/stm3240g-eval/src/up_adc.c
+ * arch/arm/src/board/up_adc.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#ifdef CONFIG_ADC
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: adc_devinit
+ *
+ * Description:
+ * All STM32 architectures must provide the following interface to work with
+ * examples/adc.
+ *
+ ************************************************************************************/
+
+int adc_devinit(void);
+
+#endif /* CONFIG_ADC */
diff --git a/nuttx/configs/px4fmu/include/up_cpuload.h b/nuttx/configs/px4fmu/include/up_cpuload.h
new file mode 100644
index 000000000..b61c5c550
--- /dev/null
+++ b/nuttx/configs/px4fmu/include/up_cpuload.h
@@ -0,0 +1,62 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+#ifndef UP_CPULOAD_H_
+#define UP_CPULOAD_H_
+
+#ifdef CONFIG_SCHED_INSTRUMENTATION
+
+#include <nuttx/sched.h>
+
+struct system_load_taskinfo_s {
+ uint64_t total_runtime; ///< Runtime since start (start_time - total_runtime)/(start_time - current_time) = load
+ uint64_t curr_start_time; ///< Start time of the current scheduling slot
+ uint64_t start_time; ///< FIRST start time of task
+ FAR struct _TCB *tcb; ///<
+ bool valid; ///< Task is currently active / valid
+};
+
+struct system_load_s {
+ uint64_t start_time; ///< Global start time of measurements
+ struct system_load_taskinfo_s tasks[CONFIG_MAX_TASKS];
+ uint8_t initialized;
+ int total_count;
+ int running_count;
+ int sleeping_count;
+};
+
+void cpuload_initialize_once(void);
+
+#endif
+
+#endif
diff --git a/nuttx/configs/px4fmu/include/up_hrt.h b/nuttx/configs/px4fmu/include/up_hrt.h
new file mode 100644
index 000000000..6fd66ad74
--- /dev/null
+++ b/nuttx/configs/px4fmu/include/up_hrt.h
@@ -0,0 +1,130 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * High-resolution timer callouts and timekeeping.
+ */
+
+#ifndef UP_HRT_H_
+#define UP_HRT_H_
+
+#include <sys/types.h>
+#include <stdbool.h>
+
+#include <time.h>
+#include <queue.h>
+
+/*
+ * Absolute time, in microsecond units.
+ *
+ * Absolute time is measured from some arbitrary epoch shortly after
+ * system startup. It should never wrap or go backwards.
+ */
+typedef uint64_t hrt_abstime;
+
+/*
+ * Callout function type.
+ *
+ * Note that callouts run in the timer interrupt context, so
+ * they are serialised with respect to each other, and must not
+ * block.
+ */
+typedef void (* hrt_callout)(void *arg);
+
+/*
+ * Callout record.
+ */
+typedef struct hrt_call {
+ struct sq_entry_s link;
+
+ hrt_abstime deadline;
+ hrt_abstime period;
+ hrt_callout callout;
+ void *arg;
+} *hrt_call_t;
+
+/*
+ * Get absolute time.
+ */
+extern hrt_abstime hrt_absolute_time(void);
+
+/*
+ * Convert a timespec to absolute time.
+ */
+extern hrt_abstime ts_to_abstime(struct timespec *ts);
+
+/*
+ * Convert absolute time to a timespec.
+ */
+extern void abstime_to_ts(struct timespec *ts, hrt_abstime abstime);
+
+/*
+ * Call callout(arg) after delay has elapsed.
+ *
+ * If callout is NULL, this can be used to implement a timeout by testing the call
+ * with hrt_called().
+ */
+extern void hrt_call_after(struct hrt_call *entry, hrt_abstime delay, hrt_callout callout, void *arg);
+
+/*
+ * Call callout(arg) at absolute time calltime.
+ */
+extern void hrt_call_at(struct hrt_call *entry, hrt_abstime calltime, hrt_callout callout, void *arg);
+
+/*
+ * Call callout(arg) after delay, and then after every interval.
+ *
+ * Note thet the interval is timed between scheduled, not actual, call times, so the call rate may
+ * jitter but should not drift.
+ */
+extern void hrt_call_every(struct hrt_call *entry, hrt_abstime delay, hrt_abstime interval, hrt_callout callout, void *arg);
+
+/*
+ * If this returns true, the entry has been invoked and removed from the callout list,
+ * or it has never been entered.
+ *
+ * Always returns false for repeating callouts.
+ */
+extern bool hrt_called(struct hrt_call *entry);
+
+/*
+ * Remove the entry from the callout list.
+ */
+extern void hrt_cancel(struct hrt_call *entry);
+
+/*
+ * Initialise the HRT.
+ */
+extern void hrt_init(void);
+
+#endif /* UP_HRT_H_ */
diff --git a/nuttx/configs/px4fmu/include/up_pwm_servo.h b/nuttx/configs/px4fmu/include/up_pwm_servo.h
new file mode 100644
index 000000000..0b35035d5
--- /dev/null
+++ b/nuttx/configs/px4fmu/include/up_pwm_servo.h
@@ -0,0 +1,117 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * Low-level PWM servo control.
+ *
+ * The pwm_servo module supports servos connected to STM32 timer
+ * blocks.
+ *
+ * On PX4FMU, the outputs are:
+ *
+ * 0 : USART2/multi CTS
+ * 1 : USART2/multi RTS
+ * 2 : USART2/multi TX
+ * 3 : USART2/multi RX
+ * 4 : CAN2 TX
+ * 5 : CAN2 RX
+ */
+
+#ifndef UP_PWM_SERVO_H
+#define UP_PWM_SERVO_H
+
+typedef uint16_t servo_position_t;
+
+
+#if defined(__cplusplus)
+extern "C" {
+#endif
+
+/**
+ * Intialise the PWM servo outputs using the specified configuration.
+ *
+ * @param channel_mask Bitmask of channels (LSB = channel 0) to enable.
+ * This allows some of the channels to remain configured
+ * as GPIOs or as another function.
+ * @return OK on success.
+ */
+extern int up_pwm_servo_init(uint32_t channel_mask);
+
+/**
+ * De-initialise the PWM servo outputs.
+ */
+extern void up_pwm_servo_deinit(void);
+
+/**
+ * Arm or disarm servo outputs.
+ *
+ * When disarmed, servos output no pulse.
+ *
+ * @bug This function should, but does not, guarantee that any pulse
+ * currently in progress is cleanly completed.
+ *
+ * @param armed If true, outputs are armed; if false they
+ * are disarmed.
+ */
+extern void up_pwm_servo_arm(bool armed);
+
+/**
+ * Set the servo update rate
+ *
+ * @param rate The update rate in Hz to set.
+ * @return OK on success, -ERANGE if an unsupported update rate is set.
+ */
+extern int up_pwm_servo_set_rate(unsigned rate);
+
+/**
+ * Set the current output value for a channel.
+ *
+ * @param channel The channel to set.
+ * @param value The output pulse width in microseconds.
+ */
+extern int up_pwm_servo_set(unsigned channel, servo_position_t value);
+
+/**
+ * Get the current output value for a channel.
+ *
+ * @param channel The channel to read.
+ * @return The output pulse width in microseconds, or zero if
+ * outputs are not armed or not configured.
+ */
+extern servo_position_t up_pwm_servo_get(unsigned channel);
+
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* UP_PWM_SERVO_H */
diff --git a/nuttx/configs/px4fmu/nsh/Make.defs b/nuttx/configs/px4fmu/nsh/Make.defs
new file mode 100644
index 000000000..87508e22e
--- /dev/null
+++ b/nuttx/configs/px4fmu/nsh/Make.defs
@@ -0,0 +1,3 @@
+include ${TOPDIR}/.config
+
+include $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/Make.defs
diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig
new file mode 100644
index 000000000..85762f4c6
--- /dev/null
+++ b/nuttx/configs/px4fmu/nsh/appconfig
@@ -0,0 +1,92 @@
+############################################################################
+# configs/px4fmu/nsh/appconfig
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+# Path to example in apps/examples containing the user_start entry point
+
+CONFIGURED_APPS += examples/nsh
+
+# The NSH application library
+CONFIGURED_APPS += nshlib
+CONFIGURED_APPS += system/readline
+
+# System library - utility functions
+CONFIGURED_APPS += systemlib
+
+CONFIGURED_APPS += systemcmds/reboot
+CONFIGURED_APPS += systemcmds/perf
+CONFIGURED_APPS += systemcmds/top
+CONFIGURED_APPS += systemcmds/boardinfo
+#CONFIGURED_APPS += systemcmds/calibration
+
+CONFIGURED_APPS += uORB
+
+ifeq ($(CONFIG_MAVLINK),y)
+CONFIGURED_APPS += mavlink
+endif
+
+CONFIGURED_APPS += gps
+CONFIGURED_APPS += commander
+#CONFIGURED_APPS += sdlog
+CONFIGURED_APPS += sensors
+CONFIGURED_APPS += ardrone_control
+CONFIGURED_APPS += px4/attitude_estimator_bm
+CONFIGURED_APPS += fixedwing_control
+CONFIGURED_APPS += mix_and_link
+CONFIGURED_APPS += position_estimator
+CONFIGURED_APPS += attitude_estimator_ekf
+
+#CONFIGURED_APPS += system/i2c
+#CONFIGURED_APPS += tools/i2c_dev
+
+# Communication and Drivers
+CONFIGURED_APPS += drivers/device
+#CONFIGURED_APPS += drivers/ms5611
+CONFIGURED_APPS += px4/px4io/driver
+CONFIGURED_APPS += px4/fmu
+
+# Testing stuff
+CONFIGURED_APPS += px4/sensors_bringup
+CONFIGURED_APPS += px4/tests
+
+ifeq ($(CONFIG_CAN),y)
+#CONFIGURED_APPS += examples/can
+endif
+
+#ifeq ($(CONFIG_USBDEV),y)
+#ifeq ($(CONFIG_CDCACM),y)
+CONFIGURED_APPS += examples/cdcacm
+#endif
+#endif
+
diff --git a/nuttx/configs/px4fmu/nsh/defconfig b/nuttx/configs/px4fmu/nsh/defconfig
new file mode 100755
index 000000000..58c9ca45c
--- /dev/null
+++ b/nuttx/configs/px4fmu/nsh/defconfig
@@ -0,0 +1,1053 @@
+############################################################################
+# configs/px4fmu/nsh/defconfig
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+#
+# architecture selection
+#
+# CONFIG_ARCH - identifies the arch subdirectory and, hence, the
+# processor architecture.
+# CONFIG_ARCH_family - for use in C code. This identifies the
+# particular chip family that the architecture is implemented
+# in.
+# CONFIG_ARCH_architecture - for use in C code. This identifies the
+# specific architecture within the chip familyl.
+# CONFIG_ARCH_CHIP - Identifies the arch/*/chip subdirectory
+# CONFIG_ARCH_CHIP_name - For use in C code
+# CONFIG_ARCH_BOARD - identifies the configs subdirectory and, hence,
+# the board that supports the particular chip or SoC.
+# CONFIG_ARCH_BOARD_name - for use in C code
+# CONFIG_ENDIAN_BIG - define if big endian (default is little endian)
+# CONFIG_BOARD_LOOPSPERMSEC - for delay loops
+# CONFIG_DRAM_SIZE - Describes the installed DRAM.
+# CONFIG_DRAM_START - The start address of DRAM (physical)
+# CONFIG_DRAM_END - Last address+1 of installed RAM
+# CONFIG_ARCH_IRQPRIO - The STM3240xxx supports interrupt prioritization
+# CONFIG_ARCH_FPU - The STM3240xxx supports a floating point unit (FPU).
+# CONFIG_ARCH_INTERRUPTSTACK - This architecture supports an interrupt
+# stack. If defined, this symbol is the size of the interrupt
+# stack in bytes. If not defined, the user task stacks will be
+# used during interrupt handling.
+# CONFIG_ARCH_STACKDUMP - Do stack dumps after assertions
+# CONFIG_ARCH_BOOTLOADER - Set if you are using a bootloader.
+# CONFIG_ARCH_LEDS - Use LEDs to show state. Unique to board architecture.
+# CONFIG_ARCH_BUTTONS - Enable support for buttons. Unique to board architecture.
+# CONFIG_ARCH_CALIBRATION - Enables some build in instrumentation that
+# cause a 100 second delay during boot-up. This 100 second delay
+# serves no purpose other than it allows you to calibrate
+# CONFIG_BOARD_LOOPSPERMSEC. You simply use a stop watch to measure
+# the 100 second delay then adjust CONFIG_BOARD_LOOPSPERMSEC until
+# the delay actually is 100 seconds.
+# CONFIG_ARCH_DMA - Support DMA initialization
+#
+CONFIG_ARCH=arm
+CONFIG_ARCH_ARM=y
+CONFIG_ARCH_CORTEXM4=y
+CONFIG_ARCH_CHIP=stm32
+CONFIG_ARCH_CHIP_STM32F405RG=y
+CONFIG_ARCH_BOARD=px4fmu
+CONFIG_ARCH_BOARD_PX4FMU=y
+CONFIG_BOARD_LOOPSPERMSEC=16717
+CONFIG_DRAM_SIZE=0x00030000
+CONFIG_DRAM_START=0x20000000
+CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
+CONFIG_ARCH_IRQPRIO=y
+CONFIG_ARCH_FPU=y
+CONFIG_ARCH_INTERRUPTSTACK=n
+CONFIG_ARCH_STACKDUMP=y
+CONFIG_ARCH_BOOTLOADER=n
+CONFIG_ARCH_LEDS=y
+CONFIG_ARCH_BUTTONS=n
+CONFIG_ARCH_CALIBRATION=n
+CONFIG_ARCH_DMA=y
+CONFIG_ARCH_MATH_H=y
+
+CONFIG_ARMV7M_CMNVECTOR=y
+
+#
+# LIBC printf() options
+#
+# CONFIG_LIBC_FLOATINGPOINT - Enables printf("%f")
+# CONFIG_LIBC_FIXEDPRECISION - Sets 7 digits after dot for printing:
+# 5.1234567
+# CONFIG_HAVE_LONG_LONG - Enabled printf("%llu)
+#
+CONFIG_LIBC_FLOATINGPOINT=y
+CONFIG_HAVE_LONG_LONG=y
+#CONFIG_LIBC_FIXEDPRECISION=7
+
+#
+# CMSIS options
+#
+# CONFIG_DSPLIB_TARGET - Target for the CMSIS DSP library, one of
+# CortexM0, CortexM3 or CortexM4 (with fpu)
+#
+CONFIG_CMSIS_DSPLIB_TARGET=CortexM4
+
+#
+# JTAG Enable settings (by default JTAG-DP and SW-DP are enabled):
+#
+# CONFIG_STM32_DFU - Use the DFU bootloader, not JTAG (ignored)
+#
+# JTAG Enable options:
+#
+# CONFIG_STM32_JTAG_FULL_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE - Enables full SWJ (JTAG-DP + SW-DP)
+# but without JNTRST.
+# CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled
+#
+CONFIG_STM32_DFU=n
+CONFIG_STM32_JTAG_FULL_ENABLE=y
+CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
+CONFIG_STM32_JTAG_SW_ENABLE=n
+
+#
+# On-board FSMC SRAM configuration
+#
+# CONFIG_STM32_FSMC - Required. See below
+# CONFIG_MM_REGIONS - Required. Must be 2 or 3 (see above)
+#
+# CONFIG_STM32_FSMC_SRAM=y - Indicates that SRAM is available via the
+# FSMC (as opposed to an LCD or FLASH).
+# CONFIG_HEAP2_BASE - The base address of the SRAM in the FSMC address space
+# CONFIG_HEAP2_END - The end (+1) of the SRAM in the FSMC address space
+#
+#CONFIG_STM32_FSMC_SRAM=n
+#CONFIG_HEAP2_BASE=0x64000000
+#CONFIG_HEAP2_END=(0x64000000+(2*1024*1024))
+
+#
+# Individual subsystems can be enabled:
+#
+# This set is exhaustive for PX4FMU and should be safe to cut and
+# paste into any other config.
+#
+# AHB1:
+CONFIG_STM32_CRC=n
+CONFIG_STM32_BKPSRAM=y
+CONFIG_STM32_CCMDATARAM=y
+CONFIG_STM32_DMA1=y
+CONFIG_STM32_DMA2=y
+CONFIG_STM32_ETHMAC=n
+CONFIG_STM32_OTGHS=n
+# AHB2:
+CONFIG_STM32_DCMI=n
+CONFIG_STM32_CRYP=n
+CONFIG_STM32_HASH=n
+CONFIG_STM32_RNG=n
+CONFIG_STM32_OTGFS=y
+# AHB3:
+CONFIG_STM32_FSMC=n
+# APB1:
+# TIM2 is owned by PWM output
+CONFIG_STM32_TIM2=n
+# TIM3 is owned by TONE_ALARM
+CONFIG_STM32_TIM3=n
+CONFIG_STM32_TIM4=y
+CONFIG_STM32_TIM5=y
+CONFIG_STM32_TIM6=y
+CONFIG_STM32_TIM7=y
+CONFIG_STM32_TIM12=y
+CONFIG_STM32_TIM13=y
+CONFIG_STM32_TIM14=y
+CONFIG_STM32_WWDG=y
+CONFIG_STM32_SPI2=n
+CONFIG_STM32_SPI3=y
+CONFIG_STM32_USART2=y
+CONFIG_STM32_USART3=n
+CONFIG_STM32_UART4=n
+CONFIG_STM32_UART5=y
+CONFIG_STM32_I2C1=y
+CONFIG_STM32_I2C2=y
+CONFIG_STM32_I2C3=y
+CONFIG_STM32_CAN1=n
+CONFIG_STM32_CAN2=y
+CONFIG_STM32_DAC=n
+CONFIG_STM32_PWR=y
+# APB2:
+# TIM1 is owned by the HRT
+CONFIG_STM32_TIM1=n
+# TIM8 is owned by PWM output
+CONFIG_STM32_TIM8=n
+CONFIG_STM32_USART1=y
+CONFIG_STM32_USART6=y
+CONFIG_STM32_ADC1=n
+CONFIG_STM32_ADC2=n
+CONFIG_STM32_ADC3=y
+CONFIG_STM32_SDIO=n
+CONFIG_STM32_SPI1=y
+CONFIG_STM32_SYSCFG=y
+CONFIG_STM32_TIM9=y
+CONFIG_STM32_TIM10=y
+CONFIG_STM32_TIM11=y
+
+#
+# Configure the ADC
+#
+CONFIG_ADC=y
+# select trigger timer
+CONFIG_STM32_TIM4_ADC3=y
+# select sample frequency 1^=1.5Msamples/second
+# 65535^=10samples/second 16bit-timer runs at 84/128 MHz
+CONFIG_STM32_ADC3_SAMPLE_FREQUENCY=6000
+# select timer channel 0=CC1,...,3=CC4
+CONFIG_STM32_ADC3_TIMTRIG=3
+CONFIG_ADC_DMA=y
+# only 4 places usable!
+CONFIG_ADC_FIFOSIZE=5
+
+#
+# Timer and I2C devices may need to the following to force power to be applied:
+#
+#CONFIG_STM32_FORCEPOWER=y
+
+#
+# I2C configuration
+#
+CONFIG_I2C=y
+CONFIG_I2C_POLLED=y
+CONFIG_I2C_TRANSFER=y
+CONFIG_I2C_WRITEREAD=y
+CONFIG_I2C_TRACE=n
+# Allow 180 us per byte, a wide margin for the 400 KHz clock we're using
+# e.g. 9.6 ms for an EEPROM page write, 0.9 ms for a MAG update
+CONFIG_STM32_I2CTIMEOUS_PER_BYTE=200
+# Constant overhead for generating I2C start / stop conditions
+CONFIG_STM32_I2CTIMEOUS_START_STOP=700
+CONFIG_DEBUG_I2C=n
+
+#
+# STM32F40xxx specific serial device driver settings
+#
+# CONFIG_SERIAL_TERMIOS - Serial driver supports termios.h interfaces (tcsetattr,
+# tcflush, etc.). If this is not defined, then the terminal settings (baud,
+# parity, etc.) are not configurable at runtime; serial streams cannot be
+# flushed, etc.
+#
+# CONFIG_USARTn_SERIAL_CONSOLE - selects the USARTn for the
+# console and ttys0 (default is the USART1).
+# CONFIG_USARTn_RXBUFSIZE - Characters are buffered as received.
+# This specific the size of the receive buffer
+# CONFIG_USARTn_TXBUFSIZE - Characters are buffered before
+# being sent. This specific the size of the transmit buffer
+# CONFIG_USARTn_BAUD - The configure BAUD of the UART. Must be
+# CONFIG_USARTn_BITS - The number of bits. Must be either 7 or 8.
+# CONFIG_USARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
+# CONFIG_USARTn_2STOP - Two stop bits
+#
+CONFIG_SERIAL_TERMIOS=y
+
+CONFIG_USART1_SERIAL_CONSOLE=y
+CONFIG_USART2_SERIAL_CONSOLE=n
+CONFIG_USART3_SERIAL_CONSOLE=n
+CONFIG_USART4_SERIAL_CONSOLE=n
+CONFIG_USART5_SERIAL_CONSOLE=n
+CONFIG_USART6_SERIAL_CONSOLE=n
+
+#Mavlink messages can be bigger than 128
+CONFIG_USART1_TXBUFSIZE=512
+CONFIG_USART2_TXBUFSIZE=128
+CONFIG_USART3_TXBUFSIZE=128
+CONFIG_USART4_TXBUFSIZE=128
+CONFIG_USART5_TXBUFSIZE=64
+CONFIG_USART6_TXBUFSIZE=128
+
+CONFIG_USART1_RXBUFSIZE=512
+CONFIG_USART2_RXBUFSIZE=128
+CONFIG_USART3_RXBUFSIZE=128
+CONFIG_USART4_RXBUFSIZE=128
+CONFIG_USART5_RXBUFSIZE=128
+CONFIG_USART6_RXBUFSIZE=128
+
+CONFIG_USART1_BAUD=57600
+CONFIG_USART2_BAUD=115200
+CONFIG_USART3_BAUD=115200
+CONFIG_USART4_BAUD=115200
+CONFIG_USART5_BAUD=115200
+CONFIG_USART6_BAUD=9600
+
+CONFIG_USART1_BITS=8
+CONFIG_USART2_BITS=8
+CONFIG_USART3_BITS=8
+CONFIG_USART4_BITS=8
+CONFIG_USART5_BITS=8
+CONFIG_USART6_BITS=8
+
+CONFIG_USART1_PARITY=0
+CONFIG_USART2_PARITY=0
+CONFIG_USART3_PARITY=0
+CONFIG_USART4_PARITY=0
+CONFIG_USART5_PARITY=0
+CONFIG_USART6_PARITY=0
+
+CONFIG_USART1_2STOP=0
+CONFIG_USART2_2STOP=0
+CONFIG_USART3_2STOP=0
+CONFIG_USART4_2STOP=0
+CONFIG_USART5_2STOP=0
+CONFIG_USART6_2STOP=0
+
+CONFIG_USART1_RXDMA=n
+CONFIG_USART2_RXDMA=y
+CONFIG_USART3_RXDMA=n
+CONFIG_USART4_RXDMA=n
+CONFIG_USART5_RXDMA=y
+CONFIG_USART6_RXDMA=y
+
+#
+# PX4FMU specific driver settings
+#
+# CONFIG_HRT_TIMER
+# Enables the high-resolution timer. The board definition must
+# set HRT_TIMER and HRT_TIMER_CHANNEL to the timer and capture/
+# compare channels to be used.
+# CONFIG_HRT_PPM
+# Enables R/C PPM input using the HRT. The board definition must
+# set HRT_PPM_CHANNEL to the timer capture/compare channel to be
+# used, and define GPIO_PPM_IN to configure the appropriate timer
+# GPIO.
+# CONFIG_TONE_ALARM
+# Enables the tone alarm (buzzer) driver The board definition must
+# set TONE_ALARM_TIMER and TONE_ALARM_CHANNEL to the timer and
+# capture/compare channels to be used.
+# CONFIG_PWM_SERVO
+# Enables the PWM servo driver. The driver configuration must be
+# supplied by the board support at initialisation time.
+# Note that USART2 must be disabled on the PX4 board for this to
+# be available.
+# CONFIG_MULTIPORT
+# Enabled support for run-time (or EEPROM based boot-time) configuration
+# of ports for different functions (e.g. USART2 or ARDrone or PWM out)
+#
+#
+CONFIG_HRT_TIMER=y
+CONFIG_HRT_PPM=y
+CONFIG_TONE_ALARM=y
+CONFIG_PWM_SERVO=n
+CONFIG_MULTIPORT=n
+
+#
+# CONFIG_UART2_RTS_CTS_AS_GPIO
+# If set, enables RTS and CTS pins as additional GPIOs 2 and 3
+#
+CONFIG_PX4_UART2_RTS_CTS_AS_GPIO=y
+
+
+#
+# STM32F40xxx specific SPI device driver settings
+#
+CONFIG_SPI_EXCHANGE=y
+# DMA needs more work, not implemented on STM32F4x yet
+#CONFIG_STM32_SPI_DMA=y
+
+#
+# STM32F40xxx specific CAN device driver settings
+#
+# CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or
+# CONFIG_STM32_CAN2 must also be defined)
+# CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages.
+# Default: 8
+# CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests.
+# Default: 4
+# CONFIG_CAN_LOOPBACK - A CAN driver may or may not support a loopback
+# mode for testing. The STM32 CAN driver does support loopback mode.
+# CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined.
+# CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined.
+#
+CONFIG_CAN=n
+#CONFIG_CAN_FIFOSIZE
+#CONFIG_CAN_NPENDINGRTR
+CONFIG_CAN_LOOPBACK=n
+CONFIG_CAN1_BAUD=700000
+CONFIG_CAN2_BAUD=700000
+
+#
+# General build options
+#
+# CONFIG_RRLOAD_BINARY - make the rrload binary format used with
+# BSPs from www.ridgerun.com using the tools/mkimage.sh script
+# CONFIG_INTELHEX_BINARY - make the Intel HEX binary format
+# used with many different loaders using the GNU objcopy program
+# Should not be selected if you are not using the GNU toolchain.
+# CONFIG_MOTOROLA_SREC - make the Motorola S-Record binary format
+# used with many different loaders using the GNU objcopy program
+# Should not be selected if you are not using the GNU toolchain.
+# CONFIG_RAW_BINARY - make a raw binary format file used with many
+# different loaders using the GNU objcopy program. This option
+# should not be selected if you are not using the GNU toolchain.
+# CONFIG_HAVE_LIBM - toolchain supports libm.a
+#
+CONFIG_RRLOAD_BINARY=n
+CONFIG_INTELHEX_BINARY=y
+CONFIG_MOTOROLA_SREC=n
+CONFIG_RAW_BINARY=y
+CONFIG_HAVE_LIBM=y
+
+#
+# General OS setup
+#
+# CONFIG_APPS_DIR - Identifies the relative path to the directory
+# that builds the application to link with NuttX. Default: ../apps
+# CONFIG_DEBUG - enables built-in debug options
+# CONFIG_DEBUG_VERBOSE - enables verbose debug output
+# CONFIG_DEBUG_SYMBOLS - build without optimization and with
+# debug symbols (needed for use with a debugger).
+# CONFIG_HAVE_CXX - Enable support for C++
+# CONFIG_MM_REGIONS - If the architecture includes multiple
+# regions of memory to allocate from, this specifies the
+# number of memory regions that the memory manager must
+# handle and enables the API mm_addregion(start, end);
+# CONFIG_ARCH_LOWPUTC - architecture supports low-level, boot
+# time console output
+# CONFIG_MSEC_PER_TICK - The default system timer is 100Hz
+# or MSEC_PER_TICK=10. This setting may be defined to
+# inform NuttX that the processor hardware is providing
+# system timer interrupts at some interrupt interval other
+# than 10 msec.
+# CONFIG_RR_INTERVAL - The round robin timeslice will be set
+# this number of milliseconds; Round robin scheduling can
+# be disabled by setting this value to zero.
+# CONFIG_SCHED_INSTRUMENTATION - enables instrumentation in
+# scheduler to monitor system performance
+# CONFIG_TASK_NAME_SIZE - Spcifies that maximum size of a
+# task name to save in the TCB. Useful if scheduler
+# instrumentation is selected. Set to zero to disable.
+# CONFIG_START_YEAR, CONFIG_START_MONTH, CONFIG_START_DAY -
+# Used to initialize the internal time logic.
+# CONFIG_GREGORIAN_TIME - Enables Gregorian time conversions.
+# You would only need this if you are concerned about accurate
+# time conversions in the past or in the distant future.
+# CONFIG_JULIAN_TIME - Enables Julian time conversions. You
+# would only need this if you are concerned about accurate
+# time conversion in the distand past. You must also define
+# CONFIG_GREGORIAN_TIME in order to use Julian time.
+# CONFIG_DEV_CONSOLE - Set if architecture-specific logic
+# provides /dev/console. Enables stdout, stderr, stdin.
+# CONFIG_DEV_LOWCONSOLE - Use the simple, low-level serial console
+# driver (minimul support)
+# CONFIG_MUTEX_TYPES: Set to enable support for recursive and
+# errorcheck mutexes. Enables pthread_mutexattr_settype().
+# CONFIG_PRIORITY_INHERITANCE : Set to enable support for priority
+# inheritance on mutexes and semaphores.
+# CONFIG_SEM_PREALLOCHOLDERS: This setting is only used if priority
+# inheritance is enabled. It defines the maximum number of
+# different threads (minus one) that can take counts on a
+# semaphore with priority inheritance support. This may be
+# set to zero if priority inheritance is disabled OR if you
+# are only using semaphores as mutexes (only one holder) OR
+# if no more than two threads participate using a counting
+# semaphore.
+# CONFIG_SEM_NNESTPRIO. If priority inheritance is enabled,
+# then this setting is the maximum number of higher priority
+# threads (minus 1) than can be waiting for another thread
+# to release a count on a semaphore. This value may be set
+# to zero if no more than one thread is expected to wait for
+# a semaphore.
+# CONFIG_FDCLONE_DISABLE. Disable cloning of all file descriptors
+# by task_create() when a new task is started. If set, all
+# files/drivers will appear to be closed in the new task.
+# CONFIG_FDCLONE_STDIO. Disable cloning of all but the first
+# three file descriptors (stdin, stdout, stderr) by task_create()
+# when a new task is started. If set, all files/drivers will
+# appear to be closed in the new task except for stdin, stdout,
+# and stderr.
+# CONFIG_SDCLONE_DISABLE. Disable cloning of all socket
+# desciptors by task_create() when a new task is started. If
+# set, all sockets will appear to be closed in the new task.
+# CONFIG_SCHED_WORKQUEUE. Create a dedicated "worker" thread to
+# handle delayed processing from interrupt handlers. This feature
+# is required for some drivers but, if there are not complaints,
+# can be safely disabled. The worker thread also performs
+# garbage collection -- completing any delayed memory deallocations
+# from interrupt handlers. If the worker thread is disabled,
+# then that clean will be performed by the IDLE thread instead
+# (which runs at the lowest of priority and may not be appropriate
+# if memory reclamation is of high priority). If CONFIG_SCHED_WORKQUEUE
+# is enabled, then the following options can also be used:
+# CONFIG_SCHED_WORKPRIORITY - The execution priority of the worker
+# thread. Default: 50
+# CONFIG_SCHED_WORKPERIOD - How often the worker thread checks for
+# work in units of microseconds. Default: 50*1000 (50 MS).
+# CONFIG_SCHED_WORKSTACKSIZE - The stack size allocated for the worker
+# thread. Default: CONFIG_IDLETHREAD_STACKSIZE.
+# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
+# the worker thread. Default: 4
+# CONFIG_SCHED_WAITPID - Enable the waitpid() API
+# CONFIG_SCHED_ATEXIT - Enabled the atexit() API
+#
+#CONFIG_APPS_DIR=
+CONFIG_DEBUG=y
+CONFIG_DEBUG_VERBOSE=y
+CONFIG_DEBUG_SYMBOLS=y
+CONFIG_DEBUG_ANALOG=n
+CONFIG_DEBUG_FS=n
+CONFIG_DEBUG_GRAPHICS=n
+CONFIG_DEBUG_LCD=n
+CONFIG_DEBUG_USB=n
+CONFIG_DEBUG_NET=n
+CONFIG_DEBUG_RTC=n
+CONFIG_HAVE_CXX=y
+CONFIG_MM_REGIONS=2
+CONFIG_ARCH_LOWPUTC=y
+CONFIG_MSEC_PER_TICK=1
+CONFIG_RR_INTERVAL=1
+CONFIG_SCHED_INSTRUMENTATION=y
+CONFIG_TASK_NAME_SIZE=24
+CONFIG_START_YEAR=1970
+CONFIG_START_MONTH=1
+CONFIG_START_DAY=1
+CONFIG_GREGORIAN_TIME=n
+CONFIG_JULIAN_TIME=n
+CONFIG_DEV_CONSOLE=y
+CONFIG_DEV_LOWCONSOLE=n
+CONFIG_MUTEX_TYPES=n
+CONFIG_PRIORITY_INHERITANCE=y
+CONFIG_SEM_PREALLOCHOLDERS=0
+CONFIG_SEM_NNESTPRIO=8
+CONFIG_FDCLONE_DISABLE=n
+CONFIG_FDCLONE_STDIO=y
+CONFIG_SDCLONE_DISABLE=y
+CONFIG_SCHED_WORKQUEUE=n
+CONFIG_SCHED_WORKPRIORITY=50
+CONFIG_SCHED_WORKPERIOD=(50*1000)
+CONFIG_SCHED_WORKSTACKSIZE=1024
+CONFIG_SIG_SIGWORK=4
+CONFIG_SCHED_WAITPID=y
+CONFIG_SCHED_ATEXIT=n
+
+#
+# The following can be used to disable categories of
+# APIs supported by the OS. If the compiler supports
+# weak functions, then it should not be necessary to
+# disable functions unless you want to restrict usage
+# of those APIs.
+#
+# There are certain dependency relationships in these
+# features.
+#
+# o mq_notify logic depends on signals to awaken tasks
+# waiting for queues to become full or empty.
+# o pthread_condtimedwait() depends on signals to wake
+# up waiting tasks.
+#
+CONFIG_DISABLE_CLOCK=n
+CONFIG_DISABLE_POSIX_TIMERS=n
+CONFIG_DISABLE_PTHREAD=n
+CONFIG_DISABLE_SIGNALS=n
+CONFIG_DISABLE_MQUEUE=n
+CONFIG_DISABLE_MOUNTPOINT=n
+CONFIG_DISABLE_ENVIRON=n
+CONFIG_DISABLE_POLL=n
+
+#
+# Misc libc settings
+#
+# CONFIG_NOPRINTF_FIELDWIDTH - sprintf-related logic is a
+# little smaller if we do not support fieldwidthes
+#
+CONFIG_NOPRINTF_FIELDWIDTH=n
+
+#
+# Allow for architecture optimized implementations
+#
+# The architecture can provide optimized versions of the
+# following to improve system performance
+#
+CONFIG_ARCH_MEMCPY=y
+CONFIG_ARCH_MEMCMP=n
+CONFIG_ARCH_MEMMOVE=n
+CONFIG_ARCH_MEMSET=n
+CONFIG_ARCH_STRCMP=n
+CONFIG_ARCH_STRCPY=n
+CONFIG_ARCH_STRNCPY=n
+CONFIG_ARCH_STRLEN=n
+CONFIG_ARCH_STRNLEN=n
+CONFIG_ARCH_BZERO=n
+
+#
+# Sizes of configurable things (0 disables)
+#
+# CONFIG_MAX_TASKS - The maximum number of simultaneously
+# active tasks. This value must be a power of two.
+# CONFIG_MAX_TASK_ARGS - This controls the maximum number of
+# of parameters that a task may receive (i.e., maxmum value
+# of 'argc')
+# CONFIG_NPTHREAD_KEYS - The number of items of thread-
+# specific data that can be retained
+# CONFIG_NFILE_DESCRIPTORS - The maximum number of file
+# descriptors (one for each open)
+# CONFIG_NFILE_STREAMS - The maximum number of streams that
+# can be fopen'ed
+# CONFIG_NAME_MAX - The maximum size of a file name.
+# CONFIG_STDIO_BUFFER_SIZE - Size of the buffer to allocate
+# on fopen. (Only if CONFIG_NFILE_STREAMS > 0)
+# CONFIG_STDIO_LINEBUFFER - If standard C buffered I/O is enabled
+# (CONFIG_STDIO_BUFFER_SIZE > 0), then this option may be added
+# to force automatic, line-oriented flushing the output buffer
+# for putc(), fputc(), putchar(), puts(), fputs(), printf(),
+# fprintf(), and vfprintf(). When a newline is encountered in
+# the output string, the output buffer will be flushed. This
+# (slightly) increases the NuttX footprint but supports the kind
+# of behavior that people expect for printf().
+# CONFIG_NUNGET_CHARS - Number of characters that can be
+# buffered by ungetc() (Only if CONFIG_NFILE_STREAMS > 0)
+# CONFIG_PREALLOC_MQ_MSGS - The number of pre-allocated message
+# structures. The system manages a pool of preallocated
+# message structures to minimize dynamic allocations
+# CONFIG_MQ_MAXMSGSIZE - Message structures are allocated with
+# a fixed payload size given by this settin (does not include
+# other message structure overhead.
+# CONFIG_MAX_WDOGPARMS - Maximum number of parameters that
+# can be passed to a watchdog handler
+# CONFIG_PREALLOC_WDOGS - The number of pre-allocated watchdog
+# structures. The system manages a pool of preallocated
+# watchdog structures to minimize dynamic allocations
+# CONFIG_PREALLOC_TIMERS - The number of pre-allocated POSIX
+# timer structures. The system manages a pool of preallocated
+# timer structures to minimize dynamic allocations. Set to
+# zero for all dynamic allocations.
+#
+CONFIG_MAX_TASKS=32
+CONFIG_MAX_TASK_ARGS=8
+CONFIG_NPTHREAD_KEYS=4
+CONFIG_NFILE_DESCRIPTORS=20
+CONFIG_NFILE_STREAMS=20
+CONFIG_NAME_MAX=32
+CONFIG_STDIO_BUFFER_SIZE=256
+CONFIG_STDIO_LINEBUFFER=y
+CONFIG_NUNGET_CHARS=2
+CONFIG_PREALLOC_MQ_MSGS=4
+CONFIG_MQ_MAXMSGSIZE=32
+CONFIG_MAX_WDOGPARMS=2
+CONFIG_PREALLOC_WDOGS=50
+CONFIG_PREALLOC_TIMERS=50
+
+#
+# Filesystem configuration
+#
+# CONFIG_FS_FAT - Enable FAT filesystem support
+# CONFIG_FAT_SECTORSIZE - Max supported sector size
+# CONFIG_FAT_LCNAMES - Enable use of the NT-style upper/lower case 8.3
+# file name support.
+# CONFIG_FAT_LFN - Enable FAT long file names. NOTE: Microsoft claims
+# patents on FAT long file name technology. Please read the
+# disclaimer in the top-level COPYING file and only enable this
+# feature if you understand these issues.
+# CONFIG_FAT_MAXFNAME - If CONFIG_FAT_LFN is defined, then the
+# default, maximum long file name is 255 bytes. This can eat up
+# a lot of memory (especially stack space). If you are willing
+# to live with some non-standard, short long file names, then
+# define this value. A good choice would be the same value as
+# selected for CONFIG_NAME_MAX which will limit the visibility
+# of longer file names anyway.
+# CONFIG_FS_NXFFS: Enable NuttX FLASH file system (NXFF) support.
+# CONFIG_NXFFS_ERASEDSTATE: The erased state of FLASH.
+# This must have one of the values of 0xff or 0x00.
+# Default: 0xff.
+# CONFIG_NXFFS_PACKTHRESHOLD: When packing flash file data,
+# don't both with file chunks smaller than this number of data bytes.
+# CONFIG_NXFFS_MAXNAMLEN: The maximum size of an NXFFS file name.
+# Default: 255.
+# CONFIG_NXFFS_PACKTHRESHOLD: When packing flash file data,
+# don't both with file chunks smaller than this number of data bytes.
+# Default: 32.
+# CONFIG_NXFFS_TAILTHRESHOLD: clean-up can either mean
+# packing files together toward the end of the file or, if file are
+# deleted at the end of the file, clean up can simply mean erasing
+# the end of FLASH memory so that it can be re-used again. However,
+# doing this can also harm the life of the FLASH part because it can
+# mean that the tail end of the FLASH is re-used too often. This
+# threshold determines if/when it is worth erased the tail end of FLASH
+# and making it available for re-use (and possible over-wear).
+# Default: 8192.
+# CONFIG_FS_ROMFS - Enable ROMFS filesystem support
+# CONFIG_FS_RAMMAP - For file systems that do not support XIP, this
+# option will enable a limited form of memory mapping that is
+# implemented by copying whole files into memory.
+#
+CONFIG_FS_FAT=y
+CONFIG_FAT_LCNAMES=y
+CONFIG_FAT_LFN=y
+CONFIG_FAT_MAXFNAME=32
+CONFIG_FS_NXFFS=n
+CONFIG_FS_ROMFS=y
+
+#
+# SPI-based MMC/SD driver
+#
+# CONFIG_MMCSD_NSLOTS
+# Number of MMC/SD slots supported by the driver
+# CONFIG_MMCSD_READONLY
+# Provide read-only access (default is read/write)
+# CONFIG_MMCSD_SPICLOCK - Maximum SPI clock to drive MMC/SD card.
+# Default is 20MHz, current setting 24 MHz
+#
+CONFIG_MMCSD_NSLOTS=1
+CONFIG_MMCSD_READONLY=n
+CONFIG_MMCSD_SPICLOCK=24000000
+
+#
+# Block driver buffering
+#
+# CONFIG_FS_READAHEAD
+# Enable read-ahead buffering
+# CONFIG_FS_WRITEBUFFER
+# Enable write buffering
+#
+CONFIG_FS_READAHEAD=n
+CONFIG_FS_WRITEBUFFER=n
+
+#
+# RTC Configuration
+#
+# CONFIG_RTC - Enables general support for a hardware RTC. Specific
+# architectures may require other specific settings.
+# CONFIG_RTC_DATETIME - There are two general types of RTC: (1) A simple
+# battery backed counter that keeps the time when power is down, and (2)
+# A full date / time RTC the provides the date and time information, often
+# in BCD format. If CONFIG_RTC_DATETIME is selected, it specifies this
+# second kind of RTC. In this case, the RTC is used to "seed" the normal
+# NuttX timer and the NuttX system timer provides for higher resoution
+# time.
+# CONFIG_RTC_HIRES - If CONFIG_RTC_DATETIME not selected, then the simple,
+# battery backed counter is used. There are two different implementations
+# of such simple counters based on the time resolution of the counter:
+# The typical RTC keeps time to resolution of 1 second, usually
+# supporting a 32-bit time_t value. In this case, the RTC is used to
+# "seed" the normal NuttX timer and the NuttX timer provides for higher
+# resoution time. If CONFIG_RTC_HIRES is enabled in the NuttX configuration,
+# then the RTC provides higher resolution time and completely replaces the
+# system timer for purpose of date and time.
+# CONFIG_RTC_FREQUENCY - If CONFIG_RTC_HIRES is defined, then the frequency
+# of the high resolution RTC must be provided. If CONFIG_RTC_HIRES is
+# not defined, CONFIG_RTC_FREQUENCY is assumed to be one.
+# CONFIG_RTC_ALARM - Enable if the RTC hardware supports setting of an
+# alarm. A callback function will be executed when the alarm goes off
+#
+CONFIG_RTC=n
+CONFIG_RTC_DATETIME=y
+CONFIG_RTC_HIRES=n
+CONFIG_RTC_FREQUENCY=n
+CONFIG_RTC_ALARM=n
+
+#
+# USB Device Configuration
+#
+# CONFIG_USBDEV
+# Enables USB device support
+# CONFIG_USBDEV_ISOCHRONOUS
+# Build in extra support for isochronous endpoints
+# CONFIG_USBDEV_DUALSPEED
+# Hardware handles high and full speed operation (USB 2.0)
+# CONFIG_USBDEV_SELFPOWERED
+# Will cause USB features to indicate that the device is
+# self-powered
+# CONFIG_USBDEV_MAXPOWER
+# Maximum power consumption in mA
+# CONFIG_USBDEV_TRACE
+# Enables USB tracing for debug
+# CONFIG_USBDEV_TRACE_NRECORDS
+# Number of trace entries to remember
+#
+CONFIG_USBDEV=y
+CONFIG_USBDEV_ISOCHRONOUS=n
+CONFIG_USBDEV_DUALSPEED=n
+CONFIG_USBDEV_SELFPOWERED=y
+CONFIG_USBDEV_REMOTEWAKEUP=n
+CONFIG_USBDEV_MAXPOWER=500
+CONFIG_USBDEV_TRACE=n
+CONFIG_USBDEV_TRACE_NRECORDS=512
+
+#
+# USB Serial Device Configuration (Prolifics PL2303 emulation)
+#
+# CONFIG_PL2303
+# Enable compilation of the USB serial driver
+# CONFIG_PL2303_EPINTIN
+# The logical 7-bit address of a hardware endpoint that supports
+# interrupt IN operation
+# CONFIG_PL2303_EPBULKOUT
+# The logical 7-bit address of a hardware endpoint that supports
+# bulk OUT operation
+# CONFIG_PL2303_EPBULKIN
+# The logical 7-bit address of a hardware endpoint that supports
+# bulk IN operation
+# # CONFIG_PL2303_NWRREQS and CONFIG_PL2303_NRDREQS
+# The number of write/read requests that can be in flight
+# CONFIG_PL2303_VENDORID and CONFIG_PL2303_VENDORSTR
+# The vendor ID code/string
+# CONFIG_PL2303_PRODUCTID and CONFIG_PL2303_PRODUCTSTR
+# The product ID code/string
+# CONFIG_PL2303_RXBUFSIZE and CONFIG_PL2303_TXBUFSIZE
+# Size of the serial receive/transmit buffers
+#
+CONFIG_PL2303=n
+CONFIG_PL2303_EPINTIN=1
+CONFIG_PL2303_EPBULKOUT=2
+CONFIG_PL2303_EPBULKIN=3
+CONFIG_PL2303_NWRREQS=4
+CONFIG_PL2303_NRDREQS=4
+CONFIG_PL2303_VENDORID=0x067b
+CONFIG_PL2303_PRODUCTID=0x2303
+CONFIG_PL2303_VENDORSTR="Nuttx"
+CONFIG_PL2303_PRODUCTSTR="USBdev Serial"
+CONFIG_PL2303_RXBUFSIZE=512
+CONFIG_PL2303_TXBUFSIZE=512
+
+#
+# USB serial device class driver (Standard CDC ACM class)
+#
+# CONFIG_CDCACM
+# Enable compilation of the USB serial driver
+# CONFIG_CDCACM_CONSOLE
+# Configures the CDC/ACM serial port as the console device.
+# CONFIG_CDCACM_EP0MAXPACKET
+# Endpoint 0 max packet size. Default 64
+# CONFIG_CDCACM_EPINTIN
+# The logical 7-bit address of a hardware endpoint that supports
+# interrupt IN operation. Default 2.
+# CONFIG_CDCACM_EPINTIN_FSSIZE
+# Max package size for the interrupt IN endpoint if full speed mode.
+# Default 64.
+# CONFIG_CDCACM_EPINTIN_HSSIZE
+# Max package size for the interrupt IN endpoint if high speed mode.
+# Default 64
+# CONFIG_CDCACM_EPBULKOUT
+# The logical 7-bit address of a hardware endpoint that supports
+# bulk OUT operation. Default 4.
+# CONFIG_CDCACM_EPBULKOUT_FSSIZE
+# Max package size for the bulk OUT endpoint if full speed mode.
+# Default 64.
+# CONFIG_CDCACM_EPBULKOUT_HSSIZE
+# Max package size for the bulk OUT endpoint if high speed mode.
+# Default 512.
+# CONFIG_CDCACM_EPBULKIN
+# The logical 7-bit address of a hardware endpoint that supports
+# bulk IN operation. Default 3.
+# CONFIG_CDCACM_EPBULKIN_FSSIZE
+# Max package size for the bulk IN endpoint if full speed mode.
+# Default 64.
+# CONFIG_CDCACM_EPBULKIN_HSSIZE
+# Max package size for the bulk IN endpoint if high speed mode.
+# Default 512.
+# CONFIG_CDCACM_NWRREQS and CONFIG_CDCACM_NRDREQS
+# The number of write/read requests that can be in flight.
+# Default 256.
+# CONFIG_CDCACM_VENDORID and CONFIG_CDCACM_VENDORSTR
+# The vendor ID code/string. Default 0x0525 and "NuttX"
+# 0x0525 is the Netchip vendor and should not be used in any
+# products. This default VID was selected for compatibility with
+# the Linux CDC ACM default VID.
+# CONFIG_CDCACM_PRODUCTID and CONFIG_CDCACM_PRODUCTSTR
+# The product ID code/string. Default 0xa4a7 and "CDC/ACM Serial"
+# 0xa4a7 was selected for compatibility with the Linux CDC ACM
+# default PID.
+# CONFIG_CDCACM_RXBUFSIZE and CONFIG_CDCACM_TXBUFSIZE
+# Size of the serial receive/transmit buffers. Default 256.
+#
+CONFIG_CDCACM=y
+CONFIG_CDCACM_CONSOLE=n
+#CONFIG_CDCACM_EP0MAXPACKET
+CONFIG_CDCACM_EPINTIN=1
+#CONFIG_CDCACM_EPINTIN_FSSIZE
+#CONFIG_CDCACM_EPINTIN_HSSIZE
+CONFIG_CDCACM_EPBULKOUT=3
+#CONFIG_CDCACM_EPBULKOUT_FSSIZE
+#CONFIG_CDCACM_EPBULKOUT_HSSIZE
+CONFIG_CDCACM_EPBULKIN=2
+#CONFIG_CDCACM_EPBULKIN_FSSIZE
+#CONFIG_CDCACM_EPBULKIN_HSSIZE
+#CONFIG_CDCACM_NWRREQS
+#CONFIG_CDCACM_NRDREQS
+CONFIG_CDCACM_VENDORID=0x26AC
+CONFIG_CDCACM_VENDORSTR="3D Robotics"
+CONFIG_CDCACM_PRODUCTID=0x0010
+CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v1.6"
+#CONFIG_CDCACM_RXBUFSIZE
+#CONFIG_CDCACM_TXBUFSIZE
+
+#
+# USB Storage Device Configuration
+#
+# CONFIG_USBMSC
+# Enable compilation of the USB storage driver
+# CONFIG_USBMSC_EP0MAXPACKET
+# Max packet size for endpoint 0
+# CONFIG_USBMSC_EPBULKOUT and CONFIG_USBMSC_EPBULKIN
+# The logical 7-bit address of a hardware endpoints that support
+# bulk OUT and IN operations
+# CONFIG_USBMSC_NWRREQS and CONFIG_USBMSC_NRDREQS
+# The number of write/read requests that can be in flight
+# CONFIG_USBMSC_BULKINREQLEN and CONFIG_USBMSC_BULKOUTREQLEN
+# The size of the buffer in each write/read request. This
+# value needs to be at least as large as the endpoint
+# maxpacket and ideally as large as a block device sector.
+# CONFIG_USBMSC_VENDORID and CONFIG_USBMSC_VENDORSTR
+# The vendor ID code/string
+# CONFIG_USBMSC_PRODUCTID and CONFIG_USBMSC_PRODUCTSTR
+# The product ID code/string
+# CONFIG_USBMSC_REMOVABLE
+# Select if the media is removable
+#
+CONFIG_USBMSC=n
+CONFIG_USBMSC_EP0MAXPACKET=64
+CONFIG_USBMSC_EPBULKOUT=2
+CONFIG_USBMSC_EPBULKIN=5
+CONFIG_USBMSC_NRDREQS=2
+CONFIG_USBMSC_NWRREQS=2
+CONFIG_USBMSC_BULKINREQLEN=256
+CONFIG_USBMSC_BULKOUTREQLEN=256
+CONFIG_USBMSC_VENDORID=0x584e
+CONFIG_USBMSC_VENDORSTR="NuttX"
+CONFIG_USBMSC_PRODUCTID=0x5342
+CONFIG_USBMSC_PRODUCTSTR="USBdev Storage"
+CONFIG_USBMSC_VERSIONNO=0x0399
+CONFIG_USBMSC_REMOVABLE=y
+
+
+#
+# Settings for apps/nshlib
+#
+# CONFIG_NSH_BUILTIN_APPS - Support external registered,
+# "named" applications that can be executed from the NSH
+# command line (see apps/README.txt for more information).
+# CONFIG_NSH_FILEIOSIZE - Size of a static I/O buffer
+# CONFIG_NSH_STRERROR - Use strerror(errno)
+# CONFIG_NSH_LINELEN - Maximum length of one command line
+# CONFIG_NSH_STACKSIZE - Stack size to use for new threads.
+# CONFIG_NSH_NESTDEPTH - Max number of nested if-then[-else]-fi
+# CONFIG_NSH_DISABLESCRIPT - Disable scripting support
+# CONFIG_NSH_DISABLEBG - Disable background commands
+# CONFIG_NSH_ROMFSETC - Use startup script in /etc
+# CONFIG_NSH_CONSOLE - Use serial console front end
+# CONFIG_NSH_TELNET - Use telnetd console front end
+# CONFIG_NSH_ARCHINIT - Platform provides architecture
+# specific initialization (nsh_archinitialize()).
+#
+# If CONFIG_NSH_TELNET is selected:
+# CONFIG_NSH_IOBUFFER_SIZE -- Telnetd I/O buffer size
+# CONFIG_NSH_DHCPC - Obtain address using DHCP
+# CONFIG_NSH_IPADDR - Provides static IP address
+# CONFIG_NSH_DRIPADDR - Provides static router IP address
+# CONFIG_NSH_NETMASK - Provides static network mask
+# CONFIG_NSH_NOMAC - Use a bogus MAC address
+#
+# If CONFIG_NSH_ROMFSETC is selected:
+# CONFIG_NSH_ROMFSMOUNTPT - ROMFS mountpoint
+# CONFIG_NSH_INITSCRIPT - Relative path to init script
+# CONFIG_NSH_ROMFSDEVNO - ROMFS RAM device minor
+# CONFIG_NSH_ROMFSSECTSIZE - ROMF sector size
+# CONFIG_NSH_FATDEVNO - FAT FS RAM device minor
+# CONFIG_NSH_FATSECTSIZE - FAT FS sector size
+# CONFIG_NSH_FATNSECTORS - FAT FS number of sectors
+# CONFIG_NSH_FATMOUNTPT - FAT FS mountpoint
+#
+CONFIG_NSH_BUILTIN_APPS=y
+CONFIG_NSH_FILEIOSIZE=512
+CONFIG_NSH_STRERROR=y
+CONFIG_NSH_LINELEN=128
+CONFIG_NSH_NESTDEPTH=8
+CONFIG_NSH_DISABLESCRIPT=n
+CONFIG_NSH_DISABLEBG=n
+CONFIG_NSH_ROMFSETC=y
+CONFIG_NSH_ARCHROMFS=y
+CONFIG_NSH_CONSOLE=y
+CONFIG_NSH_USBCONSOLE=n
+CONFIG_NSH_USBCONDEV="/dev/ttyACM0"
+CONFIG_NSH_TELNET=n
+CONFIG_NSH_ARCHINIT=y
+CONFIG_NSH_IOBUFFER_SIZE=512
+CONFIG_NSH_DHCPC=n
+CONFIG_NSH_NOMAC=y
+CONFIG_NSH_IPADDR=(10<<24|0<<16|0<<8|2)
+CONFIG_NSH_DRIPADDR=(10<<24|0<<16|0<<8|1)
+CONFIG_NSH_NETMASK=(255<<24|255<<16|255<<8|0)
+CONFIG_NSH_ROMFSMOUNTPT="/etc"
+CONFIG_NSH_INITSCRIPT="init.d/rcS"
+CONFIG_NSH_ROMFSDEVNO=0
+CONFIG_NSH_ROMFSSECTSIZE=128 # Default 64, increased to allow for more than 64 folders on the sdcard
+CONFIG_NSH_FATDEVNO=1
+CONFIG_NSH_FATSECTSIZE=512
+CONFIG_NSH_FATNSECTORS=1024
+CONFIG_NSH_FATMOUNTPT=/tmp
+
+#
+# Architecture-specific NSH options
+#
+CONFIG_NSH_MMCSDSPIPORTNO=3
+CONFIG_NSH_MMCSDSLOTNO=0
+CONFIG_NSH_MMCSDMINOR=0
+
+#
+# Settings for mavlink
+#
+# CONFIG_MAVLINK - Enable MAVLINK app
+# CONFIG_NSH_BUILTIN_APPS - Build the ADC test as an NSH built-in function.
+# Default: Built as a standalone problem
+CONFIG_MAVLINK=y
+
+#
+# Stack and heap information
+#
+# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP
+# operation from FLASH but must copy initialized .data sections to RAM.
+# (should also be =n for the STM3240G-EVAL which always runs from flash)
+# CONFIG_BOOT_COPYTORAM - Some configurations boot in FLASH
+# but copy themselves entirely into RAM for better performance.
+# CONFIG_CUSTOM_STACK - The up_ implementation will handle
+# all stack operations outside of the nuttx model.
+# CONFIG_STACK_POINTER - The initial stack pointer (arm7tdmi only)
+# CONFIG_IDLETHREAD_STACKSIZE - The size of the initial stack.
+# This is the thread that (1) performs the inital boot of the system up
+# to the point where user_start() is spawned, and (2) there after is the
+# IDLE thread that executes only when there is no other thread ready to
+# run.
+# CONFIG_USERMAIN_STACKSIZE - The size of the stack to allocate
+# for the main user thread that begins at the user_start() entry point.
+# CONFIG_PTHREAD_STACK_MIN - Minimum pthread stack size
+# CONFIG_PTHREAD_STACK_DEFAULT - Default pthread stack size
+# CONFIG_HEAP_BASE - The beginning of the heap
+# CONFIG_HEAP_SIZE - The size of the heap
+#
+CONFIG_BOOT_RUNFROMFLASH=n
+CONFIG_BOOT_COPYTORAM=n
+CONFIG_CUSTOM_STACK=n
+CONFIG_STACK_POINTER=
+# Idle thread needs 4096 bytes
+# default 1 KB is not enough
+CONFIG_IDLETHREAD_STACKSIZE=4096
+CONFIG_USERMAIN_STACKSIZE=3072
+CONFIG_PTHREAD_STACK_MIN=512
+CONFIG_PTHREAD_STACK_DEFAULT=2048
+CONFIG_HEAP_BASE=
+CONFIG_HEAP_SIZE=
diff --git a/nuttx/configs/px4fmu/nsh/setenv.sh b/nuttx/configs/px4fmu/nsh/setenv.sh
new file mode 100755
index 000000000..265520997
--- /dev/null
+++ b/nuttx/configs/px4fmu/nsh/setenv.sh
@@ -0,0 +1,67 @@
+#!/bin/bash
+# configs/stm3240g-eval/nsh/setenv.sh
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+
+if [ "$_" = "$0" ] ; then
+ echo "You must source this script, not run it!" 1>&2
+ exit 1
+fi
+
+WD=`pwd`
+if [ ! -x "setenv.sh" ]; then
+ echo "This script must be executed from the top-level NuttX build directory"
+ exit 1
+fi
+
+if [ -z "${PATH_ORIG}" ]; then
+ export PATH_ORIG="${PATH}"
+fi
+
+# This the Cygwin path to the location where I installed the RIDE
+# toolchain under windows. You will also have to edit this if you install
+# the RIDE toolchain in any other location
+#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
+
+# This the Cygwin path to the location where I installed the CodeSourcery
+# toolchain under windows. You will also have to edit this if you install
+# the CodeSourcery toolchain in any other location
+export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
+
+# This the Cygwin path to the location where I build the buildroot
+# toolchain.
+#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+
+# Add the path to the toolchain to the PATH varialble
+export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+echo "PATH : ${PATH}"
diff --git a/nuttx/configs/px4fmu/src/Makefile b/nuttx/configs/px4fmu/src/Makefile
new file mode 100644
index 000000000..2e3138aaa
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/Makefile
@@ -0,0 +1,102 @@
+############################################################################
+# configs/px4fmu/src/Makefile
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <gnutt@nuttx.org>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+-include $(TOPDIR)/Make.defs
+
+CFLAGS += -I$(TOPDIR)/sched
+
+ASRCS =
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+
+CSRCS = up_boot.c up_leds.c up_spi.c up_hrt.c \
+ drv_gpio.c drv_bma180.c drv_l3gd20.c \
+ drv_led.c drv_hmc5833l.c drv_ms5611.c drv_eeprom.c \
+ drv_tone_alarm.c up_pwm_servo.c up_usbdev.c \
+ up_cpuload.c drv_mpu6000.c
+
+ifeq ($(CONFIG_NSH_ARCHINIT),y)
+CSRCS += up_nsh.c
+endif
+
+ifeq ($(CONFIG_ADC),y)
+CSRCS += up_adc.c
+endif
+
+ifeq ($(CONFIG_CAN),y)
+CSRCS += up_can.c
+endif
+
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
+ifeq ($(WINTOOL),y)
+ CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
+else
+ CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
+endif
+
+all: libboard$(LIBEXT)
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+libboard$(LIBEXT): $(OBJS)
+ @( for obj in $(OBJS) ; do \
+ $(call ARCHIVE, $@, $${obj}); \
+ done ; )
+
+.depend: Makefile $(SRCS)
+ @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ @touch $@
+
+depend: .depend
+
+clean:
+ @rm -f libboard$(LIBEXT) *~ .*.swp
+ $(call CLEAN)
+
+distclean: clean
+ @rm -f Make.dep .depend
+
+-include Make.dep
+
diff --git a/nuttx/configs/px4fmu/src/drv_bma180.c b/nuttx/configs/px4fmu/src/drv_bma180.c
new file mode 100644
index 000000000..da80cc2e2
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_bma180.c
@@ -0,0 +1,341 @@
+/*
+ * Copyright (C) 2012 Lorenz Meier. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name of the author or the names of contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/*
+ * Driver for the Bosch BMA 180 MEMS accelerometer
+ */
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/spi.h>
+#include <nuttx/arch.h>
+#include <arch/board/board.h>
+
+#include <stdio.h>
+
+#include "chip.h"
+#include "px4fmu-internal.h"
+
+#include <arch/board/drv_bma180.h>
+
+/*
+ * BMA180 registers
+ */
+
+/* Important Notes:
+ *
+ * - MAX SPI clock: 25 MHz
+ * - Readout time: 0.417 ms in high accuracy mode
+ * - Boot / ready time: 1.27 ms
+ *
+ */
+
+#define DIR_READ (1<<7)
+#define DIR_WRITE (0<<7)
+#define ADDR_INCREMENT (1<<6)
+
+#define ADDR_CHIP_ID 0x00
+#define CHIP_ID 0x03
+#define ADDR_VERSION 0x01
+
+#define ADDR_CTRL_REG0 0x0D
+#define ADDR_CTRL_REG1 0x0E
+#define ADDR_CTRL_REG2 0x0F
+#define ADDR_BWTCS 0x20
+#define ADDR_CTRL_REG3 0x21
+#define ADDR_CTRL_REG4 0x22
+#define ADDR_OLSB1 0x35
+
+#define ADDR_ACC_X_LSB 0x02
+#define ADDR_ACC_Z_MSB 0x07
+#define ADDR_TEMPERATURE 0x08
+
+#define ADDR_STATUS_REG1 0x09
+#define ADDR_STATUS_REG2 0x0A
+#define ADDR_STATUS_REG3 0x0B
+#define ADDR_STATUS_REG4 0x0C
+
+#define ADDR_RESET 0x10
+#define SOFT_RESET 0xB6
+
+#define ADDR_DIS_I2C 0x27
+
+#define REG0_WRITE_ENABLE 0x10
+
+#define RANGEMASK 0x0E
+#define BWMASK 0xF0
+
+
+static ssize_t bma180_read(struct file *filp, FAR char *buffer, size_t buflen);
+static int bma180_ioctl(struct file *filp, int cmd, unsigned long arg);
+
+static const struct file_operations bma180_fops = {
+ .read = bma180_read,
+ .ioctl = bma180_ioctl,
+};
+
+struct bma180_dev_s
+{
+ struct spi_dev_s *spi;
+ int spi_id;
+ uint8_t rate;
+ struct bma180_buffer *buffer;
+};
+
+static struct bma180_dev_s bma180_dev;
+
+static void bma180_write_reg(uint8_t address, uint8_t data);
+static uint8_t bma180_read_reg(uint8_t address);
+static bool read_fifo(uint16_t *data);
+static int bma180_set_range(uint8_t range);
+static int bma180_set_rate(uint8_t rate);
+
+static void
+bma180_write_reg(uint8_t address, uint8_t data)
+{
+ uint8_t cmd[2] = { address | DIR_WRITE, data };
+
+ SPI_SELECT(bma180_dev.spi, bma180_dev.spi_id, true);
+ SPI_SNDBLOCK(bma180_dev.spi, &cmd, sizeof(cmd));
+ SPI_SELECT(bma180_dev.spi, bma180_dev.spi_id, false);
+}
+
+static uint8_t
+bma180_read_reg(uint8_t address)
+{
+ uint8_t cmd[2] = {address | DIR_READ, 0};
+ uint8_t data[2];
+
+ SPI_SELECT(bma180_dev.spi, bma180_dev.spi_id, true);
+ SPI_EXCHANGE(bma180_dev.spi, cmd, data, sizeof(cmd));
+ SPI_SELECT(bma180_dev.spi, bma180_dev.spi_id, false);
+
+ return data[1];
+}
+
+static bool
+read_fifo(uint16_t *data)
+{
+ struct { /* status register and data as read back from the device */
+ uint8_t cmd;
+ int16_t x;
+ int16_t y;
+ int16_t z;
+ uint8_t temp;
+ } __attribute__((packed)) report;
+
+ report.cmd = ADDR_ACC_X_LSB | DIR_READ | ADDR_INCREMENT;
+
+ SPI_LOCK(bma180_dev.spi, true);
+ report.x = bma180_read_reg(ADDR_ACC_X_LSB);
+ report.x |= (bma180_read_reg(ADDR_ACC_X_LSB+1) << 8);
+ report.y = bma180_read_reg(ADDR_ACC_X_LSB+2);
+ report.y |= (bma180_read_reg(ADDR_ACC_X_LSB+3) << 8);
+ report.z = bma180_read_reg(ADDR_ACC_X_LSB+4);
+ report.z |= (bma180_read_reg(ADDR_ACC_X_LSB+5) << 8);
+ report.temp = bma180_read_reg(ADDR_ACC_X_LSB+6);
+ SPI_LOCK(bma180_dev.spi, false);
+
+ /* Collect status and remove two top bits */
+
+ uint8_t new_data = (report.x & 0x01) + (report.x & 0x01) + (report.x & 0x01);
+ report.x = (report.x >> 2);
+ report.y = (report.y >> 2);
+ report.z = (report.z >> 2);
+
+ data[0] = report.x;
+ data[1] = report.y;
+ data[2] = report.z;
+
+ /* return 1 for all three axes new */
+ return (new_data > 0); // bit funky, depends on timing
+}
+
+static int
+bma180_set_range(uint8_t range)
+{
+ /* enable writing to chip config */
+ uint8_t ctrl0 = bma180_read_reg(ADDR_CTRL_REG0);
+ ctrl0 |= REG0_WRITE_ENABLE;
+ bma180_write_reg(ADDR_CTRL_REG0, ctrl0);
+
+ /* set range */
+ uint8_t olsb1 = bma180_read_reg(ADDR_OLSB1);
+ olsb1 &= (~RANGEMASK);
+ olsb1 |= (range);// & RANGEMASK);
+ bma180_write_reg(ADDR_OLSB1, olsb1);
+
+ // up_udelay(500);
+
+ /* block writing to chip config */
+ ctrl0 = bma180_read_reg(ADDR_CTRL_REG0);
+ ctrl0 &= (~REG0_WRITE_ENABLE);
+ bma180_write_reg(ADDR_CTRL_REG0, ctrl0);
+
+ uint8_t new_olsb1 = bma180_read_reg(ADDR_OLSB1);
+
+ /* return 0 on success, 1 on failure */
+ return !(olsb1 == new_olsb1);
+}
+
+static int
+bma180_set_rate(uint8_t rate)
+{
+ /* enable writing to chip config */
+ uint8_t ctrl0 = bma180_read_reg(ADDR_CTRL_REG0);
+ ctrl0 |= REG0_WRITE_ENABLE;
+ bma180_write_reg(ADDR_CTRL_REG0, ctrl0);
+
+ /* set rate / bandwidth */
+ uint8_t bwtcs = bma180_read_reg(ADDR_BWTCS);
+ bwtcs &= (~BWMASK);
+ bwtcs |= (rate);// & BWMASK);
+ bma180_write_reg(ADDR_BWTCS, bwtcs);
+
+ // up_udelay(500);
+
+ /* block writing to chip config */
+ ctrl0 = bma180_read_reg(ADDR_CTRL_REG0);
+ ctrl0 &= (~REG0_WRITE_ENABLE);
+ bma180_write_reg(ADDR_CTRL_REG0, ctrl0);
+
+ uint8_t new_bwtcs = bma180_read_reg(ADDR_BWTCS);
+
+ /* return 0 on success, 1 on failure */
+ return !(bwtcs == new_bwtcs);
+}
+
+static ssize_t
+bma180_read(struct file *filp, char *buffer, size_t buflen)
+{
+ /* if the buffer is large enough, and data are available, return success */
+ if (buflen >= 6) {
+ if (read_fifo((uint16_t *)buffer))
+ return 6;
+
+ /* no data */
+ return 0;
+ }
+
+ /* buffer too small */
+ errno = ENOSPC;
+ return ERROR;
+}
+
+static int
+bma180_ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ int result = ERROR;
+
+ switch (cmd) {
+ case BMA180_SETRATE:
+ result = bma180_set_rate(arg);
+ break;
+
+ case BMA180_SETRANGE:
+ result = bma180_set_range(arg);
+ break;
+
+ case BMA180_SETBUFFER:
+ bma180_dev.buffer = (struct bma180_buffer *)arg;
+ result = 0;
+ break;
+ }
+
+ if (result)
+ errno = EINVAL;
+ return result;
+}
+
+int
+bma180_attach(struct spi_dev_s *spi, int spi_id)
+{
+ int result = ERROR;
+
+ bma180_dev.spi = spi;
+ bma180_dev.spi_id = spi_id;
+
+ SPI_LOCK(bma180_dev.spi, true);
+
+ /* verify that the device is attached and functioning */
+ if (bma180_read_reg(ADDR_CHIP_ID) == CHIP_ID) {
+
+ bma180_write_reg(ADDR_RESET, SOFT_RESET); // page 48
+
+ up_udelay(13000); // wait 12 ms, see page 49
+
+ /* Configuring the BMA180 */
+
+ /* enable writing to chip config */
+ uint8_t ctrl0 = bma180_read_reg(ADDR_CTRL_REG0);
+ ctrl0 |= REG0_WRITE_ENABLE;
+ bma180_write_reg(ADDR_CTRL_REG0, ctrl0);
+
+ /* disable I2C interface, datasheet page 31 */
+ uint8_t disi2c = bma180_read_reg(ADDR_DIS_I2C);
+ disi2c |= 0x01;
+ bma180_write_reg(ADDR_DIS_I2C, disi2c);
+
+ /* block writing to chip config */
+ ctrl0 = bma180_read_reg(ADDR_CTRL_REG0);
+ ctrl0 &= (~REG0_WRITE_ENABLE);
+ bma180_write_reg(ADDR_CTRL_REG0, ctrl0);
+
+ // up_udelay(500);
+
+ /* set rate */
+ result = bma180_set_rate(BMA180_RATE_LP_600HZ);
+
+ // up_udelay(500);
+
+ /* set range */
+ result += bma180_set_range(BMA180_RANGE_4G);
+
+ // up_udelay(500);
+
+ if (result == 0) {
+ /* make ourselves available */
+ register_driver("/dev/bma180", &bma180_fops, 0666, NULL);
+ }
+ } else {
+ errno = EIO;
+ }
+
+ SPI_LOCK(bma180_dev.spi, false);
+
+ return result;
+}
+
diff --git a/nuttx/configs/px4fmu/src/drv_eeprom.c b/nuttx/configs/px4fmu/src/drv_eeprom.c
new file mode 100644
index 000000000..c22062ec5
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_eeprom.c
@@ -0,0 +1,522 @@
+/*
+ * Copyright (C) 2012 Lorenz Meier. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name of the author or the names of contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/*
+ * Generic driver for I2C EEPROMs with 8 bit or 16 bit addressing
+ */
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+#include <errno.h>
+#include <string.h>
+#include <stdio.h>
+#include <unistd.h>
+
+#include <nuttx/i2c.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "chip.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+#include <arch/board/drv_eeprom.h>
+
+/* Split I2C transfers into smaller chunks to make sure to stay within tight timeout limits */
+
+/* check defines */
+#ifndef MAX_EEPROMS
+ #error MAX_EEPROMS number must be defined (1-3)
+#endif
+
+#if (MAX_EEPROMS > 3)
+ #error Currently only a maximum of three EEPROMS is supported, add missing code around here: __FILE__:__LINE__
+#endif
+static int eeprom_open0(FAR struct file *filp);
+static int eeprom_close0(FAR struct file *filp);
+static ssize_t eeprom_read0(struct file *filp, FAR char *buffer, size_t buflen);
+static ssize_t eeprom_write0(struct file *filp, FAR const char *buffer, size_t buflen);
+static off_t eeprom_seek0(FAR struct file *filp, off_t offset, int whence);
+#if (MAX_EEPROMS > 1)
+static int eeprom_open1(FAR struct file *filp);
+static int eeprom_close1(FAR struct file *filp);
+static ssize_t eeprom_read1(struct file *filp, FAR char *buffer, size_t buflen);
+static ssize_t eeprom_write1(struct file *filp, FAR const char *buffer, size_t buflen);
+static off_t eeprom_seek1(FAR struct file *filp, off_t offset, int whence);
+#endif
+#if (MAX_EEPROMS > 2)
+static int eeprom_open2(FAR struct file *filp);
+static int eeprom_close2(FAR struct file *filp);
+static ssize_t eeprom_read2(struct file *filp, FAR char *buffer, size_t buflen);
+static ssize_t eeprom_write2(struct file *filp, FAR const char *buffer, size_t buflen);
+static off_t eeprom_seek2(FAR struct file *filp, off_t offset, int whence);
+#endif
+
+static const struct file_operations eeprom_fops[MAX_EEPROMS] = {{
+ .open = eeprom_open0,
+ .close = eeprom_close0,
+ .read = eeprom_read0,
+ .write = eeprom_write0,
+ .seek = eeprom_seek0,
+ .ioctl = 0,
+#ifndef CONFIG_DISABLE_POLL
+ .poll = 0
+#endif
+}
+#if (MAX_EEPROMS > 1)
+,{
+ .open = eeprom_open1,
+ .close = eeprom_close1,
+ .read = eeprom_read1,
+ .write = eeprom_write1,
+ .seek = eeprom_seek1,
+}
+#endif
+#if (MAX_EEPROMS > 2)
+,{
+ .open = eeprom_open2,
+ .close = eeprom_close2,
+ .read = eeprom_read2,
+ .write = eeprom_write2,
+ .seek = eeprom_seek2,
+}
+#endif
+};
+
+static FAR struct eeprom_dev_s
+{
+ struct i2c_dev_s *i2c;
+ uint8_t eeprom_address;
+ uint16_t eeprom_size_bytes;
+ uint16_t eeprom_page_size_bytes;
+ uint16_t eeprom_page_write_time;
+ off_t offset;
+ bool is_open;
+} eeprom_dev[MAX_EEPROMS];
+
+static int
+eeprom_open0(FAR struct file *filp)
+{
+ /* only allow one open at a time */
+ if (eeprom_dev[0].is_open) {
+ errno = EBUSY;
+ return -EBUSY;
+ }
+ /* reset pointer */
+ //eeprom_dev[0].is_open = true;
+ eeprom_dev[0].offset = 0;
+ return OK;
+}
+#if (MAX_EEPROMS > 1)
+static int
+eeprom_open1(FAR struct file *filp)
+{
+ /* only allow one open at a time */
+ if (eeprom_dev[1].is_open) {
+ errno = EBUSY;
+ return -EBUSY;
+ }
+ /* reset pointer */
+ //eeprom_dev[1].is_open = true;
+ eeprom_dev[1].offset = 0;
+ return OK;
+}
+#endif
+#if (MAX_EEPROMS > 2)
+static int
+eeprom_open2(FAR struct file *filp)
+{
+ /* only allow one open at a time */
+ if (eeprom_dev[2].is_open) {
+ errno = EBUSY;
+ return -EBUSY;
+ }
+ /* reset pointer */
+ //eeprom_dev[2].is_open = true;
+ eeprom_dev[2].offset = 0;
+ return OK;
+}
+#endif
+
+static int
+eeprom_close0(FAR struct file *filp)
+{
+ eeprom_dev[0].is_open = false;
+ return OK;
+}
+#if (MAX_EEPROMS > 1)
+static int
+eeprom_close1(FAR struct file *filp)
+{
+ eeprom_dev[1].is_open = false;
+ return OK;
+}
+#endif
+#if (MAX_EEPROMS > 2)
+static int
+eeprom_close2(FAR struct file *filp)
+{
+ eeprom_dev[2].is_open = false;
+ return OK;
+}
+#endif
+
+static int
+eeprom_read_internal(int dev, uint16_t len, uint8_t *data)
+{
+ /* abort if the number of requested bytes exceeds the EEPROM size */
+ if (eeprom_dev[dev].offset + len > eeprom_dev[dev].eeprom_size_bytes)
+ {
+ errno = ENOSPC;
+ return -ENOSPC;
+ }
+
+ /* set device address */
+ I2C_SETADDRESS(eeprom_dev[dev].i2c, eeprom_dev[dev].eeprom_address, 7);
+
+ uint8_t cmd[2] = {0, 0}; /* first (or only) part of address */
+ /* second part of address, omitted if eeprom has 256 bytes or less */
+ int ret = 0;
+ int remaining = len;
+ int readcounts = 0;
+
+ while (remaining > 0)
+ {
+ /* read all requested bytes over potentially multiple pages */
+ //int readlen = (remaining < eeprom_dev[dev].eeprom_page_size_bytes) ? remaining : eeprom_dev[dev].eeprom_page_size_bytes;
+ int read_offset = eeprom_dev[dev].offset + len - remaining;//+ write_counts*eeprom_dev[dev].eeprom_page_size_bytes;
+ /* set read length to page border */
+ int readlen = eeprom_dev[dev].eeprom_page_size_bytes - (read_offset % eeprom_dev[dev].eeprom_page_size_bytes);//(remaining < eeprom_dev[dev].eeprom_page_size_bytes) ? remaining : eeprom_dev[dev].eeprom_page_size_bytes;
+ /* cap read length if not a full page read is needed */
+ if (readlen > remaining) readlen = remaining;
+
+ if (eeprom_dev[dev].eeprom_size_bytes <= 256)
+ {
+ cmd[0] = (read_offset); /* set at first byte */
+ /* 8 bit addresses */
+ ret = I2C_WRITEREAD(eeprom_dev[dev].i2c, cmd, 1, (data+(readcounts*eeprom_dev[dev].eeprom_page_size_bytes)), readlen);
+ }
+ else
+ {
+ /* 16 bit addresses */
+ /* EEPROM: first address high, then address low */
+ cmd[0] = (((uint16_t)read_offset) >> 8);
+ cmd[1] = (((uint8_t)read_offset));
+ ret = I2C_WRITEREAD(eeprom_dev[dev].i2c, cmd, 2, (data+(readcounts*eeprom_dev[dev].eeprom_page_size_bytes)), readlen);
+ }
+
+ /* abort on error */
+ if (ret < 0) break;
+
+ /* handled another chunk */
+ remaining -= readlen;
+ readcounts++;
+ }
+
+ /* use the negated value from I2C_TRANSFER to fill errno */
+ errno = -ret;
+
+ /* return len if data was read, < 0 else */
+ if (ret == OK)
+ eeprom_dev[dev].offset += len;
+ return len;
+
+ /* no data, return negated value from I2C_TRANSFER */
+ return ret;
+}
+
+static int
+eeprom_write_internal(int dev, uint16_t len, const uint8_t *data)
+{
+ /* abort if the number of requested bytes exceeds the EEPROM size */
+ if (eeprom_dev[dev].offset + len > eeprom_dev[dev].eeprom_size_bytes)
+ {
+ errno = ENOSPC;
+ return -ENOSPC;
+ }
+
+ int ret = 0;
+ int remaining = len;
+ int write_counts = 0;
+
+ uint8_t write_buf[2];
+
+ while (remaining > 0)
+ {
+ /* write all requested bytes over potentially multiple pages */
+ int write_offset = eeprom_dev[dev].offset + len - remaining;//+ write_counts*eeprom_dev[dev].eeprom_page_size_bytes;
+ /* set write length to page border */
+ int writelen = eeprom_dev[dev].eeprom_page_size_bytes - (write_offset % eeprom_dev[dev].eeprom_page_size_bytes);//(remaining < eeprom_dev[dev].eeprom_page_size_bytes) ? remaining : eeprom_dev[dev].eeprom_page_size_bytes;
+ /* cap write length if not a full page write is requested */
+ if (writelen > remaining) writelen = remaining;
+
+ if (eeprom_dev[dev].eeprom_size_bytes <= 256)
+ {
+ write_buf[0] = (write_offset); /* set at first byte */
+ /* 8 bit addresses */
+
+ const uint8_t* data_ptr = (data+(write_offset));
+
+ struct i2c_msg_s msgv_eeprom_write[2] = {
+ {
+ .addr = eeprom_dev[dev].eeprom_address,
+ .flags = I2C_M_NORESTART,
+ .buffer = write_buf,
+ .length = 1
+ },
+ {
+ .addr = eeprom_dev[dev].eeprom_address,
+ .flags = I2C_M_NORESTART,
+ .buffer = (uint8_t*)data_ptr,
+ .length = writelen
+ }
+ };
+
+
+ if ( (ret = I2C_TRANSFER(eeprom_dev[dev].i2c, msgv_eeprom_write, 2)) == OK )
+ {
+ //printf("SUCCESS WRITING EEPROM 8BIT ADDR: %d, bytes: %d\n", ret, writelen);
+ }
+ }
+ else
+ {
+ /* 16 bit addresses */
+ /* EEPROM: first address high, then address low */
+ write_buf[0] = (((uint16_t)write_offset) >> 8);
+ write_buf[1] = (((uint8_t)write_offset));
+
+ const uint8_t* data_ptr = data+(write_counts*eeprom_dev[dev].eeprom_page_size_bytes);
+
+ struct i2c_msg_s msgv_eeprom_write[2] = {
+ {
+ .addr = eeprom_dev[dev].eeprom_address,
+ .flags = I2C_M_NORESTART,
+ .buffer = write_buf,
+ .length = 2
+ },
+ {
+ .addr = eeprom_dev[dev].eeprom_address,
+ .flags = I2C_M_NORESTART,
+ .buffer = (uint8_t*)data_ptr,
+ .length = writelen
+ }
+ };
+
+
+ if ( (ret = I2C_TRANSFER(eeprom_dev[dev].i2c, msgv_eeprom_write, 2)) == OK )
+ {
+ //printf("SUCCESS WRITING EEPROM 16BIT ADDR: %d, bytes: %d\n", ret, writelen);
+ }
+ }
+
+ /* abort on error */
+ if (ret < 0) break;
+
+ /* handled another chunk */
+ remaining -= writelen;
+ write_counts++;
+ /* wait for the device to write the page */
+ usleep(eeprom_dev[dev].eeprom_page_write_time);
+ }
+
+ /* use the negated value from I2C_TRANSFER to fill errno */
+ errno = -ret;
+
+ /* return length if data was written, < 0 else */
+ if (ret == OK)
+ eeprom_dev[dev].offset += len;
+ return len;
+
+ /* no data, return negated value from I2C_TRANSFER */
+ return ret;
+}
+
+static ssize_t
+eeprom_read0(struct file *filp, char *buffer, size_t buflen)
+{
+ return eeprom_read_internal(0, buflen, (uint8_t *)buffer);
+}
+#if (MAX_EEPROMS > 1)
+static ssize_t
+eeprom_read1(struct file *filp, char *buffer, size_t buflen)
+{
+ return eeprom_read_internal(1, buflen, (uint8_t *)buffer);
+}
+#endif
+#if (MAX_EEPROMS > 2)
+static ssize_t
+eeprom_read2(struct file *filp, char *buffer, size_t buflen)
+{
+ return eeprom_read_internal(2, buflen, (uint8_t *)buffer);
+}
+#endif
+
+static ssize_t
+eeprom_write0(struct file *filp, const char *buffer, size_t buflen)
+{
+ return eeprom_write_internal(0, buflen, (const uint8_t *)buffer);
+}
+#if (MAX_EEPROMS > 1)
+static ssize_t
+eeprom_write1(struct file *filp, const char *buffer, size_t buflen)
+{
+ return eeprom_write_internal(1, buflen, (const uint8_t *)buffer);
+}
+#endif
+#if (MAX_EEPROMS > 2)
+static ssize_t
+eeprom_write2(struct file *filp, const char *buffer, size_t buflen)
+{
+ return eeprom_write_internal(2, buflen, (const uint8_t *)buffer);
+}
+#endif
+
+static off_t eeprom_seek0(FAR struct file *filp, off_t offset, int whence)
+{
+ switch (whence)
+ {
+ case SEEK_SET:
+ if (offset < eeprom_dev[0].eeprom_size_bytes - 1) {
+ eeprom_dev[0].offset = offset;
+ } else {
+ errno = ESPIPE;
+ return -ESPIPE;
+ }
+ break;
+ case SEEK_CUR:
+ if (eeprom_dev[0].offset + offset < eeprom_dev[0].eeprom_size_bytes - 1) {
+ eeprom_dev[0].offset = eeprom_dev[0].offset + offset;
+ } else {
+ errno = ESPIPE;
+ return -ESPIPE;
+ }
+ break;
+ case SEEK_END:
+ errno = ESPIPE;
+ return -ESPIPE;
+ break;
+ }
+ return eeprom_dev[0].offset;
+}
+#if (MAX_EEPROMS > 1)
+static off_t eeprom_seek1(FAR struct file *filp, off_t offset, int whence)
+{
+ switch (whence)
+ {
+ case SEEK_SET:
+ if (offset < eeprom_dev[1].eeprom_size_bytes - 1) {
+ eeprom_dev[1].offset = offset;
+ } else {
+ errno = ESPIPE;
+ return -ESPIPE;
+ }
+ break;
+ case SEEK_CUR:
+ if (eeprom_dev[1].offset + offset < eeprom_dev[1].eeprom_size_bytes - 1) {
+ eeprom_dev[1].offset = eeprom_dev[1].offset + offset;
+ } else {
+ errno = ESPIPE;
+ return -ESPIPE;
+ }
+ break;
+ case SEEK_END:
+ errno = ESPIPE;
+ return -ESPIPE;
+ break;
+ }
+ return eeprom_dev[1].offset;
+}
+#endif
+#if (MAX_EEPROMS > 2)
+static off_t eeprom_seek2(FAR struct file *filp, off_t offset, int whence)
+{
+ switch (whence)
+ {
+ case SEEK_SET:
+ if (offset < eeprom_dev[2].eeprom_size_bytes - 1) {
+ eeprom_dev[2].offset = offset;
+ } else {
+ errno = ESPIPE;
+ return -ESPIPE;
+ }
+ break;
+ case SEEK_CUR:
+ if (eeprom_dev[2].offset + offset < eeprom_dev[2].eeprom_size_bytes - 1) {
+ eeprom_dev[2].offset = eeprom_dev[2].offset + offset;
+ } else {
+ errno = ESPIPE;
+ return -ESPIPE;
+ }
+ break;
+ case SEEK_END:
+ errno = ESPIPE;
+ return -ESPIPE;
+ break;
+ }
+ return eeprom_dev[2].offset;
+}
+#endif
+
+int
+eeprom_attach(struct i2c_dev_s *i2c, uint8_t device_address, uint16_t total_size_bytes, uint16_t page_size_bytes, uint16_t page_write_time_us, const char* device_name, uint8_t fail_if_missing)
+{
+ static int eeprom_dev_counter = 0;
+ eeprom_dev[eeprom_dev_counter].i2c = i2c;
+ eeprom_dev[eeprom_dev_counter].eeprom_address = device_address;
+ eeprom_dev[eeprom_dev_counter].eeprom_size_bytes = total_size_bytes;
+ eeprom_dev[eeprom_dev_counter].eeprom_page_size_bytes = page_size_bytes;
+ eeprom_dev[eeprom_dev_counter].eeprom_page_write_time = page_write_time_us;
+ eeprom_dev[eeprom_dev_counter].offset = 0;
+ eeprom_dev[eeprom_dev_counter].is_open = false;
+
+ int ret;
+
+ if (fail_if_missing) {
+ /* read first value */
+ uint8_t read_test;
+ ret = (eeprom_read_internal(eeprom_dev_counter, 1, &read_test) == 1) ? OK : ERROR;
+ } else {
+ ret = OK;
+ }
+
+ /* make ourselves available */
+ if (ret == OK)
+ {
+ register_driver(device_name, &(eeprom_fops[eeprom_dev_counter]), 0666, NULL);
+ eeprom_dev_counter++;
+ }
+
+ /* Return 0 for device found, error number else */
+ return ret;
+}
diff --git a/nuttx/configs/px4fmu/src/drv_gpio.c b/nuttx/configs/px4fmu/src/drv_gpio.c
new file mode 100644
index 000000000..be95420dd
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_gpio.c
@@ -0,0 +1,195 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * GPIO driver for PX4FMU.
+ *
+ */
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "chip.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+#include <arch/board/drv_gpio.h>
+
+static int px4fmu_gpio_ioctl(struct file *filep, int cmd, unsigned long arg);
+
+static const struct file_operations px4fmu_gpio_fops = {
+ .ioctl = px4fmu_gpio_ioctl,
+};
+
+static struct {
+ uint32_t input;
+ uint32_t output;
+ uint32_t alt;
+} gpio_tab[] = {
+ {GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0},
+ {GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0},
+ {GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, GPIO_USART2_CTS_1},
+ {GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, GPIO_USART2_RTS_1},
+ {GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, GPIO_USART2_TX_1},
+ {GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, GPIO_USART2_RX_1},
+ {GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, GPIO_CAN2_TX_2},
+ {GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, GPIO_CAN2_RX_2},
+};
+
+#define NGPIO (sizeof(gpio_tab) / sizeof(gpio_tab[0]))
+
+
+static void
+px4fmu_gpio_reset(void)
+{
+ /*
+ * Setup default GPIO config - all pins as GPIOs, GPIO driver chip
+ * to input mode.
+ */
+ for (unsigned i = 0; i < NGPIO; i++)
+ stm32_configgpio(gpio_tab[i].input);
+
+ stm32_gpiowrite(GPIO_GPIO_DIR, 0);
+ stm32_configgpio(GPIO_GPIO_DIR);
+}
+
+static void
+px4fmu_gpio_set_function(uint32_t gpios, int function)
+{
+ /*
+ * GPIOs 0 and 1 must have the same direction as they are buffered
+ * by a shared 2-port driver. Any attempt to set either sets both.
+ */
+ if (gpios & 3) {
+ gpios |= 3;
+
+ /* flip the buffer to output mode if required */
+ if (GPIO_SET_OUTPUT == function)
+ stm32_gpiowrite(GPIO_GPIO_DIR, 1);
+ }
+
+ /* configure selected GPIOs as required */
+ for (unsigned i = 0; i < NGPIO; i++) {
+ if (gpios & (1<<i)) {
+ switch (function) {
+ case GPIO_SET_INPUT:
+ stm32_configgpio(gpio_tab[i].input);
+ break;
+ case GPIO_SET_OUTPUT:
+ stm32_configgpio(gpio_tab[i].output);
+ break;
+ case GPIO_SET_ALT_1:
+ if (gpio_tab[i].alt != 0)
+ stm32_configgpio(gpio_tab[i].alt);
+ break;
+ }
+ }
+ }
+
+ /* flip buffer to input mode if required */
+ if ((GPIO_SET_INPUT == function) && (gpios & 3))
+ stm32_gpiowrite(GPIO_GPIO_DIR, 0);
+}
+
+static void
+px4fmu_gpio_write(uint32_t gpios, int function)
+{
+ int value = (function == GPIO_SET) ? 1 : 0;
+
+ for (unsigned i = 0; i < NGPIO; i++)
+ if (gpios & (1<<i))
+ stm32_gpiowrite(gpio_tab[i].output, value);
+}
+
+static uint32_t
+px4fmu_gpio_read(void)
+{
+ uint32_t bits = 0;
+
+ for (unsigned i = 0; i < NGPIO; i++)
+ if (stm32_gpioread(gpio_tab[i].input))
+ bits |= (1 << i);
+
+ return bits;
+}
+
+void
+px4fmu_gpio_init(void)
+{
+ /* reset all GPIOs to default state */
+ px4fmu_gpio_reset();
+
+ /* register the driver */
+ register_driver(GPIO_DEVICE_PATH, &px4fmu_gpio_fops, 0666, NULL);
+}
+
+static int
+px4fmu_gpio_ioctl(struct file *filep, int cmd, unsigned long arg)
+{
+ int result = OK;
+
+ switch (cmd) {
+
+ case GPIO_RESET:
+ px4fmu_gpio_reset();
+ break;
+
+ case GPIO_SET_OUTPUT:
+ case GPIO_SET_INPUT:
+ case GPIO_SET_ALT_1:
+ px4fmu_gpio_set_function(arg, cmd);
+ break;
+
+ case GPIO_SET:
+ case GPIO_CLEAR:
+ px4fmu_gpio_write(arg, cmd);
+ break;
+
+ case GPIO_GET:
+ *(uint32_t *)arg = px4fmu_gpio_read();
+ break;
+
+ default:
+ result = -ENOTTY;
+ }
+ return result;
+}
+
diff --git a/nuttx/configs/px4fmu/src/drv_hmc5833l.c b/nuttx/configs/px4fmu/src/drv_hmc5833l.c
new file mode 100644
index 000000000..0e6dbe2ac
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_hmc5833l.c
@@ -0,0 +1,352 @@
+/*
+ * Copyright (C) 2012 Lorenz Meier. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name of the author or the names of contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/*
+ * Driver for the Honeywell/ST HMC5883L MEMS magnetometer
+ */
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/i2c.h>
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "px4fmu-internal.h"
+
+#include <arch/board/drv_hmc5883l.h>
+
+#define ADDR_CONF_A 0x00
+#define ADDR_CONF_B 0x01
+#define ADDR_MODE 0x02
+#define ADDR_DATA_OUT_X_MSB 0x03
+#define ADDR_DATA_OUT_X_LSB 0x04
+#define ADDR_DATA_OUT_Z_MSB 0x05
+#define ADDR_DATA_OUT_Z_LSB 0x06
+#define ADDR_DATA_OUT_Y_MSB 0x07
+#define ADDR_DATA_OUT_Y_LSB 0x08
+#define ADDR_STATUS 0x09
+#define ADDR_ID_A 0x10
+#define ADDR_ID_B 0x11
+#define ADDR_ID_C 0x12
+
+#define HMC5883L_ADDRESS 0x1E
+
+/* modes not changeable outside of driver */
+#define HMC5883L_MODE_NORMAL (0 << 0) /* default */
+#define HMC5883L_MODE_POSITIVE_BIAS (1 << 0) /* positive bias */
+#define HMC5883L_MODE_NEGATIVE_BIAS (1 << 1) /* negative bias */
+
+#define HMC5883L_AVERAGING_1 (0 << 5) /* conf a register */
+#define HMC5883L_AVERAGING_2 (1 << 5)
+#define HMC5883L_AVERAGING_4 (2 << 5)
+#define HMC5883L_AVERAGING_8 (3 << 5)
+
+#define MODE_REG_CONTINOUS_MODE (0 << 0)
+#define MODE_REG_SINGLE_MODE (1 << 0) /* default */
+
+#define STATUS_REG_DATA_OUT_LOCK (1 << 1) /* page 16: set if data is only partially read, read device to reset */
+#define STATUS_REG_DATA_READY (1 << 0) /* page 16: set if all axes have valid measurements */
+
+#define ID_A_WHO_AM_I 'H'
+#define ID_B_WHO_AM_I '4'
+#define ID_C_WHO_AM_I '3'
+
+static FAR struct hmc5883l_dev_s hmc5883l_dev;
+
+static ssize_t hmc5883l_read(struct file *filp, FAR char *buffer, size_t buflen);
+static int hmc5883l_ioctl(struct file *filp, int cmd, unsigned long arg);
+
+static const struct file_operations hmc5883l_fops = {
+ .open = 0,
+ .close = 0,
+ .read = hmc5883l_read,
+ .write = 0,
+ .seek = 0,
+ .ioctl = hmc5883l_ioctl,
+#ifndef CONFIG_DISABLE_POLL
+ .poll = 0
+#endif
+};
+
+struct hmc5883l_dev_s
+{
+ struct i2c_dev_s *i2c;
+ uint8_t rate;
+ struct hmc5883l_buffer *buffer;
+};
+
+static int hmc5883l_write_reg(uint8_t address, uint8_t data);
+static int hmc5883l_read_reg(uint8_t address);
+static int hmc5883l_reset(void);
+
+static int
+hmc5883l_write_reg(uint8_t address, uint8_t data)
+{
+ uint8_t cmd[] = {address, data};
+ return I2C_WRITE(hmc5883l_dev.i2c, cmd, 2);
+}
+
+static int
+hmc5883l_read_reg(uint8_t address)
+{
+ uint8_t cmd = address;
+ uint8_t data;
+
+ int ret = I2C_WRITEREAD(hmc5883l_dev.i2c, &cmd, 1, &data, 1);
+ /* return data on success, error code on failure */
+ if (ret == OK) {
+ ret = data;
+ }
+ return ret;
+}
+
+static int
+hmc5883l_set_range(uint8_t range)
+{
+ I2C_SETADDRESS(hmc5883l_dev.i2c, HMC5883L_ADDRESS, 7);
+
+
+ /* mask out illegal bit positions */
+ uint8_t write_range = range; //& REG4_RANGE_MASK;
+ /* immediately return if user supplied invalid value */
+ if (write_range != range) return EINVAL;
+ /* set remaining bits to a sane value */
+// write_range |= REG4_BDU;
+ /* write to device */
+ hmc5883l_write_reg(ADDR_CONF_B, write_range);
+ /* return 0 if register value is now written value, 1 if unchanged */
+ return !(hmc5883l_read_reg(ADDR_CONF_B) == write_range);
+}
+
+static int
+hmc5883l_set_rate(uint8_t rate)
+{
+ I2C_SETADDRESS(hmc5883l_dev.i2c, HMC5883L_ADDRESS, 7);
+ /* mask out illegal bit positions */
+ uint8_t write_rate = rate;// & REG1_RATE_LP_MASK;
+ /* immediately return if user supplied invalid value */
+ if (write_rate != rate) return EINVAL;
+ /* set remaining bits to a sane value */
+// write_rate |= REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE;
+ write_rate |= HMC5883L_AVERAGING_8;
+ /* write to device */
+ hmc5883l_write_reg(ADDR_CONF_A, write_rate);
+ /* return 0 if register value is now written value, 1 if unchanged */
+ return !(hmc5883l_read_reg(ADDR_CONF_A) == write_rate);
+}
+
+static bool
+read_values(int16_t *data)
+{
+ struct { /* status register and data as read back from the device */
+ int16_t x;
+ int16_t z;
+ int16_t y;
+ uint8_t status;
+ } __attribute__((packed)) hmc_report;
+ hmc_report.status = 0;
+
+ static int read_err_count = 0;
+
+ /* exchange the report structure with the device */
+
+ uint8_t cmd = ADDR_DATA_OUT_X_MSB;
+
+ int ret = 0;
+
+ I2C_SETADDRESS(hmc5883l_dev.i2c, HMC5883L_ADDRESS, 7);
+
+ /* set device into single mode, trigger next measurement */
+ ret = hmc5883l_write_reg(ADDR_MODE, MODE_REG_SINGLE_MODE);
+
+ /* Only execute consecutive steps on success */
+ if (ret == OK)
+ {
+ cmd = ADDR_DATA_OUT_X_MSB;
+ ret = I2C_WRITEREAD(hmc5883l_dev.i2c, &cmd, 1, (uint8_t*)&hmc_report, 6);
+ if (ret == OK)
+ {
+ /* Six bytes to read, stop if timed out */
+ int hmc_status = hmc5883l_read_reg(ADDR_STATUS);
+ if (hmc_status < 0)
+ {
+ if (ret == ETIMEDOUT) hmc5883l_reset();
+ ret = hmc_status;
+ }
+ else
+ {
+ hmc_report.status = hmc_status;
+ ret = OK;
+ }
+ }
+ else
+ {
+ if (ret == ETIMEDOUT) hmc5883l_reset();
+ }
+ }
+ else
+ {
+ if (ret == ETIMEDOUT) hmc5883l_reset();
+ }
+
+ if (ret != OK)
+ {
+ read_err_count++;
+ /* If the last reads failed as well, reset the bus and chip */
+ if (read_err_count > 3) hmc5883l_reset();
+
+ *get_errno_ptr() = -ret;
+ } else {
+ read_err_count = 0;
+ /* write values, and exchange the two 8bit blocks (big endian to little endian) */
+ data[0] = ((hmc_report.x & 0x00FF) << 8) | ((hmc_report.x & 0xFF00) >> 8);
+ data[1] = ((hmc_report.y & 0x00FF) << 8) | ((hmc_report.y & 0xFF00) >> 8);
+ data[2] = ((hmc_report.z & 0x00FF) << 8) | ((hmc_report.z & 0xFF00) >> 8);
+ if ((hmc_report.status & STATUS_REG_DATA_READY) > 0)
+ {
+ ret = 6;
+ } else {
+ ret = -EAGAIN;
+ }
+ }
+
+ /* return len if new data is available, error else. hmc_report.status is 0 on errors */
+ return ret;
+}
+
+static ssize_t
+hmc5883l_read(struct file *filp, char *buffer, size_t buflen)
+{
+ /* if the buffer is large enough, and data are available, return success */
+ if (buflen >= 6) {
+ return read_values((int16_t *)buffer);
+ }
+
+ /* buffer too small */
+ *get_errno_ptr() = ENOSPC;
+ return -ERROR;
+}
+
+static int
+hmc5883l_ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ int result = ERROR;
+
+ switch (cmd) {
+ case HMC5883L_SETRATE:
+ result = hmc5883l_set_rate(arg);
+ break;
+
+ case HMC5883L_SETRANGE:
+ result = hmc5883l_set_range(arg);
+ break;
+//
+// case HMC5883L_SETBUFFER:
+// hmc5883l_dev.buffer = (struct hmc5883l_buffer *)arg;
+// result = 0;
+// break;
+
+ case HMC5883L_RESET:
+ result = hmc5883l_reset();
+ break;
+ }
+
+ if (result)
+ errno = EINVAL;
+ return result;
+}
+
+int hmc5883l_reset()
+{
+ int ret;
+ printf("[hmc5883l drv] Resettet I2C2 BUS\n");
+ up_i2cuninitialize(hmc5883l_dev.i2c);
+ hmc5883l_dev.i2c = up_i2cinitialize(2);
+ I2C_SETFREQUENCY(hmc5883l_dev.i2c, 400000);
+ // up_i2creset(hmc5883l_dev.i2c);
+ //I2C_SETADDRESS(hmc5883l_dev.i2c, HMC5883L_ADDRESS, 7);
+ //hmc5883l_set_range(HMC5883L_RANGE_0_88GA);
+ //hmc5883l_set_rate(HMC5883L_RATE_75HZ);
+ /* set device into single mode, start measurement */
+ //ret = hmc5883l_write_reg(ADDR_MODE, MODE_REG_SINGLE_MODE);
+ return ret;
+}
+
+int
+hmc5883l_attach(struct i2c_dev_s *i2c)
+{
+ int result = ERROR;
+
+ hmc5883l_dev.i2c = i2c;
+
+// I2C_LOCK(hmc5883l_dev.i2c, true);
+ I2C_SETADDRESS(hmc5883l_dev.i2c, HMC5883L_ADDRESS, 7);
+
+ uint8_t cmd = ADDR_STATUS;
+ uint8_t status_id[4] = {0, 0, 0, 0};
+
+
+ int ret = I2C_WRITEREAD(i2c, &cmd, 1, status_id, 4);
+
+ /* verify that the device is attached and functioning */
+ if ((ret >= 0) && (status_id[1] == ID_A_WHO_AM_I) && (status_id[2] == ID_B_WHO_AM_I) && (status_id[3] == ID_C_WHO_AM_I)) {
+
+ /* set update rate to 75 Hz */
+ /* set 0.88 Ga range */
+ if ((ret != 0) || (hmc5883l_set_range(HMC5883L_RANGE_0_88GA) != 0) ||
+ (hmc5883l_set_rate(HMC5883L_RATE_75HZ) != 0))
+ {
+ errno = EIO;
+ } else {
+
+ /* set device into single mode, start measurement */
+ ret = hmc5883l_write_reg(ADDR_MODE, MODE_REG_SINGLE_MODE);
+
+ /* make ourselves available */
+ register_driver("/dev/hmc5883l", &hmc5883l_fops, 0666, NULL);
+
+ result = 0;
+ }
+
+ } else {
+ errno = EIO;
+ }
+
+
+
+ return result;
+}
diff --git a/nuttx/configs/px4fmu/src/drv_l3gd20.c b/nuttx/configs/px4fmu/src/drv_l3gd20.c
new file mode 100644
index 000000000..1c6c05449
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_l3gd20.c
@@ -0,0 +1,364 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * Driver for the ST L3GD20 MEMS gyroscope
+ */
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+#include <nuttx/arch.h>
+#include <arch/board/drv_l3gd20.h>
+
+#include "chip.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+#define DIR_READ (1<<7)
+#define DIR_WRITE (0<<7)
+#define ADDR_INCREMENT (1<<6)
+
+#define ADDR_WHO_AM_I 0x0F
+#define WHO_I_AM 0xD4
+#define ADDR_CTRL_REG1 0x20
+#define ADDR_CTRL_REG2 0x21
+#define ADDR_CTRL_REG3 0x22
+#define ADDR_CTRL_REG4 0x23
+#define ADDR_CTRL_REG5 0x24
+#define ADDR_REFERENCE 0x25
+#define ADDR_OUT_TEMP 0x26
+#define ADDR_STATUS_REG 0x27
+#define ADDR_OUT_X_L 0x28
+#define ADDR_OUT_X_H 0x29
+#define ADDR_OUT_Y_L 0x2A
+#define ADDR_OUT_Y_H 0x2B
+#define ADDR_OUT_Z_L 0x2C
+#define ADDR_OUT_Z_H 0x2D
+#define ADDR_FIFO_CTRL_REG 0x2E
+#define ADDR_FIFO_SRC_REG 0x2F
+#define ADDR_INT1_CFG 0x30
+#define ADDR_INT1_SRC 0x31
+#define ADDR_INT1_TSH_XH 0x32
+#define ADDR_INT1_TSH_XL 0x33
+#define ADDR_INT1_TSH_YH 0x34
+#define ADDR_INT1_TSH_YL 0x35
+#define ADDR_INT1_TSH_ZH 0x36
+#define ADDR_INT1_TSH_ZL 0x37
+#define ADDR_INT1_DURATION 0x38
+
+#define REG1_RATE_LP_MASK 0xF0 /* Mask to guard partial register update */
+#define REG4_RANGE_MASK 0x30 /* Mask to guard partial register update */
+
+/* Internal configuration values */
+#define REG1_POWER_NORMAL (1<<3)
+#define REG1_Z_ENABLE (1<<2)
+#define REG1_Y_ENABLE (1<<1)
+#define REG1_X_ENABLE (1<<0)
+
+#define REG4_BDU (1<<7)
+#define REG4_BLE (1<<6)
+//#define REG4_SPI_3WIRE (1<<0)
+
+#define REG5_FIFO_ENABLE (1<<6)
+#define REG5_REBOOT_MEMORY (1<<7)
+
+#define STATUS_ZYXOR (1<<7)
+#define STATUS_ZOR (1<<6)
+#define STATUS_YOR (1<<5)
+#define STATUS_XOR (1<<4)
+#define STATUS_ZYXDA (1<<3)
+#define STATUS_ZDA (1<<2)
+#define STATUS_YDA (1<<1)
+#define STATUS_XDA (1<<0)
+
+#define FIFO_CTRL_BYPASS_MODE (0<<5)
+#define FIFO_CTRL_FIFO_MODE (1<<5)
+#define FIFO_CTRL_STREAM_MODE (1<<6)
+#define FIFO_CTRL_STREAM_TO_FIFO_MODE (3<<5)
+#define FIFO_CTRL_BYPASS_TO_STREAM_MODE (1<<7)
+
+static FAR struct l3gd20_dev_s l3gd20_dev;
+
+static ssize_t l3gd20_read(struct file *filp, FAR char *buffer, size_t buflen);
+static int l3gd20_ioctl(struct file *filp, int cmd, unsigned long arg);
+
+static const struct file_operations l3gd20_fops = {
+ .open = 0,
+ .close = 0,
+ .read = l3gd20_read,
+ .write = 0,
+ .seek = 0,
+ .ioctl = l3gd20_ioctl,
+#ifndef CONFIG_DISABLE_POLL
+ .poll = 0
+#endif
+};
+
+struct l3gd20_dev_s
+{
+ struct spi_dev_s *spi;
+ int spi_id;
+ uint8_t rate;
+ struct l3gd20_buffer *buffer;
+};
+
+static void l3gd20_write_reg(uint8_t address, uint8_t data);
+static uint8_t l3gd20_read_reg(uint8_t address);
+
+static void
+l3gd20_write_reg(uint8_t address, uint8_t data)
+{
+ uint8_t cmd[2] = { address | DIR_WRITE, data };
+
+ SPI_SELECT(l3gd20_dev.spi, l3gd20_dev.spi_id, true);
+ SPI_SNDBLOCK(l3gd20_dev.spi, &cmd, sizeof(cmd));
+ SPI_SELECT(l3gd20_dev.spi, l3gd20_dev.spi_id, false);
+}
+
+static uint8_t
+l3gd20_read_reg(uint8_t address)
+{
+ uint8_t cmd[2] = {address | DIR_READ, 0};
+ uint8_t data[2];
+
+ SPI_SELECT(l3gd20_dev.spi, l3gd20_dev.spi_id, true);
+ SPI_EXCHANGE(l3gd20_dev.spi, cmd, data, sizeof(cmd));
+ SPI_SELECT(l3gd20_dev.spi, l3gd20_dev.spi_id, false);
+
+ return data[1];
+}
+
+static int
+set_range(uint8_t range)
+{
+ /* mask out illegal bit positions */
+ uint8_t write_range = range & REG4_RANGE_MASK;
+ /* immediately return if user supplied invalid value */
+ if (write_range != range) return EINVAL;
+ /* set remaining bits to a sane value */
+ write_range |= REG4_BDU;
+ /* write to device */
+ l3gd20_write_reg(ADDR_CTRL_REG4, write_range);
+ /* return 0 if register value is now written value, 1 if unchanged */
+ return !(l3gd20_read_reg(ADDR_CTRL_REG4) == write_range);
+}
+
+static int
+set_rate(uint8_t rate)
+{
+ /* mask out illegal bit positions */
+ uint8_t write_rate = rate & REG1_RATE_LP_MASK;
+ /* immediately return if user supplied invalid value */
+ if (write_rate != rate) return EINVAL;
+ /* set remaining bits to a sane value */
+ write_rate |= REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE;
+ /* write to device */
+ l3gd20_write_reg(ADDR_CTRL_REG1, write_rate);
+ /* return 0 if register value is now written value, 1 if unchanged */
+ return !(l3gd20_read_reg(ADDR_CTRL_REG1) == write_rate);
+}
+
+static int
+read_fifo(int16_t *data)
+{
+
+ struct { /* status register and data as read back from the device */
+ uint8_t cmd;
+ uint8_t temp;
+ uint8_t status;
+ int16_t x;
+ int16_t y;
+ int16_t z;
+ } __attribute__((packed)) report = {.status = 11};
+
+ report.cmd = 0x26 | DIR_READ | ADDR_INCREMENT;
+
+ SPI_LOCK(l3gd20_dev.spi, true);
+ SPI_SELECT(l3gd20_dev.spi, PX4_SPIDEV_GYRO, true);
+ SPI_SETFREQUENCY(l3gd20_dev.spi, 25000000);
+
+ SPI_EXCHANGE(l3gd20_dev.spi, &report, &report, sizeof(report));
+
+ /* XXX if the status value is unchanged, attempt a second exchange */
+ if (report.status == 11) SPI_EXCHANGE(l3gd20_dev.spi, &report, &report, sizeof(report));
+ /* XXX set magic error value if this still didn't succeed */
+ if (report.status == 11) report.status = 12;
+
+ SPI_SETFREQUENCY(l3gd20_dev.spi, 10000000);
+ SPI_SELECT(l3gd20_dev.spi, PX4_SPIDEV_GYRO, false);
+ SPI_LOCK(l3gd20_dev.spi, false);
+
+ data[0] = report.x;
+ data[1] = report.y;
+ data[2] = report.z;
+
+ /* if all axes are valid, return buflen (6), else return negative status */
+ int ret = -((int)report.status);
+ if (STATUS_ZYXDA == (report.status & STATUS_ZYXDA) || STATUS_ZYXOR == (report.status & STATUS_ZYXOR))
+ {
+ ret = 6;
+ }
+
+ return ret;
+}
+
+static ssize_t
+l3gd20_read(struct file *filp, char *buffer, size_t buflen)
+{
+ /* if the buffer is large enough, and data are available, return success */
+ if (buflen >= 6) {
+ /* return buflen or a negative value */
+ int ret = read_fifo((int16_t *)buffer);
+ if (ret != 6) *get_errno_ptr() = EAGAIN;
+ return ret;
+ }
+
+ /* buffer too small */
+ *get_errno_ptr() = ENOSPC;
+ return ERROR;
+}
+
+static int
+l3gd20_ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ int result = ERROR;
+
+ switch (cmd) {
+ case L3GD20_SETRATE:
+ if ((arg & REG1_RATE_LP_MASK) == arg) {
+ SPI_LOCK(l3gd20_dev.spi, true);
+ set_rate(arg);
+ SPI_LOCK(l3gd20_dev.spi, false);
+ result = 0;
+ l3gd20_dev.rate = arg;
+ }
+ break;
+
+ case L3GD20_SETRANGE:
+ if ((arg & REG4_RANGE_MASK) == arg) {
+ SPI_LOCK(l3gd20_dev.spi, true);
+ set_range(arg);
+ SPI_LOCK(l3gd20_dev.spi, false);
+ result = 0;
+ }
+ break;
+
+ case L3GD20_SETBUFFER:
+ l3gd20_dev.buffer = (struct l3gd20_buffer *)arg;
+ result = 0;
+ break;
+ }
+
+ if (result)
+ errno = EINVAL;
+ return result;
+}
+
+int
+l3gd20_attach(struct spi_dev_s *spi, int spi_id)
+{
+ int result = ERROR;
+
+ l3gd20_dev.spi = spi;
+ l3gd20_dev.spi_id = spi_id;
+
+ SPI_LOCK(l3gd20_dev.spi, true);
+ /* read dummy value to void to clear SPI statemachine on sensor */
+ (void)l3gd20_read_reg(ADDR_WHO_AM_I);
+
+ /* verify that the device is attached and functioning */
+ if (l3gd20_read_reg(ADDR_WHO_AM_I) == WHO_I_AM) {
+
+ /* reset device memory */
+ //l3gd20_write_reg(ADDR_CTRL_REG5, REG5_REBOOT_MEMORY);
+ //up_udelay(1000);
+
+ /* set default configuration */
+ l3gd20_write_reg(ADDR_CTRL_REG1, REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE);
+ l3gd20_write_reg(ADDR_CTRL_REG2, 0); /* disable high-pass filters */
+ l3gd20_write_reg(ADDR_CTRL_REG3, 0); /* no interrupts - we don't use them */
+ l3gd20_write_reg(ADDR_CTRL_REG4, 0x10);
+ l3gd20_write_reg(ADDR_CTRL_REG5, 0);
+
+ l3gd20_write_reg(ADDR_CTRL_REG5, REG5_FIFO_ENABLE); /* disable wake-on-interrupt */
+ l3gd20_write_reg(ADDR_FIFO_CTRL_REG, FIFO_CTRL_STREAM_MODE); /* Enable FIFO, old data is overwritten */
+
+ if ((set_range(L3GD20_RANGE_500DPS) != 0) ||
+ (set_rate(L3GD20_RATE_760HZ_LP_100HZ) != 0)) /* takes device out of low-power mode */
+ {
+ errno = EIO;
+ } else {
+ /* Read out the first few funky values */
+ struct { /* status register and data as read back from the device */
+ uint8_t cmd;
+ uint8_t temp;
+ uint8_t status;
+ int16_t x;
+ int16_t y;
+ int16_t z;
+ } __attribute__((packed)) report;
+
+ report.cmd = 0x26 | DIR_READ | ADDR_INCREMENT;
+
+ SPI_SELECT(spi, PX4_SPIDEV_GYRO, true);
+ SPI_EXCHANGE(spi, &report, &report, sizeof(report));
+ SPI_SELECT(spi, PX4_SPIDEV_GYRO, false);
+ up_udelay(500);
+ /* And read another set */
+ SPI_SELECT(spi, PX4_SPIDEV_GYRO, true);
+ SPI_EXCHANGE(spi, &report, &report, sizeof(report));
+ SPI_SELECT(spi, PX4_SPIDEV_GYRO, false);
+
+
+ /* make ourselves available */
+ register_driver("/dev/l3gd20", &l3gd20_fops, 0666, NULL);
+
+ result = 0;
+ }
+
+ } else {
+
+ errno = EIO;
+ }
+
+ SPI_LOCK(l3gd20_dev.spi, false);
+
+ return result;
+}
diff --git a/nuttx/configs/px4fmu/src/drv_led.c b/nuttx/configs/px4fmu/src/drv_led.c
new file mode 100644
index 000000000..13d8eb22a
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_led.c
@@ -0,0 +1,113 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * led driver for PX4FMU
+ *
+ * This is something of an experiment currently (ha, get it?)
+ */
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "chip.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+#include <arch/board/drv_led.h>
+
+static int px4fmu_led_ioctl(struct file *filep, int cmd, unsigned long arg);
+static ssize_t px4fmu_led_pseudoread(struct file *filp, FAR char *buffer, size_t buflen);
+
+static const struct file_operations px4fmu_led_fops = {
+ .read = px4fmu_led_pseudoread,
+ .ioctl = px4fmu_led_ioctl,
+};
+
+int
+px4fmu_led_init(void)
+{
+ /* register the driver */
+ return register_driver("/dev/led", &px4fmu_led_fops, 0666, NULL);
+}
+
+static ssize_t
+px4fmu_led_pseudoread(struct file *filp, FAR char *buffer, size_t buflen)
+{
+ return 0;
+}
+
+static int
+px4fmu_led_ioctl(struct file *filep, int cmd, unsigned long arg)
+{
+ int result = 0;
+
+ switch (cmd) {
+
+ case LED_ON:
+ switch (arg) {
+ case 0:
+ case 1:
+ up_ledon(arg);
+ break;
+ default:
+ result = -1;
+ break;
+ }
+ break;
+
+ case LED_OFF:
+ switch (arg) {
+ case 0:
+ case 1:
+ up_ledoff(arg);
+ break;
+ default:
+ result = -1;
+ break;
+ }
+ break;
+ default:
+ result = -1;
+ break;
+ }
+ return result;
+}
+
diff --git a/nuttx/configs/px4fmu/src/drv_lis331.c b/nuttx/configs/px4fmu/src/drv_lis331.c
new file mode 100644
index 000000000..fd477b46f
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_lis331.c
@@ -0,0 +1,272 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * Driver for the ST LIS331 MEMS accelerometer
+ */
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "chip.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+#include <arch/board/drv_lis331.h>
+
+/*
+ * LIS331 registers
+ */
+
+#define DIR_READ (1<<7)
+#define DIR_WRITE (0<<7)
+#define ADDR_INCREMENT (1<<6)
+
+#define ADDR_WHO_AM_I 0x0f
+#define WHO_I_AM 0x32
+
+#define ADDR_CTRL_REG1 0x20 /* sample rate constants are in the public header */
+#define REG1_POWER_NORMAL (1<<5)
+#define REG1_RATE_MASK (3<<3)
+#define REG1_Z_ENABLE (1<<2)
+#define REG1_Y_ENABLE (1<<1)
+#define REG1_X_ENABLE (1<<0)
+
+#define ADDR_CTRL_REG2 0x21
+
+#define ADDR_CTRL_REG3 0x22
+
+#define ADDR_CTRL_REG4 0x23
+#define REG4_BDU (1<<7)
+#define REG4_BIG_ENDIAN (1<<6)
+#define REG4_RANGE_MASK (3<<4)
+#define REG4_SPI_3WIRE (1<<0)
+
+#define ADDR_CTRL_REG5 0x24
+
+#define ADDR_HP_FILTER_RESET 0x25
+#define ADDR_REFERENCE 0x26
+#define ADDR_STATUS_REG 0x27
+#define STATUS_ZYXOR (1<<7)
+#define STATUS_ZOR (1<<6)
+#define STATUS_YOR (1<<5)
+#define STATUS_XOR (1<<4)
+#define STATUS_ZYXDA (1<<3)
+#define STATUS_ZDA (1<<2)
+#define STATUS_YDA (1<<1)
+#define STATUS_XDA (1<<0)
+
+#define ADDR_OUT_X 0x28 /* 16 bits */
+#define ADDR_OUT_Y 0x2A /* 16 bits */
+#define ADDR_OUT_Z 0x2C /* 16 bits */
+
+
+static ssize_t lis331_read(struct file *filp, FAR char *buffer, size_t buflen);
+static int lis331_ioctl(struct file *filp, int cmd, unsigned long arg);
+
+static const struct file_operations lis331_fops = {
+ .read = lis331_read,
+ .ioctl = lis331_ioctl,
+};
+
+struct lis331_dev_s
+{
+ struct spi_dev_s *spi;
+ int spi_id;
+
+ uint8_t rate;
+ struct lis331_buffer *buffer;
+};
+
+static struct lis331_dev_s lis331_dev;
+
+static void write_reg(uint8_t address, uint8_t data);
+static uint8_t read_reg(uint8_t address);
+static bool read_fifo(uint16_t *data);
+static void set_range(uint8_t range);
+static void set_rate(uint8_t rate);
+
+static void
+write_reg(uint8_t address, uint8_t data)
+{
+ uint8_t cmd[2] = { address | DIR_WRITE, data };
+
+ SPI_SELECT(lis331_dev.spi, lis331_dev.spi_id, true);
+ SPI_SNDBLOCK(lis331_dev.spi, &cmd, sizeof(cmd));
+ SPI_SELECT(lis331_dev.spi, lis331_dev.spi_id, false);
+}
+
+static uint8_t
+read_reg(uint8_t address)
+{
+ uint8_t cmd[2] = {address | DIR_READ, 0};
+ uint8_t data[2];
+
+ SPI_SELECT(lis331_dev.spi, lis331_dev.spi_id, true);
+ SPI_EXCHANGE(lis331_dev.spi, cmd, data, sizeof(cmd));
+ SPI_SELECT(lis331_dev.spi, lis331_dev.spi_id, false);
+
+ return data[1];
+}
+
+static bool
+read_fifo(uint16_t *data)
+{
+ struct { /* status register and data as read back from the device */
+ uint8_t cmd;
+ uint8_t status;
+ int16_t x;
+ int16_t y;
+ int16_t z;
+ } __attribute__((packed)) report;
+
+ report.cmd = ADDR_STATUS_REG | DIR_READ | ADDR_INCREMENT;
+
+ /* exchange the report structure with the device */
+ SPI_LOCK(lis331_dev.spi, true);
+ SPI_SELECT(lis331_dev.spi, lis331_dev.spi_id, true);
+ SPI_EXCHANGE(lis331_dev.spi, &report, &report, sizeof(report));
+ SPI_SELECT(lis331_dev.spi, lis331_dev.spi_id, false);
+ SPI_LOCK(lis331_dev.spi, false);
+
+ data[0] = report.x;
+ data[1] = report.y;
+ data[2] = report.z;
+
+ return report.status & STATUS_ZYXDA;
+}
+
+static void
+set_range(uint8_t range)
+{
+ range &= REG4_RANGE_MASK;
+ write_reg(ADDR_CTRL_REG4, range | REG4_BDU);
+}
+
+static void
+set_rate(uint8_t rate)
+{
+ rate &= REG1_RATE_MASK;
+ write_reg(ADDR_CTRL_REG1, rate | REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE);
+}
+
+static ssize_t
+lis331_read(struct file *filp, char *buffer, size_t buflen)
+{
+ /* if the buffer is large enough, and data are available, return success */
+ if (buflen >= 12) {
+ if (read_fifo((uint16_t *)buffer))
+ return 12;
+
+ /* no data */
+ return 0;
+ }
+
+ /* buffer too small */
+ errno = ENOSPC;
+ return ERROR;
+}
+
+static int
+lis331_ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ int result = ERROR;
+
+ switch (cmd) {
+ case LIS331_SETRATE:
+ if ((arg & REG1_RATE_MASK) == arg) {
+ set_rate(arg);
+ result = 0;
+ lis331_dev.rate = arg;
+ }
+ break;
+
+ case LIS331_SETRANGE:
+ if ((arg & REG4_RANGE_MASK) == arg) {
+ set_range(arg);
+ result = 0;
+ }
+ break;
+
+ case LIS331_SETBUFFER:
+ lis331_dev.buffer = (struct lis331_buffer *)arg;
+ result = 0;
+ break;
+ }
+
+ if (result)
+ errno = EINVAL;
+ return result;
+}
+
+int
+lis331_attach(struct spi_dev_s *spi, int spi_id)
+{
+ int result = ERROR;
+
+ lis331_dev.spi = spi;
+
+ SPI_LOCK(lis331_dev.spi, true);
+
+ /* verify that the device is attached and functioning */
+ if (read_reg(ADDR_WHO_AM_I) == WHO_I_AM) {
+
+ /* set default configuration */
+ write_reg(ADDR_CTRL_REG2, 0); /* disable interrupt-generating high-pass filters */
+ write_reg(ADDR_CTRL_REG3, 0); /* no interrupts - we don't use them */
+ write_reg(ADDR_CTRL_REG5, 0); /* disable wake-on-interrupt */
+
+ set_range(LIS331_RANGE_4G);
+ set_rate(LIS331_RATE_400Hz); /* takes device out of low-power mode */
+
+ /* make ourselves available */
+ register_driver("/dev/lis331", &lis331_fops, 0666, NULL);
+
+ result = 0;
+ } else {
+ errno = EIO;
+ }
+
+ SPI_LOCK(lis331_dev.spi, false);
+
+ return result;
+}
+
diff --git a/nuttx/configs/px4fmu/src/drv_mpu6000.c b/nuttx/configs/px4fmu/src/drv_mpu6000.c
new file mode 100644
index 000000000..47f655563
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_mpu6000.c
@@ -0,0 +1,411 @@
+/*
+ * Copyright (C) 2012 Lorenz Meier. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name of the author or the names of contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/*
+ * Driver for the ST mpu6000 MEMS gyroscope
+ */
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+#include <errno.h>
+#include <unistd.h>
+#include <stdio.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+#include <nuttx/arch.h>
+
+#include "chip.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+#include <arch/board/drv_mpu6000.h>
+
+#define DIR_READ (0x80)
+#define DIR_WRITE (0<<7)
+#define ADDR_INCREMENT (1<<6)
+
+#define WHO_I_AM 0xD4
+
+// MPU 6000 registers
+#define MPUREG_WHOAMI 0x75 //
+#define MPUREG_SMPLRT_DIV 0x19 //
+#define MPUREG_CONFIG 0x1A //
+#define MPUREG_GYRO_CONFIG 0x1B
+#define MPUREG_ACCEL_CONFIG 0x1C
+#define MPUREG_FIFO_EN 0x23
+#define MPUREG_INT_PIN_CFG 0x37
+#define MPUREG_INT_ENABLE 0x38
+#define MPUREG_INT_STATUS 0x3A
+#define MPUREG_ACCEL_XOUT_H 0x3B //
+#define MPUREG_ACCEL_XOUT_L 0x3C //
+#define MPUREG_ACCEL_YOUT_H 0x3D //
+#define MPUREG_ACCEL_YOUT_L 0x3E //
+#define MPUREG_ACCEL_ZOUT_H 0x3F //
+#define MPUREG_ACCEL_ZOUT_L 0x40 //
+#define MPUREG_TEMP_OUT_H 0x41//
+#define MPUREG_TEMP_OUT_L 0x42//
+#define MPUREG_GYRO_XOUT_H 0x43 //
+#define MPUREG_GYRO_XOUT_L 0x44 //
+#define MPUREG_GYRO_YOUT_H 0x45 //
+#define MPUREG_GYRO_YOUT_L 0x46 //
+#define MPUREG_GYRO_ZOUT_H 0x47 //
+#define MPUREG_GYRO_ZOUT_L 0x48 //
+#define MPUREG_USER_CTRL 0x6A //
+#define MPUREG_PWR_MGMT_1 0x6B //
+#define MPUREG_PWR_MGMT_2 0x6C //
+#define MPUREG_FIFO_COUNTH 0x72
+#define MPUREG_FIFO_COUNTL 0x73
+#define MPUREG_FIFO_R_W 0x74
+#define MPUREG_PRODUCT_ID 0x0C // Product ID Register
+
+
+// Configuration bits MPU 3000 and MPU 6000 (not revised)?
+#define BIT_SLEEP 0x40
+#define BIT_H_RESET 0x80
+#define BITS_CLKSEL 0x07
+#define MPU_CLK_SEL_PLLGYROX 0x01
+#define MPU_CLK_SEL_PLLGYROZ 0x03
+#define MPU_EXT_SYNC_GYROX 0x02
+#define BITS_FS_250DPS 0x00
+#define BITS_FS_500DPS 0x08
+#define BITS_FS_1000DPS 0x10
+#define BITS_FS_2000DPS 0x18
+#define BITS_FS_MASK 0x18
+#define BITS_DLPF_CFG_256HZ_NOLPF2 0x00
+#define BITS_DLPF_CFG_188HZ 0x01
+#define BITS_DLPF_CFG_98HZ 0x02
+#define BITS_DLPF_CFG_42HZ 0x03
+#define BITS_DLPF_CFG_20HZ 0x04
+#define BITS_DLPF_CFG_10HZ 0x05
+#define BITS_DLPF_CFG_5HZ 0x06
+#define BITS_DLPF_CFG_2100HZ_NOLPF 0x07
+#define BITS_DLPF_CFG_MASK 0x07
+#define BIT_INT_ANYRD_2CLEAR 0x10
+#define BIT_RAW_RDY_EN 0x01
+#define BIT_I2C_IF_DIS 0x10
+#define BIT_INT_STATUS_DATA 0x01
+ // Product ID Description for MPU6000
+ // high 4 bits low 4 bits
+ // Product Name Product Revision
+#define MPU6000ES_REV_C4 0x14 // 0001 0100
+#define MPU6000ES_REV_C5 0x15 // 0001 0101
+#define MPU6000ES_REV_D6 0x16 // 0001 0110
+#define MPU6000ES_REV_D7 0x17 // 0001 0111
+#define MPU6000ES_REV_D8 0x18 // 0001 1000
+#define MPU6000_REV_C4 0x54 // 0101 0100
+#define MPU6000_REV_C5 0x55 // 0101 0101
+#define MPU6000_REV_D6 0x56 // 0101 0110
+#define MPU6000_REV_D7 0x57 // 0101 0111
+#define MPU6000_REV_D8 0x58 // 0101 1000
+#define MPU6000_REV_D9 0x59 // 0101 1001
+#define MPU6000_REV_D10 0x5A // 0101 1010
+
+static FAR struct mpu6000_dev_s mpu6000_dev;
+
+static ssize_t mpu6000_read(struct file *filp, FAR char *buffer, size_t buflen);
+static int mpu6000_ioctl(struct file *filp, int cmd, unsigned long arg);
+
+static const struct file_operations mpu6000_fops = {
+ .open = 0,
+ .close = 0,
+ .read = mpu6000_read,
+ .write = 0,
+ .seek = 0,
+ .ioctl = mpu6000_ioctl,
+#ifndef CONFIG_DISABLE_POLL
+ .poll = 0
+#endif
+};
+
+struct mpu6000_dev_s
+{
+ struct spi_dev_s *spi;
+ int spi_id;
+ uint8_t rate;
+ struct mpu6000_buffer *buffer;
+};
+
+static void mpu6000_write_reg(uint8_t address, uint8_t data);
+static uint8_t mpu6000_read_reg(uint8_t address);
+
+static void
+mpu6000_write_reg(uint8_t address, uint8_t data)
+{
+ uint8_t cmd[2] = { address | DIR_WRITE, data };
+
+ SPI_SELECT(mpu6000_dev.spi, mpu6000_dev.spi_id, true);
+ SPI_SNDBLOCK(mpu6000_dev.spi, &cmd, sizeof(cmd));
+ SPI_SELECT(mpu6000_dev.spi, mpu6000_dev.spi_id, false);
+}
+
+static uint8_t
+mpu6000_read_reg(uint8_t address)
+{
+ uint8_t cmd[2] = {address | DIR_READ, 0};
+ uint8_t data[2];
+
+ SPI_SELECT(mpu6000_dev.spi, mpu6000_dev.spi_id, true);
+ SPI_EXCHANGE(mpu6000_dev.spi, cmd, data, sizeof(cmd));
+ SPI_SELECT(mpu6000_dev.spi, mpu6000_dev.spi_id, false);
+
+ return data[1];
+}
+
+static int
+mpu6000_set_range(uint8_t range)
+{
+// /* mask out illegal bit positions */
+// uint8_t write_range = range & REG4_RANGE_MASK;
+// /* immediately return if user supplied invalid value */
+// if (write_range != range) return EINVAL;
+// /* set remaining bits to a sane value */
+// write_range |= REG4_BDU;
+// /* write to device */
+// write_reg(ADDR_CTRL_REG4, write_range);
+// /* return 0 if register value is now written value, 1 if unchanged */
+// return !(read_reg(ADDR_CTRL_REG4) == write_range);
+}
+
+static int
+mpu6000_set_rate(uint8_t rate)
+{
+// /* mask out illegal bit positions */
+// uint8_t write_rate = rate & REG1_RATE_LP_MASK;
+// /* immediately return if user supplied invalid value */
+// if (write_rate != rate) return EINVAL;
+// /* set remaining bits to a sane value */
+// write_rate |= REG1_POWER_NORMAL | REG1_Z_ENABLE | REG1_Y_ENABLE | REG1_X_ENABLE;
+// /* write to device */
+// write_reg(ADDR_CTRL_REG1, write_rate);
+// /* return 0 if register value is now written value, 1 if unchanged */
+// return !(read_reg(ADDR_CTRL_REG1) == write_rate);
+}
+
+static int
+mpu6000_read_fifo(int16_t *data)
+{
+// struct { /* status register and data as read back from the device */
+// uint8_t cmd;
+// uint8_t temp;
+// uint8_t status;
+// int16_t x;
+// int16_t y;
+// int16_t z;
+// } __attribute__((packed)) report;
+//
+// report.cmd = ADDR_OUT_TEMP | DIR_READ | ADDR_INCREMENT;
+//
+// /* exchange the report structure with the device */
+// SPI_LOCK(mpu6000_dev.spi, true);
+//
+// SPI_SELECT(mpu6000_dev.spi, mpu6000_dev.spi_id, true);
+//
+// read_reg(ADDR_WHO_AM_I);
+//
+// SPI_EXCHANGE(mpu6000_dev.spi, &report, &report, sizeof(report));
+// SPI_SELECT(mpu6000_dev.spi, mpu6000_dev.spi_id, false);
+//
+// SPI_LOCK(mpu6000_dev.spi, false);
+//
+//
+//
+ //
+
+ // Device has MSB first at lower address (big endian)
+
+
+ struct { /* status register and data as read back from the device */
+ uint8_t cmd;
+ uint8_t int_status;
+ int16_t xacc;
+ int16_t yacc;
+ int16_t zacc;
+ int8_t temp;
+ int16_t rollspeed;
+ int16_t pitchspeed;
+ int16_t yawspeed;
+ } __attribute__((packed)) report;
+
+ report.cmd = 0x26 | DIR_READ | ADDR_INCREMENT;
+
+ SPI_LOCK(mpu6000_dev.spi, true);
+ SPI_SELECT(mpu6000_dev.spi, PX4_SPIDEV_MPU, true);
+ SPI_EXCHANGE(mpu6000_dev.spi, &report, &report, sizeof(report));
+ SPI_SELECT(mpu6000_dev.spi, PX4_SPIDEV_MPU, false);
+ SPI_LOCK(mpu6000_dev.spi, false);
+
+ data[0] = report.xacc;
+ data[1] = report.yacc;
+ data[2] = report.zacc;
+
+ return (report.int_status & 0x01);
+}
+
+static ssize_t
+mpu6000_read(struct file *filp, char *buffer, size_t buflen)
+{
+ /* if the buffer is large enough, and data are available, return success */
+ if (buflen >= 6) {
+ if (mpu6000_read_fifo((int16_t *)buffer))
+ return 6;
+
+ /* no data */
+ return 0;
+ }
+
+ /* buffer too small */
+ errno = ENOSPC;
+ return ERROR;
+}
+
+static int
+mpu6000_ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ int result = ERROR;
+
+ switch (cmd) {
+ case MPU6000_SETRATE:
+ if ((arg & 0x00/* XXX REG MASK MISSING */) == arg) {
+ SPI_LOCK(mpu6000_dev.spi, true);
+ mpu6000_set_rate(arg);
+ SPI_LOCK(mpu6000_dev.spi, false);
+ result = 0;
+ mpu6000_dev.rate = arg;
+ }
+ break;
+
+ case MPU6000_SETRANGE:
+ if ((arg & 0x00/* XXX REG MASK MISSING */) == arg) {
+ SPI_LOCK(mpu6000_dev.spi, true);
+ mpu6000_set_range(arg);
+ SPI_LOCK(mpu6000_dev.spi, false);
+ result = 0;
+ }
+ break;
+
+ case MPU6000_SETBUFFER:
+ mpu6000_dev.buffer = (struct mpu6000_buffer *)arg;
+ result = 0;
+ break;
+ }
+
+ if (result)
+ errno = EINVAL;
+ return result;
+}
+
+int
+mpu6000_attach(struct spi_dev_s *spi, int spi_id)
+{
+ int result = ERROR;
+
+ mpu6000_dev.spi = spi;
+ mpu6000_dev.spi_id = spi_id;
+
+ SPI_LOCK(mpu6000_dev.spi, true);
+
+ // Set sensor-specific SPI mode
+ SPI_SETFREQUENCY(mpu6000_dev.spi, 10000000); // 500 KHz
+ SPI_SETBITS(mpu6000_dev.spi, 8);
+ // Either mode 1 or mode 3
+ SPI_SETMODE(mpu6000_dev.spi, SPIDEV_MODE3);
+
+ // Chip reset
+ mpu6000_write_reg(MPUREG_PWR_MGMT_1, BIT_H_RESET);
+ up_udelay(10000);
+ // Wake up device and select GyroZ clock (better performance)
+ mpu6000_write_reg(MPUREG_PWR_MGMT_1, MPU_CLK_SEL_PLLGYROZ);
+ up_udelay(1000);
+ // Disable I2C bus (recommended on datasheet)
+ mpu6000_write_reg(MPUREG_USER_CTRL, BIT_I2C_IF_DIS);
+ up_udelay(1000);
+ // SAMPLE RATE
+ mpu6000_write_reg(MPUREG_SMPLRT_DIV,0x04); // Sample rate = 200Hz Fsample= 1Khz/(4+1) = 200Hz
+ usleep(1000);
+ // FS & DLPF FS=2000¼/s, DLPF = 98Hz (low pass filter)
+ mpu6000_write_reg(MPUREG_CONFIG, BITS_DLPF_CFG_98HZ);
+ usleep(1000);
+ mpu6000_write_reg(MPUREG_GYRO_CONFIG,BITS_FS_2000DPS); // Gyro scale 2000¼/s
+ usleep(1000);
+
+ uint8_t _product_id = mpu6000_read_reg(MPUREG_PRODUCT_ID);
+ printf("MPU-6000 product id: %d\n", (int)_product_id);
+
+ if ((_product_id == MPU6000ES_REV_C4) || (_product_id == MPU6000ES_REV_C5) ||
+ (_product_id == MPU6000_REV_C4) || (_product_id == MPU6000_REV_C5)){
+ // Accel scale 8g (4096 LSB/g)
+ // Rev C has different scaling than rev D
+ mpu6000_write_reg(MPUREG_ACCEL_CONFIG,1<<3);
+ } else {
+ // Accel scale 8g (4096 LSB/g)
+ mpu6000_write_reg(MPUREG_ACCEL_CONFIG,2<<3);
+ }
+ usleep(1000);
+
+ // INT CFG => Interrupt on Data Ready
+ mpu6000_write_reg(MPUREG_INT_ENABLE,BIT_RAW_RDY_EN); // INT: Raw data ready
+ usleep(1000);
+ mpu6000_write_reg(MPUREG_INT_PIN_CFG,BIT_INT_ANYRD_2CLEAR); // INT: Clear on any read
+ usleep(1000);
+ // Oscillator set
+ // write_reg(MPUREG_PWR_MGMT_1,MPU_CLK_SEL_PLLGYROZ);
+ usleep(1000);
+
+ /* revert back to normal bus mode */
+ SPI_SETFREQUENCY(mpu6000_dev.spi, 10000000);
+ SPI_SETBITS(mpu6000_dev.spi, 8);
+ SPI_SETMODE(mpu6000_dev.spi, SPIDEV_MODE3);
+
+ /* verify that the device is attached and functioning */
+ if ((_product_id == MPU6000ES_REV_C4) || (_product_id == MPU6000ES_REV_C5) ||
+ (_product_id == MPU6000_REV_C4) || (_product_id == MPU6000_REV_C5) ||
+ (_product_id == MPU6000_REV_D7) || (_product_id == MPU6000_REV_D8) ||
+ (_product_id == MPU6000_REV_D9) || (_product_id == MPU6000_REV_D10)){
+
+ /* make ourselves available */
+ register_driver("/dev/mpu6000", &mpu6000_fops, 0666, NULL);
+
+ result = OK;
+ } else {
+
+ errno = EIO;
+ }
+
+ SPI_LOCK(mpu6000_dev.spi, false);
+
+ SPI_LOCK(mpu6000_dev.spi, false);
+
+ return result;
+}
diff --git a/nuttx/configs/px4fmu/src/drv_ms5611.c b/nuttx/configs/px4fmu/src/drv_ms5611.c
new file mode 100644
index 000000000..7fea65159
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_ms5611.c
@@ -0,0 +1,493 @@
+/*
+ * Copyright (C) 2012 Lorenz Meier. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name of the author or the names of contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/*
+ * Driver for the Measurement Specialties MS5611 barometric pressure sensor
+ */
+
+#include <nuttx/config.h>
+#include <nuttx/i2c.h>
+#include <nuttx/arch.h>
+#include <arch/board/board.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+#include <errno.h>
+#include <string.h>
+#include <stdio.h>
+#include <math.h>
+
+#include "chip.h"
+#include "px4fmu-internal.h"
+
+#include <arch/board/up_hrt.h>
+#include <arch/board/drv_ms5611.h>
+
+/* internal conversion time: 9.17 ms, so should not be read at rates higher than 100 Hz */
+#define MS5611_MIN_INTER_MEASUREMENT_INTERVAL 9200
+
+#define MS5611_ADDRESS_1 0x76 /* address select pins pulled high (PX4FMU series v1.6+) */
+#define MS5611_ADDRESS_2 0x77 /* address select pins pulled low (PX4FMU prototypes) */
+
+#define ADDR_RESET_CMD 0x1E /* read from this address to reset chip (0b0011110 on bus) */
+#define ADDR_CMD_CONVERT_D1 0x48 /* 4096 samples to this address to start conversion (0b01001000 on bus) */
+#define ADDR_CMD_CONVERT_D2 0x58 /* 4096 samples */
+#define ADDR_DATA 0x00 /* address of 3 bytes / 32bit pressure data */
+#define ADDR_PROM_SETUP 0xA0 /* address of 8x 2 bytes factory and calibration data */
+#define ADDR_PROM_C1 0xA2 /* address of 6x 2 bytes calibration data */
+
+static FAR struct ms5611_dev_s ms5611_dev;
+
+static ssize_t ms5611_read(struct file *filp, FAR char *buffer, size_t buflen);
+static int ms5611_ioctl(struct file *filp, int cmd, unsigned long arg);
+
+static const struct file_operations ms5611_fops = {
+ .read = ms5611_read,
+ .ioctl = ms5611_ioctl,
+};
+
+struct ms5611_prom_s
+{
+ uint16_t factory_setup;
+ uint16_t c1_pressure_sens;
+ uint16_t c2_pressure_offset;
+ uint16_t c3_temp_coeff_pres_sens;
+ uint16_t c4_temp_coeff_pres_offset;
+ uint16_t c5_reference_temp;
+ uint16_t c6_temp_coeff_temp;
+ uint16_t serial_and_crc;
+} __attribute__((packed));
+
+union ms5611_prom_u
+{
+ uint16_t c[8];
+ struct ms5611_prom_s s;
+} __attribute__((packed));
+
+struct ms5611_dev_s
+{
+ union ms5611_prom_u prom;
+ struct i2c_dev_s *i2c;
+ struct ms5611_buffer *buffer;
+} __attribute__((packed));
+
+static FAR uint8_t MS5611_ADDRESS;
+
+static FAR struct {
+ /* status register and data as read back from the device */
+ float pressure;
+ float altitude;
+ float temperature;
+ uint32_t d1_raw;
+ uint32_t d2_raw;
+ uint32_t measurements_count;
+ uint8_t last_state;
+ uint64_t last_read;
+ } ms5611_report = {
+ .pressure = 0.0f,
+ .altitude = 0.0f,
+ .temperature = 0.0f,
+ .last_state = 0,
+ /* make sure the first readout can be performed */
+ .last_read = 0,
+};
+
+static int ms5611_read_prom(void);
+
+static bool
+read_values(float *data)
+{
+ int ret;
+ uint8_t cmd_data[3];
+
+ /* check validity of pointer */
+ if (data == NULL)
+ {
+ *get_errno_ptr() = EINVAL;
+ return -EINVAL;
+ }
+
+ /* only start reading when data is available */
+ if (ms5611_report.measurements_count > 0)
+ {
+ /* do not read more often than at minimum 9.17 ms intervals */
+ if ((hrt_absolute_time() - ms5611_report.last_read) < MS5611_MIN_INTER_MEASUREMENT_INTERVAL)
+ {
+ /* set errno to 'come back later' */
+ ret = -EAGAIN;
+ goto handle_return;
+ }
+ else
+ {
+ /* set new value */
+ ms5611_report.last_read = hrt_absolute_time();
+ }
+
+ /* Read out last measurement */
+ cmd_data[0] = 0x00;
+
+ struct i2c_msg_s msgv[2] = {
+ {
+ .addr = MS5611_ADDRESS,
+ .flags = 0,
+ .buffer = cmd_data,
+ .length = 1
+ },
+ {
+ .addr = MS5611_ADDRESS,
+ .flags = I2C_M_READ,
+ .buffer = cmd_data,
+ .length = 3
+ }
+ };
+ ret = I2C_TRANSFER(ms5611_dev.i2c, msgv, 2);
+ if (ret != OK) goto handle_return;
+
+
+ /* at value 1 the last reading was temperature */
+ if (ms5611_report.last_state == 1)
+ {
+ /* put temperature into the raw set */
+ ms5611_report.d2_raw = (((uint32_t)cmd_data[0]) << 16) | (((uint32_t)cmd_data[1]) << 8) | ((uint32_t)cmd_data[2]);
+ }
+ else
+ {
+ /* put altitude into the raw set */
+ ms5611_report.d1_raw = (((uint32_t)cmd_data[0]) << 16) | (((uint32_t)cmd_data[1]) << 8) | ((uint32_t)cmd_data[2]);
+ }
+ }
+ ms5611_report.measurements_count++;
+
+ /*
+ * this block reads four pressure values and one temp value,
+ * resulting in 80 Hz pressure update and 20 Hz temperature updates
+ * at 100 Hz continuous operation.
+ */
+ if (ms5611_report.last_state == 0)
+ {
+ /* request first a temperature reading */
+ cmd_data[0] = ADDR_CMD_CONVERT_D2;
+ }
+ else
+ {
+ /* request pressure reading */
+ cmd_data[0] = ADDR_CMD_CONVERT_D1;
+ }
+
+ if (ms5611_report.last_state == 3)
+ {
+ ms5611_report.last_state = 0;
+ }
+ else
+ {
+ ms5611_report.last_state++;
+ }
+
+
+ /* write measurement command */
+ struct i2c_msg_s conv_cmd[1] = {
+ {
+ .addr = MS5611_ADDRESS,
+ .flags = 0,
+ .buffer = cmd_data,
+ .length = 1
+ },
+ };
+
+ ret = I2C_TRANSFER(ms5611_dev.i2c, conv_cmd, 1);
+ if (ret != OK) goto handle_return;
+
+ /* only write back values after first complete set */
+ if (ms5611_report.measurements_count > 2)
+ {
+ /* Calculate results */
+
+ /* temperature calculation */
+ int32_t dT = ms5611_report.d2_raw - (((int32_t)ms5611_dev.prom.s.c5_reference_temp)*256);
+ int64_t temp_int64 = 2000 + (((int64_t)dT)*ms5611_dev.prom.s.c6_temp_coeff_temp)/8388608;
+
+ /* pressure calculation */
+ int64_t offset = (int64_t)ms5611_dev.prom.s.c2_pressure_offset * 65536 + ((int64_t)dT*ms5611_dev.prom.s.c4_temp_coeff_pres_offset)/128;
+ int64_t sens = (int64_t)ms5611_dev.prom.s.c1_pressure_sens * 32768 + ((int64_t)dT*ms5611_dev.prom.s.c3_temp_coeff_pres_sens)/256;
+
+ /* it's pretty cold, second order temperature compensation needed */
+ if (temp_int64 < 2000)
+ {
+ /* second order temperature compensation */
+ int64_t temp2 = (((int64_t)dT)*dT) >> 31;
+ int64_t tmp_64 = (temp_int64-2000)*(temp_int64-2000);
+ int64_t offset2 = (5*tmp_64)>>1;
+ int64_t sens2 = (5*tmp_64)>>2;
+ temp_int64 = temp_int64 - temp2;
+ offset = offset - offset2;
+ sens = sens - sens2;
+ }
+
+ int64_t press_int64 = (((ms5611_report.d1_raw*sens)/2097152-offset)/32768);
+
+ ms5611_report.temperature = temp_int64 / 100.0f;
+ ms5611_report.pressure = press_int64 / 100.0f;
+ /* convert as double for max. precision, store as float (more than enough precision) */
+ ms5611_report.altitude = (44330.0 * (1.0 - pow((press_int64 / 101325.0), 0.190295)));
+
+ /* Write back float values */
+ data[0] = ms5611_report.pressure;
+ data[1] = ms5611_report.altitude;
+ data[2] = ms5611_report.temperature;
+ }
+ else
+ {
+ /* not ready, try again */
+ ret = -EINPROGRESS;
+ }
+
+ /* return 1 if new data is available, 0 else */
+ handle_return:
+ if (ret == OK)
+ {
+ return (sizeof(ms5611_report.d1_raw) + sizeof(ms5611_report.altitude) + sizeof(ms5611_report.d2_raw));
+ }
+ else
+ {
+ errno = -ret;
+ return ret;
+ }
+}
+
+static ssize_t
+ms5611_read(struct file *filp, char *buffer, size_t buflen)
+{
+ /* if the buffer is large enough, and data are available, return success */
+ if (buflen >= 12) {
+ return read_values((float *)buffer);
+ }
+
+ /* buffer too small */
+ errno = ENOSPC;
+ return -ENOSPC;
+}
+
+static int
+ms5611_ioctl(struct file *filp, int cmd, unsigned long arg)
+{
+ return -ENOSYS;
+
+// switch (cmd) {
+// case MS5611_SETRATE:
+// if ((arg & REG1_RATE_LP_MASK) == arg) {
+// set_rate(arg);
+// result = 0;
+// dev.rate = arg;
+// }
+// break;
+//
+// case MS5611_SETBUFFER:
+// dev.buffer = (struct ms5611_buffer *)arg;
+// result = 0;
+// break;
+// }
+//
+// if (result)
+// errno = EINVAL;
+// return result;
+}
+
+
+
+int ms5611_crc4(uint16_t n_prom[])
+{
+ /* routine ported from MS5611 application note */
+ int16_t cnt;
+ uint16_t n_rem;
+ uint16_t crc_read;
+ uint8_t n_bit;
+ n_rem = 0x00;
+ /* save the read crc */
+ crc_read = n_prom[7];
+ /* remove CRC byte */
+ n_prom[7] = (0xFF00 & (n_prom[7]));
+ for (cnt = 0; cnt < 16; cnt++)
+ {
+ /* uneven bytes */
+ if (cnt & 1)
+ {
+ n_rem ^= (uint8_t) ((n_prom[cnt>>1]) & 0x00FF);
+ }
+ else
+ {
+ n_rem ^= (uint8_t) (n_prom[cnt>>1] >> 8);
+ }
+ for (n_bit = 8; n_bit > 0; n_bit--)
+ {
+ if (n_rem & 0x8000)
+ {
+ n_rem = (n_rem << 1) ^ 0x3000;
+
+ }
+ else
+ {
+ n_rem = (n_rem << 1);
+ }
+ }
+ }
+ /* final 4 bit remainder is CRC value */
+ n_rem = (0x000F & (n_rem >> 12));
+ n_prom[7] = crc_read;
+
+ /* return 0 == OK if CRCs match, 1 else */
+ return !((0x000F & crc_read) == (n_rem ^ 0x00));
+}
+
+
+int ms5611_read_prom()
+{
+ /* read PROM data */
+ uint8_t prom_buf[2] = {255,255};
+
+ int retval = 0;
+
+ for (int i = 0; i < 8; i++)
+ {
+ uint8_t cmd = {ADDR_PROM_SETUP + (i*2)};
+
+ I2C_SETADDRESS(ms5611_dev.i2c, MS5611_ADDRESS, 7);
+ retval = I2C_WRITEREAD(ms5611_dev.i2c, &cmd, 1, prom_buf, 2);
+
+ /* assemble 16 bit value and convert from big endian (sensor) to little endian (MCU) */
+ ms5611_dev.prom.c[i] = (((uint16_t)prom_buf[0])<<8) | ((uint16_t)prom_buf[1]);
+
+ if (retval != OK)
+ {
+ break;
+ }
+ }
+
+ /* calculate CRC and return error if mismatch */
+ return ms5611_crc4(ms5611_dev.prom.c);
+}
+
+int
+ms5611_attach(struct i2c_dev_s *i2c)
+{
+ int result = ERROR;
+
+ ms5611_dev.i2c = i2c;
+
+ MS5611_ADDRESS = MS5611_ADDRESS_1;
+
+ /* write reset command */
+ uint8_t cmd_data = ADDR_RESET_CMD;
+
+ struct i2c_msg_s reset_cmd[1] = {
+ {
+ .addr = MS5611_ADDRESS,
+ .flags = 0,
+ .buffer = &cmd_data,
+ .length = 1
+ },
+ };
+
+ int ret = I2C_TRANSFER(ms5611_dev.i2c, reset_cmd, 1);
+
+ if (ret == OK)
+ {
+ /* wait for PROM contents to be in the device (2.8 ms) */
+ up_udelay(3000);
+
+ /* read PROM */
+ ret = ms5611_read_prom();
+ }
+
+ /* check if the address was wrong */
+ if (ret != OK)
+ {
+ /* try second address */
+ MS5611_ADDRESS = MS5611_ADDRESS_2;
+
+ /* write reset command */
+ cmd_data = ADDR_RESET_CMD;
+
+ struct i2c_msg_s reset_cmd_2[1] = {
+ {
+ .addr = MS5611_ADDRESS,
+ .flags = 0,
+ .buffer = &cmd_data,
+ .length = 1
+ },
+ };
+
+ ret = I2C_TRANSFER(ms5611_dev.i2c, reset_cmd_2, 1);
+
+ /* wait for PROM contents to be in the device (2.8 ms) */
+ up_udelay(3000);
+
+ /* read PROM */
+ ret = ms5611_read_prom();
+ }
+
+ if (ret < 0) return -EIO;
+
+
+ /* verify that the device is attached and functioning */
+ if (ret == OK) {
+
+ if (MS5611_ADDRESS == MS5611_ADDRESS_1)
+ {
+ printf("[ms5611 driver] Attached MS5611 at addr #1 (0x76)\n");
+ }
+ else
+ {
+ printf("[ms5611 driver] Attached MS5611 at addr #2 (0x77)\n");
+ }
+
+ /* trigger temperature read */
+ (void)read_values(NULL);
+ /* wait for conversion to complete */
+ up_udelay(9200);
+
+ /* trigger pressure read */
+ (void)read_values(NULL);
+ /* wait for conversion to complete */
+ up_udelay(9200);
+ /* now a read_values call would obtain valid results */
+
+ /* make ourselves available */
+ register_driver("/dev/ms5611", &ms5611_fops, 0666, NULL);
+
+ result = OK;
+
+ } else {
+ errno = EIO;
+ }
+
+ return result;
+}
diff --git a/nuttx/configs/px4fmu/src/drv_tone_alarm.c b/nuttx/configs/px4fmu/src/drv_tone_alarm.c
new file mode 100644
index 000000000..958a18904
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/drv_tone_alarm.c
@@ -0,0 +1,511 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * Speaker driver supporting alarm sequences.
+ *
+ * Works with any of the 'generic' STM32 timers that has an output
+ * pin, does not require an interrupt.
+ *
+ * Depends on the HRT timer.
+ */
+
+#include <nuttx/config.h>
+#include <nuttx/arch.h>
+#include <nuttx/irq.h>
+
+#include <sys/types.h>
+#include <stdbool.h>
+
+#include <assert.h>
+#include <debug.h>
+#include <time.h>
+#include <queue.h>
+#include <errno.h>
+#include <string.h>
+#include <stdio.h>
+
+#include <arch/board/board.h>
+#include <arch/board/drv_tone_alarm.h>
+#include <arch/board/up_hrt.h>
+
+#include "chip.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+#include "stm32_internal.h"
+#include "stm32_gpio.h"
+#include "stm32_tim.h"
+
+#ifdef CONFIG_TONE_ALARM
+# ifndef CONFIG_HRT_TIMER
+# error CONFIG_TONE_ALARM requires CONFIG_HRT_TIMER
+# endif
+
+/* Tone alarm configuration */
+#if TONE_ALARM_TIMER == 2
+# define TONE_ALARM_BASE STM32_TIM2_BASE
+# define TONE_ALARM_CLOCK STM32_APB1_TIM2_CLKIN
+# define TONE_ALARM_CLOCK_ENABLE RCC_APB1ENR_TIM2EN
+# ifdef CONFIG_STM32_TIM2
+# error Must not set CONFIG_STM32_TIM2 when TONE_ALARM_TIMER is 2
+# endif
+#elif TONE_ALARM_TIMER == 3
+# define TONE_ALARM_BASE STM32_TIM3_BASE
+# define TONE_ALARM_CLOCK STM32_APB1_TIM3_CLKIN
+# define TONE_ALARM_CLOCK_ENABLE RCC_APB1ENR_TIM3EN
+# ifdef CONFIG_STM32_TIM3
+# error Must not set CONFIG_STM32_TIM3 when TONE_ALARM_TIMER is 3
+# endif
+#elif TONE_ALARM_TIMER == 4
+# define TONE_ALARM_BASE STM32_TIM4_BASE
+# define TONE_ALARM_CLOCK STM32_APB1_TIM4_CLKIN
+# define TONE_ALARM_CLOCK_ENABLE RCC_APB1ENR_TIM4EN
+# ifdef CONFIG_STM32_TIM4
+# error Must not set CONFIG_STM32_TIM4 when TONE_ALARM_TIMER is 4
+# endif
+#elif TONE_ALARM_TIMER == 5
+# define TONE_ALARM_BASE STM32_TIM5_BASE
+# define TONE_ALARM_CLOCK STM32_APB1_TIM5_CLKIN
+# define TONE_ALARM_CLOCK_ENABLE RCC_APB1ENR_TIM5EN
+# ifdef CONFIG_STM32_TIM5
+# error Must not set CONFIG_STM32_TIM5 when TONE_ALARM_TIMER is 5
+# endif
+#elif TONE_ALARM_TIMER == 9
+# define TONE_ALARM_BASE STM32_TIM9_BASE
+# define TONE_ALARM_CLOCK STM32_APB1_TIM9_CLKIN
+# define TONE_ALARM_CLOCK_ENABLE RCC_APB1ENR_TIM9EN
+# ifdef CONFIG_STM32_TIM9
+# error Must not set CONFIG_STM32_TIM9 when TONE_ALARM_TIMER is 9
+# endif
+#elif TONE_ALARM_TIMER == 10
+# define TONE_ALARM_BASE STM32_TIM10_BASE
+# define TONE_ALARM_CLOCK STM32_APB1_TIM10_CLKIN
+# define TONE_ALARM_CLOCK_ENABLE RCC_APB1ENR_TIM10EN
+# ifdef CONFIG_STM32_TIM10
+# error Must not set CONFIG_STM32_TIM10 when TONE_ALARM_TIMER is 10
+# endif
+#elif TONE_ALARM_TIMER == 11
+# define TONE_ALARM_BASE STM32_TIM11_BASE
+# define TONE_ALARM_CLOCK STM32_APB1_TIM11_CLKIN
+# define TONE_ALARM_CLOCK_ENABLE RCC_APB1ENR_TIM11EN
+# ifdef CONFIG_STM32_TIM11
+# error Must not set CONFIG_STM32_TIM11 when TONE_ALARM_TIMER is 11
+# endif
+#else
+# error Must set TONE_ALARM_TIMER to a generic timer if CONFIG_TONE_ALARM is set
+#endif
+
+#if TONE_ALARM_CHANNEL == 1
+# define TONE_CCMR1 (3 << 4)
+# define TONE_CCMR2 0
+# define TONE_CCER (1 << 0)
+# define TONE_rCCR rCCR1
+#elif TONE_ALARM_CHANNEL == 2
+# define TONE_CCMR1 (3 << 12)
+# define TONE_CCMR2 0
+# define TONE_CCER (1 << 4)
+# define TONE_rCCR rCCR2
+#elif TONE_ALARM_CHANNEL == 3
+# define TONE_CCMR1 0
+# define TONE_CCMR2 (3 << 4)
+# define TONE_CCER (1 << 8)
+# define TONE_rCCR rCCR3
+#elif TONE_ALARM_CHANNEL == 4
+# define TONE_CCMR1 0
+# define TONE_CCMR2 (3 << 12)
+# define TONE_CCER (1 << 12)
+# define TONE_rCCR rCCR4
+#else
+# error Must set TONE_ALARM_CHANNEL to a value between 1 and 4
+#endif
+
+/*
+ * Timer register accessors
+ */
+#define REG(_reg) (*(volatile uint32_t *)(TONE_ALARM_BASE + _reg))
+
+#define rCR1 REG(STM32_GTIM_CR1_OFFSET)
+#define rCR2 REG(STM32_GTIM_CR2_OFFSET)
+#define rSMCR REG(STM32_GTIM_SMCR_OFFSET)
+#define rDIER REG(STM32_GTIM_DIER_OFFSET)
+#define rSR REG(STM32_GTIM_SR_OFFSET)
+#define rEGR REG(STM32_GTIM_EGR_OFFSET)
+#define rCCMR1 REG(STM32_GTIM_CCMR1_OFFSET)
+#define rCCMR2 REG(STM32_GTIM_CCMR2_OFFSET)
+#define rCCER REG(STM32_GTIM_CCER_OFFSET)
+#define rCNT REG(STM32_GTIM_CNT_OFFSET)
+#define rPSC REG(STM32_GTIM_PSC_OFFSET)
+#define rARR REG(STM32_GTIM_ARR_OFFSET)
+#define rCCR1 REG(STM32_GTIM_CCR1_OFFSET)
+#define rCCR2 REG(STM32_GTIM_CCR2_OFFSET)
+#define rCCR3 REG(STM32_GTIM_CCR3_OFFSET)
+#define rCCR4 REG(STM32_GTIM_CCR4_OFFSET)
+#define rDCR REG(STM32_GTIM_DCR_OFFSET)
+#define rDMAR REG(STM32_GTIM_DMAR_OFFSET)
+
+#define TONE_MAX_PATTERN 6
+#define TONE_MAX_PATTERN_LEN 40
+
+/* predefined patterns for alarms 1-TONE_MAX_PATTERN */
+const struct tone_note patterns[TONE_MAX_PATTERN][TONE_MAX_PATTERN_LEN] = {
+ {
+ {TONE_NOTE_A7, 12},
+ {TONE_NOTE_D8, 12},
+ {TONE_NOTE_C8, 12},
+ {TONE_NOTE_A7, 12},
+ {TONE_NOTE_D8, 12},
+ {TONE_NOTE_C8, 12},
+ {TONE_NOTE_D8, 4},
+ {TONE_NOTE_C8, 4},
+ {TONE_NOTE_D8, 4},
+ {TONE_NOTE_C8, 4},
+ {TONE_NOTE_D8, 4},
+ {TONE_NOTE_C8, 4},
+ },
+ {{TONE_NOTE_B6, 100}},
+ {{TONE_NOTE_C7, 100}},
+ {{TONE_NOTE_D7, 100}},
+ {{TONE_NOTE_E7, 100}},
+ { //This is tetris ;)
+ {TONE_NOTE_C6, 40},
+ {TONE_NOTE_G5, 20},
+ {TONE_NOTE_G5S, 20},
+ {TONE_NOTE_A5S, 40},
+ {TONE_NOTE_G5S, 20},
+ {TONE_NOTE_G5, 20},
+ {TONE_NOTE_F5, 40},
+ {TONE_NOTE_F5, 20},
+ {TONE_NOTE_G5S, 20},
+ {TONE_NOTE_C6, 40},
+ {TONE_NOTE_A5S, 20},
+ {TONE_NOTE_G5S, 20},
+ {TONE_NOTE_G5, 60},
+ {TONE_NOTE_G5S, 20},
+ {TONE_NOTE_A5S, 40},
+ {TONE_NOTE_C6, 40},
+ {TONE_NOTE_G5S, 40},
+ {TONE_NOTE_F5, 40},
+ {TONE_NOTE_F5, 60},
+
+ {TONE_NOTE_A5S, 40},
+ {TONE_NOTE_C6S, 20},
+ {TONE_NOTE_F6, 40},
+ {TONE_NOTE_D6S, 20},
+ {TONE_NOTE_C6S, 20},
+ {TONE_NOTE_C6, 60},
+ {TONE_NOTE_G5S, 20},
+ {TONE_NOTE_C6, 40},
+ {TONE_NOTE_A5S, 20},
+ {TONE_NOTE_G5S, 20},
+ {TONE_NOTE_G5, 40},
+ {TONE_NOTE_G5, 20},
+ {TONE_NOTE_G5S, 20},
+ {TONE_NOTE_A5S, 40},
+ {TONE_NOTE_C6, 40},
+ {TONE_NOTE_G5S, 40},
+ {TONE_NOTE_F5, 40},
+ {TONE_NOTE_F5, 60},
+ }
+};
+
+static uint16_t notes[TONE_NOTE_MAX] = {
+ 63707, /* E4 */
+ 60132, /* F4 */
+ 56758, /* F#4/Gb4 */
+ 53571, /* G4 */
+ 50565, /* G#4/Ab4 */
+ 47727, /* A4 */
+ 45048, /* A#4/Bb4 */
+ 42520, /* B4 */
+ 40133, /* C5 */
+ 37880, /* C#5/Db5 */
+ 35755, /* D5 */
+ 33748, /* D#5/Eb5 */
+ 31853, /* E5 */
+ 30066, /* F5 */
+ 28378, /* F#5/Gb5 */
+ 26786, /* G5 */
+ 25282, /* G#5/Ab5 */
+ 23863, /* A5 */
+ 22524, /* A#5/Bb5 */
+ 21260, /* B5 */
+ 20066, /* C6 */
+ 18940, /* C#6/Db6 */
+ 17877, /* D6 */
+ 16874, /* D#6/Eb6 */
+ 15927, /* E6 */
+ 15033, /* F6 */
+ 14189, /* F#6/Gb6 */
+ 13393, /* G6 */
+ 12641, /* G#6/Ab6 */
+ 11931, /* A6 */
+ 11262, /* A#6/Bb6 */
+ 10630, /* B6 */
+ 10033, /* C7 */
+ 9470, /* C#7/Db7 */
+ 8938, /* D7 */
+ 8437, /* D#7/Eb7 */
+ 7963, /* E7 */
+ 7516, /* F7 */
+ 7094, /* F#7/Gb7 */
+ 6696, /* G7 */
+ 6320, /* G#7/Ab7 */
+ 5965, /* A7 */
+ 5631, /* A#7/Bb7 */
+ 5315, /* B7 */
+ 5016, /* C8 */
+ 4735, /* C#8/Db8 */
+ 4469, /* D8 */
+ 4218 /* D#8/Eb8 */
+};
+
+/* current state of the tone driver */
+struct state {
+ int pattern; /* current pattern */
+#define PATTERN_NONE -1
+#define PATTERN_USER 0
+ int note; /* next note to play */
+ struct hrt_call note_end;
+ struct tone_note user_pattern[TONE_MAX_PATTERN_LEN]; /* user-supplied pattern (plays at pattern 0) */
+};
+
+static struct state tone_state;
+
+static int tone_write(struct file *filp, const char *buffer, size_t len);
+static int tone_ioctl(struct file *filep, int cmd, unsigned long arg);
+
+static const struct file_operations tone_fops = {
+ .write = tone_write,
+ .ioctl = tone_ioctl
+};
+
+static void tone_next(void);
+static bool tone_ok(struct tone_note *pattern);
+int
+tone_alarm_init(void)
+{
+ /* configure the GPIO */
+ stm32_configgpio(GPIO_TONE_ALARM);
+
+ /* clock/power on our timer */
+ modifyreg32(STM32_RCC_APB1ENR, 0, TONE_ALARM_CLOCK_ENABLE);
+
+ /* default the state */
+ tone_state.pattern = -1;
+
+ /* initialise the timer */
+ rCR1 = 0;
+ rCR2 = 0;
+ rSMCR = 0;
+ rDIER = 0;
+ rCCER = 0; /* unlock CCMR* registers */
+ rCCMR1 = TONE_CCMR1;
+ rCCMR2 = TONE_CCMR2;
+ rCCER = TONE_CCER;
+ rDCR = 0;
+
+ /* toggle the CC output each time the count passes 1 */
+ TONE_rCCR = 1;
+
+ /*
+ * Configure the timebase to free-run at half max frequency.
+ * XXX this should be more flexible in order to get a better
+ * frequency range, but for the F4 with the APB1 timers based
+ * at 42MHz, this gets us down to ~320Hz or so.
+ */
+ rPSC = 1;
+
+ tone_state.pattern = PATTERN_NONE;
+ tone_state.note = 0;
+
+ /* play the startup tune */
+ tone_ioctl(NULL, TONE_SET_ALARM, 1);
+
+ /* register the device */
+ return register_driver("/dev/tone_alarm", &tone_fops, 0666, NULL);
+}
+
+static int
+tone_ioctl(struct file *filep, int cmd, unsigned long arg)
+{
+ int result = 0;
+ int new = (int)arg;
+
+ irqstate_t flags = irqsave();
+
+ /* decide whether to increase the alarm level to cmd or leave it alone */
+ switch (cmd) {
+ case TONE_SET_ALARM:
+ if (new == 0) {
+ /* cancel any current alarm */
+ tone_state.pattern = PATTERN_NONE;
+ tone_next();
+
+ } else if (new > TONE_MAX_PATTERN) {
+
+ /* not a legal alarm value */
+ result = -ERANGE;
+
+ } else if (new > tone_state.pattern) {
+
+ /* higher priority than the current alarm */
+ tone_state.pattern = new;
+ tone_state.note = 0;
+
+ /* and start playing it */
+ tone_next();
+ }
+ break;
+ default:
+ result = -EINVAL;
+ break;
+ }
+
+ irqrestore(flags);
+ return result;
+}
+
+static int
+tone_write(struct file *filp, const char *buffer, size_t len)
+{
+ irqstate_t flags;
+
+ /* sanity-check the size of the write */
+ if (len > (TONE_MAX_PATTERN_LEN * sizeof(struct tone_note)))
+ return -EFBIG;
+ if ((len % sizeof(struct tone_note)) || (len == 0))
+ return -EIO;
+ if (!tone_ok((struct tone_note *)buffer))
+ return -EIO;
+
+ flags = irqsave();
+
+ /* if we aren't playing an alarm tone */
+ if (tone_state.pattern <= PATTERN_USER) {
+
+ /* reset the tone state to play the new user pattern */
+ tone_state.pattern = PATTERN_USER;
+ tone_state.note = 0;
+
+ /* copy in the new pattern */
+ memset(tone_state.user_pattern, 0, sizeof(tone_state.user_pattern));
+ memcpy(tone_state.user_pattern, buffer, len);
+
+ /* and start it */
+ tone_next();
+ }
+ irqrestore(flags);
+
+ return len;
+}
+
+static void
+tone_next(void)
+{
+ const struct tone_note *np;
+
+ /* stop the current note */
+ rCR1 = 0;
+
+ /* if we are no longer playing a pattern, we have nothing else to do here */
+ if (tone_state.pattern == PATTERN_NONE) {
+ return;
+ }
+
+ /* if the current pattern has ended, clear the pattern and stop */
+ if (tone_state.note == TONE_NOTE_MAX) {
+ tone_state.pattern = PATTERN_NONE;
+ return;
+ }
+
+ /* find the note to play */
+ if (tone_state.pattern == PATTERN_USER) {
+ np = &tone_state.user_pattern[tone_state.note];
+ } else {
+ np = &patterns[tone_state.pattern - 1][tone_state.note];
+ }
+
+ /* work out which note is next */
+ tone_state.note++;
+ if (tone_state.note >= TONE_NOTE_MAX) {
+ /* hit the end of the pattern, stop */
+ tone_state.pattern = PATTERN_NONE;
+ } else if (np[1].duration == DURATION_END) {
+ /* hit the end of the pattern, stop */
+ tone_state.pattern = PATTERN_NONE;
+ } else if (np[1].duration == DURATION_REPEAT) {
+ /* next note is a repeat, rewind in preparation */
+ tone_state.note = 0;
+ }
+
+ /* set the timer to play the note, if required */
+ if (np->pitch <= TONE_NOTE_SILENCE) {
+
+ /* set reload based on the pitch */
+ rARR = notes[np->pitch];
+
+ /* force an update, reloads the counter and all registers */
+ rEGR = GTIM_EGR_UG;
+
+ /* start the timer */
+ rCR1 = GTIM_CR1_CEN;
+ }
+
+ /* arrange a callback when the note/rest is done */
+ hrt_call_after(&tone_state.note_end, (hrt_abstime)10000 * np->duration, (hrt_callout)tone_next, NULL);
+
+}
+
+static bool
+tone_ok(struct tone_note *pattern)
+{
+ int i;
+
+ for (i = 0; i < TONE_NOTE_MAX; i++) {
+
+ /* first note must not be repeat or end */
+ if ((i == 0) &&
+ ((pattern[i].duration == DURATION_END) || (pattern[i].duration == DURATION_REPEAT)))
+ return false;
+ if (pattern[i].duration == DURATION_END)
+ break;
+
+ /* pitch must be legal */
+ if (pattern[i].pitch >= TONE_NOTE_MAX)
+ return false;
+ }
+ return true;
+}
+
+#endif /* CONFIG_TONE_ALARM */ \ No newline at end of file
diff --git a/nuttx/configs/px4fmu/src/px4fmu-internal.h b/nuttx/configs/px4fmu/src/px4fmu-internal.h
new file mode 100644
index 000000000..f48b1bf5e
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/px4fmu-internal.h
@@ -0,0 +1,166 @@
+/****************************************************************************************************
+ * configs/px4fmu/src/px4fmu_internal.h
+ * arch/arm/src/board/px4fmu_internal.n
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************************************/
+
+#ifndef __CONFIGS_PX4FMU_SRC_PX4FMU_INTERNAL_H
+#define __CONFIGS_PX4FMU_SRC_PX4FMU_INTERNAL_H
+
+/****************************************************************************************************
+ * Included Files
+ ****************************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+#include <stdint.h>
+
+/****************************************************************************************************
+ * Definitions
+ ****************************************************************************************************/
+/* Configuration ************************************************************************************/
+
+#ifdef CONFIG_STM32_SPI2
+# error "SPI2 is not supported on this board"
+#endif
+
+#if defined(CONFIG_STM32_CAN1)
+# warning "CAN1 is not supported on this board"
+#endif
+
+/* PX4FMU GPIOs ***********************************************************************************/
+/* LEDs */
+
+#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN15)
+#define GPIO_LED2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN14)
+
+/* External interrupts */
+#define GPIO_EXTI_COMPASS (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN1)
+// XXX MPU6000 DRDY?
+
+/* SPI chip selects */
+#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14)
+#define GPIO_SPI_CS_ACCEL (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
+#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
+#define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
+
+/* User GPIOs
+ *
+ * GPIO0-1 are the buffered high-power GPIOs.
+ * GPIO2-5 are the USART2 pins.
+ * GPIO6-7 are the CAN2 pins.
+ */
+#define GPIO_GPIO0_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN4)
+#define GPIO_GPIO1_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN5)
+#define GPIO_GPIO2_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_GPIO3_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_GPIO4_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN2)
+#define GPIO_GPIO5_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_GPIO6_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN13)
+#define GPIO_GPIO7_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN2)
+#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN4)
+#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN5)
+#define GPIO_GPIO2_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
+#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN1)
+#define GPIO_GPIO4_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN2)
+#define GPIO_GPIO5_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN3)
+#define GPIO_GPIO6_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN13)
+#define GPIO_GPIO7_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN12)
+#define GPIO_GPIO_DIR (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
+
+/* USB OTG FS
+ *
+ * PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED)
+ */
+#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9)
+
+/* PWM
+ *
+ * The PX4FMU has five PWM outputs, of which only the output on
+ * pin PC8 is fixed assigned to this function. The other four possible
+ * pwm sources are the TX, RX, RTS and CTS pins of USART2
+ *
+ * Alternate function mapping:
+ * PC8 - BUZZER - TIM8_CH3/SDIO_D0 /TIM3_CH3/ USART6_CK / DCMI_D2
+ */
+
+#ifdef CONFIG_PWM
+# if defined(CONFIG_STM32_TIM3_PWM)
+# define BUZZER_PWMCHANNEL 3
+# define BUZZER_PWMTIMER 3
+# elif defined(CONFIG_STM32_TIM8_PWM)
+# define BUZZER_PWMCHANNEL 3
+# define BUZZER_PWMTIMER 8
+# endif
+#endif
+
+/****************************************************************************************************
+ * Public Types
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Public data
+ ****************************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/****************************************************************************************************
+ * Public Functions
+ ****************************************************************************************************/
+
+/****************************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the PX4FMU board.
+ *
+ ****************************************************************************************************/
+
+extern void stm32_spiinitialize(void);
+
+/****************************************************************************************************
+ * Name: px4fmu_gpio_init
+ *
+ * Description:
+ * Called to configure the PX4FMU user GPIOs
+ *
+ ****************************************************************************************************/
+
+extern void px4fmu_gpio_init(void);
+
+
+// XXX additional SPI chipselect functions required?
+
+#endif /* __ASSEMBLY__ */
+#endif /* __CONFIGS_PX4FMU_SRC_PX4FMU_INTERNAL_H */
+
diff --git a/nuttx/configs/px4fmu/src/up_adc.c b/nuttx/configs/px4fmu/src/up_adc.c
new file mode 100644
index 000000000..2d74e6f00
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_adc.c
@@ -0,0 +1,173 @@
+/************************************************************************************
+ * configs/stm3240g-eval/src/up_adc.c
+ * arch/arm/src/board/up_adc.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <errno.h>
+#include <debug.h>
+#include <stdio.h>
+
+#include <nuttx/analog/adc.h>
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+
+//#include "stm32_pwm.h"
+#include "stm32_adc.h"
+#include "px4fmu-internal.h"
+
+#ifdef CONFIG_ADC
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Configuration ************************************************************/
+/* Up to 3 ADC interfaces are supported */
+
+#if STM32_NADC < 3
+# undef CONFIG_STM32_ADC3
+#endif
+
+#if STM32_NADC < 2
+# undef CONFIG_STM32_ADC2
+#endif
+
+#if STM32_NADC < 1
+# undef CONFIG_STM32_ADC3
+#endif
+
+#if defined(CONFIG_STM32_ADC1) || defined(CONFIG_STM32_ADC2) || defined(CONFIG_STM32_ADC3)
+#ifndef CONFIG_STM32_ADC3
+# warning "Channel information only available for ADC3"
+#endif
+
+#define ADC3_NCHANNELS 4
+
+/************************************************************************************
+ * Private Data
+ ************************************************************************************/
+/* The PX4FMU board has four ADC channels: ADC323 IN10-13
+ */
+
+/* Identifying number of each ADC channel: Variable Resistor. */
+
+#ifdef CONFIG_STM32_ADC3
+static const uint8_t g_chanlist[ADC3_NCHANNELS] = {10, 11};// , 12, 13}; ADC12 and 13 are used by MPU on v1.5 boards
+
+/* Configurations of pins used byte each ADC channels */
+static const uint32_t g_pinlist[ADC3_NCHANNELS] = {GPIO_ADC3_IN10, GPIO_ADC3_IN11}; // ADC12 and 13 are used by MPU on v1.5 boards, GPIO_ADC3_IN12, GPIO_ADC3_IN13};
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: adc_devinit
+ *
+ * Description:
+ * All STM32 architectures must provide the following interface to work with
+ * examples/adc.
+ *
+ ************************************************************************************/
+
+int adc_devinit(void)
+{
+#ifdef CONFIG_STM32_ADC3
+ static bool initialized = false;
+ struct adc_dev_s *adc[ADC3_NCHANNELS];
+ int ret;
+ int i;
+
+ /* Check if we have already initialized */
+
+ if (!initialized)
+ {
+ char name[11];
+
+ for (i = 0; i < ADC3_NCHANNELS; i++)
+ {
+ stm32_configgpio(g_pinlist[i]);
+ }
+
+ for (i = 0; i < 1; i++)
+ {
+ /* Configure the pins as analog inputs for the selected channels */
+ //stm32_configgpio(g_pinlist[i]);
+
+ /* Call stm32_adcinitialize() to get an instance of the ADC interface */
+ //multiple channels only supported with dma!
+ adc[i] = stm32_adcinitialize(3, (g_chanlist), 4);
+ if (adc == NULL)
+ {
+ adbg("ERROR: Failed to get ADC interface\n");
+ return -ENODEV;
+ }
+
+
+ /* Register the ADC driver at "/dev/adc0" */
+ sprintf(name, "/dev/adc%d", i);
+ ret = adc_register(name, adc[i]);
+ if (ret < 0)
+ {
+ adbg("adc_register failed for adc %s: %d\n", name, ret);
+ return ret;
+ }
+ }
+
+ /* Now we are initialized */
+
+ initialized = true;
+ }
+
+ return OK;
+#else
+ return -ENOSYS;
+#endif
+}
+
+#endif /* CONFIG_STM32_ADC || CONFIG_STM32_ADC2 || CONFIG_STM32_ADC3 */
+#endif /* CONFIG_ADC */
diff --git a/nuttx/configs/px4fmu/src/up_boot.c b/nuttx/configs/px4fmu/src/up_boot.c
new file mode 100644
index 000000000..da396cdd6
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_boot.c
@@ -0,0 +1,76 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "px4fmu-internal.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+void stm32_boardinitialize(void)
+{
+ /* configure SPI interfaces */
+ stm32_spiinitialize();
+
+ /* configure LEDs */
+ up_ledinit();
+}
diff --git a/nuttx/configs/px4fmu/src/up_can.c b/nuttx/configs/px4fmu/src/up_can.c
new file mode 100644
index 000000000..daf6484f2
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_can.c
@@ -0,0 +1,142 @@
+/************************************************************************************
+ * configs/px4fmu/src/up_can.c
+ * arch/arm/src/board/up_can.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/can.h>
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+
+#include "stm32.h"
+#include "stm32_can.h"
+#include "px4fmu-internal.h"
+
+#if defined(CONFIG_CAN) && (defined(CONFIG_STM32_CAN1) || defined(CONFIG_STM32_CAN2))
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* Configuration ********************************************************************/
+
+#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
+# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
+# undef CONFIG_STM32_CAN2
+#endif
+
+#ifdef CONFIG_STM32_CAN1
+# define CAN_PORT 1
+#else
+# define CAN_PORT 2
+#endif
+
+/* Debug ***************************************************************************/
+/* Non-standard debug that may be enabled just for testing CAN */
+
+#ifdef CONFIG_DEBUG_CAN
+# define candbg dbg
+# define canvdbg vdbg
+# define canlldbg lldbg
+# define canllvdbg llvdbg
+#else
+# define candbg(x...)
+# define canvdbg(x...)
+# define canlldbg(x...)
+# define canllvdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: can_devinit
+ *
+ * Description:
+ * All STM32 architectures must provide the following interface to work with
+ * examples/can.
+ *
+ ************************************************************************************/
+
+int can_devinit(void)
+{
+ static bool initialized = false;
+ struct can_dev_s *can;
+ int ret;
+
+ /* Check if we have already initialized */
+
+ if (!initialized)
+ {
+ /* Call stm32_caninitialize() to get an instance of the CAN interface */
+
+ can = stm32_caninitialize(CAN_PORT);
+ if (can == NULL)
+ {
+ candbg("ERROR: Failed to get CAN interface\n");
+ return -ENODEV;
+ }
+
+ /* Register the CAN driver at "/dev/can0" */
+
+ ret = can_register("/dev/can0", can);
+ if (ret < 0)
+ {
+ candbg("ERROR: can_register failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Now we are initialized */
+
+ initialized = true;
+ }
+
+ return OK;
+}
+
+#endif /* CONFIG_STM32_CAN || CONFIG_STM32_CAN2 || CONFIG_STM32_CAN3 */
diff --git a/nuttx/configs/px4fmu/src/up_cpuload.c b/nuttx/configs/px4fmu/src/up_cpuload.c
new file mode 100644
index 000000000..750ec4852
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_cpuload.c
@@ -0,0 +1,182 @@
+/****************************************************************************
+ * configs/px4fmu/src/up_leds.c
+ * arch/arm/src/board/up_leds.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <sys/time.h>
+
+#include <arch/board/board.h>
+#include <arch/board/up_hrt.h>
+#include <arch/board/up_cpuload.h>
+
+#include "chip.h"
+#include "up_arch.h"
+#include "up_internal.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name:
+ ****************************************************************************/
+
+#ifdef CONFIG_SCHED_INSTRUMENTATION
+
+struct system_load_s system_load;
+
+extern FAR _TCB *sched_gettcb(pid_t pid);
+
+void cpuload_initialize_once(void);
+
+void cpuload_initialize_once()
+{
+// if (!system_load.initialized)
+// {
+ system_load.start_time = hrt_absolute_time();
+ int i;
+ for (i = 0; i < CONFIG_MAX_TASKS; i++)
+ {
+ system_load.tasks[i].valid = false;
+ }
+ system_load.total_count = 0;
+
+ uint64_t now = hrt_absolute_time();
+
+ /* initialize idle thread statically */
+ system_load.tasks[0].start_time = now;
+ system_load.tasks[0].total_runtime = 0;
+ system_load.tasks[0].curr_start_time = 0;
+ system_load.tasks[0].tcb = sched_gettcb(0);
+ system_load.tasks[0].valid = true;
+ system_load.total_count++;
+
+ /* initialize init thread statically */
+ system_load.tasks[1].start_time = now;
+ system_load.tasks[1].total_runtime = 0;
+ system_load.tasks[1].curr_start_time = 0;
+ system_load.tasks[1].tcb = sched_gettcb(1);
+ system_load.tasks[1].valid = true;
+ /* count init thread */
+ system_load.total_count++;
+ // }
+}
+
+void sched_note_start(FAR _TCB *tcb )
+{
+ /* search first free slot */
+ int i;
+ for (i = 1; i < CONFIG_MAX_TASKS; i++)
+ {
+ if (!system_load.tasks[i].valid)
+ {
+ /* slot is available */
+ system_load.tasks[i].start_time = hrt_absolute_time();
+ system_load.tasks[i].total_runtime = 0;
+ system_load.tasks[i].curr_start_time = 0;
+ system_load.tasks[i].tcb = tcb;
+ system_load.tasks[i].valid = true;
+ system_load.total_count++;
+ break;
+ }
+ }
+}
+
+void sched_note_stop(FAR _TCB *tcb )
+{
+ int i;
+ for (i = 1; i < CONFIG_MAX_TASKS; i++)
+ {
+ if (system_load.tasks[i].tcb->pid == tcb->pid)
+ {
+ /* mark slot as fee */
+ system_load.tasks[i].valid = false;
+ system_load.tasks[i].total_runtime = 0;
+ system_load.tasks[i].curr_start_time = 0;
+ system_load.tasks[i].tcb = NULL;
+ system_load.total_count--;
+ break;
+ }
+ }
+}
+
+void sched_note_switch(FAR _TCB *pFromTcb, FAR _TCB *pToTcb)
+{
+ uint64_t new_time = hrt_absolute_time();
+
+ /* Kind of inefficient: find both tasks and update times */
+ uint8_t both_found = 0;
+ for (int i = 0; i < CONFIG_MAX_TASKS; i++)
+ {
+ /* Task ending its current scheduling run */
+ if (system_load.tasks[i].tcb->pid == pFromTcb->pid)
+ {
+ //if (system_load.tasks[i].curr_start_time != 0)
+ {
+ system_load.tasks[i].total_runtime += new_time - system_load.tasks[i].curr_start_time;
+ }
+ both_found++;
+ }
+ else if (system_load.tasks[i].tcb->pid == pToTcb->pid)
+ {
+ system_load.tasks[i].curr_start_time = new_time;
+ both_found++;
+ }
+
+ /* Do only iterate as long as needed */
+ if (both_found == 2)
+ {
+ break;
+ }
+ }
+}
+
+#endif /* CONFIG_SCHED_INSTRUMENTATION */
diff --git a/nuttx/configs/px4fmu/src/up_hrt.c b/nuttx/configs/px4fmu/src/up_hrt.c
new file mode 100644
index 000000000..35aecfe08
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_hrt.c
@@ -0,0 +1,801 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file High-resolution timer callouts and timekeeping.
+ *
+ * This can use any general or advanced STM32 timer.
+ *
+ * Note that really, this could use systick too, but that's
+ * monopolised by NuttX and stealing it would just be awkward.
+ *
+ * We don't use the NuttX STM32 driver per se; rather, we
+ * claim the timer and then drive it directly.
+ */
+
+#include <nuttx/config.h>
+#include <nuttx/arch.h>
+#include <nuttx/irq.h>
+
+#include <sys/types.h>
+#include <stdbool.h>
+
+#include <assert.h>
+#include <debug.h>
+#include <time.h>
+#include <queue.h>
+#include <errno.h>
+#include <string.h>
+
+#include <arch/board/board.h>
+#include <arch/board/up_hrt.h>
+
+#include "chip.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+#include "stm32_internal.h"
+#include "stm32_gpio.h"
+#include "stm32_tim.h"
+
+#ifdef CONFIG_HRT_TIMER
+
+/* HRT configuration */
+#if HRT_TIMER == 1
+# define HRT_TIMER_BASE STM32_TIM1_BASE
+# define HRT_TIMER_POWER_REG STM32_RCC_APB2ENR
+# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM1EN
+# define HRT_TIMER_VECTOR STM32_IRQ_TIM1CC
+# define HRT_TIMER_CLOCK STM32_APB2_TIM1_CLKIN
+# if CONFIG_STM32_TIM1
+# error must not set CONFIG_STM32_TIM1=y and HRT_TIMER=1
+# endif
+#elif HRT_TIMER == 2
+# define HRT_TIMER_BASE STM32_TIM2_BASE
+# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
+# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM2EN
+# define HRT_TIMER_VECTOR STM32_IRQ_TIM2
+# define HRT_TIMER_CLOCK STM32_APB1_TIM2_CLKIN
+# if CONFIG_STM32_TIM2
+# error must not set CONFIG_STM32_TIM2=y and HRT_TIMER=2
+# endif
+#elif HRT_TIMER == 3
+# define HRT_TIMER_BASE STM32_TIM3_BASE
+# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
+# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM3EN
+# define HRT_TIMER_VECTOR STM32_IRQ_TIM3
+# define HRT_TIMER_CLOCK STM32_APB1_TIM3_CLKIN
+# if CONFIG_STM32_TIM3
+# error must not set CONFIG_STM32_TIM3=y and HRT_TIMER=3
+# endif
+#elif HRT_TIMER == 4
+# define HRT_TIMER_BASE STM32_TIM4_BASE
+# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
+# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM4EN
+# define HRT_TIMER_VECTOR STM32_IRQ_TIM4
+# define HRT_TIMER_CLOCK STM32_APB1_TIM4_CLKIN
+# if CONFIG_STM32_TIM4
+# error must not set CONFIG_STM32_TIM4=y and HRT_TIMER=4
+# endif
+#elif HRT_TIMER == 5
+# define HRT_TIMER_BASE STM32_TIM5_BASE
+# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
+# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM5EN
+# define HRT_TIMER_VECTOR STM32_IRQ_TIM5
+# define HRT_TIMER_CLOCK STM32_APB1_TIM5_CLKIN
+# if CONFIG_STM32_TIM5
+# error must not set CONFIG_STM32_TIM5=y and HRT_TIMER=5
+# endif
+#elif HRT_TIMER == 8
+# define HRT_TIMER_BASE STM32_TIM8_BASE
+# define HRT_TIMER_POWER_REG STM32_RCC_APB2ENR
+# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM8EN
+# define HRT_TIMER_VECTOR STM32_IRQ_TIM8CC
+# define HRT_TIMER_CLOCK STM32_APB2_TIM8_CLKIN
+# if CONFIG_STM32_TIM8
+# error must not set CONFIG_STM32_TIM8=y and HRT_TIMER=6
+# endif
+#elif HRT_TIMER == 9
+# define HRT_TIMER_BASE STM32_TIM9_BASE
+# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
+# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM9EN
+# define HRT_TIMER_VECTOR STM32_IRQ_TIM1BRK
+# define HRT_TIMER_CLOCK STM32_APB1_TIM9_CLKIN
+# if CONFIG_STM32_TIM9
+# error must not set CONFIG_STM32_TIM9=y and HRT_TIMER=9
+# endif
+#elif HRT_TIMER == 10
+# define HRT_TIMER_BASE STM32_TIM10_BASE
+# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
+# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM10EN
+# define HRT_TIMER_VECTOR STM32_IRQ_TIM1UP
+# define HRT_TIMER_CLOCK STM32_APB1_TIM10_CLKIN
+# if CONFIG_STM32_TIM10
+# error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=10
+# endif
+#elif HRT_TIMER == 11
+# define HRT_TIMER_BASE STM32_TIM11_BASE
+# define HRT_TIMER_POWER_REG STM32_RCC_APB1ENR
+# define HRT_TIMER_POWER_BIT RCC_APB2ENR_TIM11EN
+# define HRT_TIMER_VECTOR STM32_IRQ_TIM1TRGCOM
+# define HRT_TIMER_CLOCK STM32_APB1_TIM11_CLKIN
+# if CONFIG_STM32_TIM11
+# error must not set CONFIG_STM32_TIM11=y and HRT_TIMER=11
+# endif
+#else
+# error HRT_TIMER must be set in board.h if CONFIG_HRT_TIMER=y
+#endif
+
+/*
+ * HRT clock must be a multiple of 1MHz greater than 1MHz
+ */
+#if (HRT_TIMER_CLOCK % 1000000) != 0
+# error HRT_TIMER_CLOCK must be a multiple of 1MHz
+#endif
+#if HRT_TIMER_CLOCK <= 1000000
+# error HRT_TIMER_CLOCK must be greater than 1MHz
+#endif
+
+/*
+ * Minimum/maximum deadlines.
+ *
+ * These are suitable for use with a 16-bit timer/counter clocked
+ * at 1MHz. The high-resolution timer need only guarantee that it
+ * not wrap more than once in the 50ms period for absolute time to
+ * be consistently maintained.
+ *
+ * The minimum deadline must be such that the time taken between
+ * reading a time and writing a deadline to the timer cannot
+ * result in missing the deadline.
+ */
+#define HRT_INTERVAL_MIN 50
+#define HRT_INTERVAL_MAX 50000
+
+/*
+ * Period of the free-running counter, in microseconds.
+ */
+#define HRT_COUNTER_PERIOD 65536
+
+/*
+ * Scaling factor(s) for the free-running counter; convert an input
+ * in counts to a time in microseconds.
+ */
+#define HRT_COUNTER_SCALE(_c) (_c)
+
+/*
+ * Timer register accessors
+ */
+#define REG(_reg) (*(volatile uint32_t *)(HRT_TIMER_BASE + _reg))
+
+#define rCR1 REG(STM32_GTIM_CR1_OFFSET)
+#define rCR2 REG(STM32_GTIM_CR2_OFFSET)
+#define rSMCR REG(STM32_GTIM_SMCR_OFFSET)
+#define rDIER REG(STM32_GTIM_DIER_OFFSET)
+#define rSR REG(STM32_GTIM_SR_OFFSET)
+#define rEGR REG(STM32_GTIM_EGR_OFFSET)
+#define rCCMR1 REG(STM32_GTIM_CCMR1_OFFSET)
+#define rCCMR2 REG(STM32_GTIM_CCMR2_OFFSET)
+#define rCCER REG(STM32_GTIM_CCER_OFFSET)
+#define rCNT REG(STM32_GTIM_CNT_OFFSET)
+#define rPSC REG(STM32_GTIM_PSC_OFFSET)
+#define rARR REG(STM32_GTIM_ARR_OFFSET)
+#define rCCR1 REG(STM32_GTIM_CCR1_OFFSET)
+#define rCCR2 REG(STM32_GTIM_CCR2_OFFSET)
+#define rCCR3 REG(STM32_GTIM_CCR3_OFFSET)
+#define rCCR4 REG(STM32_GTIM_CCR4_OFFSET)
+#define rDCR REG(STM32_GTIM_DCR_OFFSET)
+#define rDMAR REG(STM32_GTIM_DMAR_OFFSET)
+
+/*
+ * Specific registers and bits used by HRT sub-functions
+ */
+#if HRT_TIMER_CHANNEL == 1
+# define rCCR_HRT rCCR1 /* compare register for HRT */
+# define DIER_HRT GTIM_DIER_CC1IE /* interrupt enable for HRT */
+# define SR_INT_HRT GTIM_SR_CC1IF /* interrupt status for HRT */
+#elif HRT_TIMER_CHANNEL == 2
+# define rCCR_HRT rCCR2 /* compare register for HRT */
+# define DIER_HRT GTIM_DIER_CC2IE /* interrupt enable for HRT */
+# define SR_INT_HRT GTIM_SR_CC2IF /* interrupt status for HRT */
+#elif HRT_TIMER_CHANNEL == 3
+# define rCCR_HRT rCCR3 /* compare register for HRT */
+# define DIER_HRT GTIM_DIER_CC3IE /* interrupt enable for HRT */
+# define SR_INT_HRT GTIM_SR_CC3IF /* interrupt status for HRT */
+#elif HRT_TIMER_CHANNEL == 4
+# define rCCR_HRT rCCR4 /* compare register for HRT */
+# define DIER_HRT GTIM_DIER_CC4IE /* interrupt enable for HRT */
+# define SR_INT_HRT GTIM_SR_CC4IF /* interrupt status for HRT */
+#else
+# error HRT_TIMER_CHANNEL must be a value between 1 and 4
+#endif
+
+/*
+ * Queue of callout entries.
+ */
+static struct sq_queue_s callout_queue;
+
+/* timer-specific functions */
+static void hrt_tim_init(void);
+static int hrt_tim_isr(int irq, void *context);
+
+/* callout list manipulation */
+static void hrt_call_internal(struct hrt_call *entry,
+ hrt_abstime deadline,
+ hrt_abstime interval,
+ hrt_callout callout,
+ void *arg);
+static void hrt_call_enter(struct hrt_call *entry);
+static void hrt_call_reschedule(void);
+static void hrt_call_invoke(void);
+
+/*
+ * Specific registers and bits used by PPM sub-functions
+ */
+#ifdef CONFIG_HRT_PPM
+# if HRT_PPM_CHANNEL == 1
+# define rCCR_PPM rCCR1 /* capture register for PPM */
+# define DIER_PPM GTIM_DIER_CC1IE /* capture interrupt (non-DMA mode) */
+# define SR_INT_PPM GTIM_SR_CC1IF /* capture interrupt (non-DMA mode) */
+# define SR_OVF_PPM GTIM_SR_CC1OF /* capture overflow (non-DMA mode) */
+# define CCMR1_PPM 1 /* not on TI1/TI2 */
+# define CCMR2_PPM 0 /* on TI3, not on TI4 */
+# define CCER_PPM (GTIM_CCER_CC1E | GTIM_CCER_CC1P | GTIM_CCER_CC1NP) /* CC1, both edges */
+# elif HRT_PPM_CHANNEL == 2
+# define rCCR_PPM rCCR2 /* capture register for PPM */
+# define DIER_PPM GTIM_DIER_CC2IE /* capture interrupt (non-DMA mode) */
+# define SR_INT_PPM GTIM_SR_CC2IF /* capture interrupt (non-DMA mode) */
+# define SR_OVF_PPM GTIM_SR_CC2OF /* capture overflow (non-DMA mode) */
+# define CCMR1_PPM 2 /* not on TI1/TI2 */
+# define CCMR2_PPM 0 /* on TI3, not on TI4 */
+# define CCER_PPM (GTIM_CCER_CC2E | GTIM_CCER_CC2P | GTIM_CCER_CC2NP) /* CC2, both edges */
+# elif HRT_PPM_CHANNEL == 3
+# define rCCR_PPM rCCR3 /* capture register for PPM */
+# define DIER_PPM GTIM_DIER_CC3IE /* capture interrupt (non-DMA mode) */
+# define SR_INT_PPM GTIM_SR_CC3IF /* capture interrupt (non-DMA mode) */
+# define SR_OVF_PPM GTIM_SR_CC3OF /* capture overflow (non-DMA mode) */
+# define CCMR1_PPM 0 /* not on TI1/TI2 */
+# define CCMR2_PPM 1 /* on TI3, not on TI4 */
+# define CCER_PPM (GTIM_CCER_CC3E | GTIM_CCER_CC3P | GTIM_CCER_CC3NP) /* CC3, both edges */
+# elif HRT_PPM_CHANNEL == 4
+# define rCCR_PPM rCCR4 /* capture register for PPM */
+# define DIER_PPM GTIM_DIER_CC4IE /* capture interrupt (non-DMA mode) */
+# define SR_INT_PPM GTIM_SR_CC4IF /* capture interrupt (non-DMA mode) */
+# define SR_OVF_PPM GTIM_SR_CC4OF /* capture overflow (non-DMA mode) */
+# define CCMR1_PPM 0 /* not on TI1/TI2 */
+# define CCMR2_PPM 2 /* on TI3, not on TI4 */
+# define CCER_PPM (GTIM_CCER_CC4E | GTIM_CCER_CC4P | GTIM_CCER_CC4NP) /* CC4, both edges */
+# else
+# error HRT_PPM_CHANNEL must be a value between 1 and 4 if CONFIG_HRT_PPM is set
+# endif
+
+/*
+ * PPM decoder tuning parameters
+ */
+# define PPM_MAX_PULSE_WIDTH 500 /* maximum width of a pulse */
+# define PPM_MIN_CHANNEL_VALUE 750 /* shortest valid channel signal */
+# define PPM_MAX_CHANNEL_VALUE 2400 /* longest valid channel signal */
+# define PPM_MIN_START 5000 /* shortest valid start gap */
+
+/* decoded PPM buffer */
+#define PPM_MAX_CHANNELS 12
+uint16_t ppm_buffer[PPM_MAX_CHANNELS];
+unsigned ppm_decoded_channels;
+
+/* PPM edge history */
+uint16_t ppm_edge_history[32];
+unsigned ppm_edge_next;
+
+/* PPM pulse history */
+uint16_t ppm_pulse_history[32];
+unsigned ppm_pulse_next;
+
+static uint16_t ppm_temp_buffer[PPM_MAX_CHANNELS];
+
+/* PPM decoder state machine */
+struct {
+ uint16_t last_edge; /* last capture time */
+ uint16_t last_mark; /* last significant edge */
+ unsigned next_channel;
+ enum {
+ UNSYNCH = 0,
+ ARM,
+ ACTIVE,
+ INACTIVE
+ } phase;
+} ppm;
+
+static void hrt_ppm_decode(uint32_t status);
+
+#else
+/* disable the PPM configuration */
+# define rCCR_PPM 0
+# define DIER_PPM 0
+# define SR_INT_PPM 0
+# define SR_OVF_PPM 0
+# define CCMR1_PPM 0
+# define CCMR2_PPM 0
+# define CCER_PPM 0
+#endif /* CONFIG_HRT_PPM */
+
+/*
+ * Initialise the timer we are going to use.
+ *
+ * We expect that we'll own one of the reduced-function STM32 general
+ * timers, and that we can use channel 1 in compare mode.
+ */
+static void
+hrt_tim_init(void)
+{
+ /* clock/power on our timer */
+ modifyreg32(HRT_TIMER_POWER_REG, 0, HRT_TIMER_POWER_BIT);
+
+ /* claim our interrupt vector */
+ irq_attach(HRT_TIMER_VECTOR, hrt_tim_isr);
+
+ /* disable and configure the timer */
+ rCR1 = 0;
+ rCR2 = 0;
+ rSMCR = 0;
+ rDIER = DIER_HRT | DIER_PPM;
+ rCCER = 0; /* unlock CCMR* registers */
+ rCCMR1 = CCMR1_PPM;
+ rCCMR2 = CCMR2_PPM;
+ rCCER = CCER_PPM;
+ rDCR = 0;
+
+ /* configure the timer to free-run at 1MHz */
+ rPSC = (HRT_TIMER_CLOCK / 1000000) - 1; /* this really only works for whole-MHz clocks */
+
+ /* run the full span of the counter */
+ rARR = 0xffff;
+
+ /* set an initial capture a little ways off */
+ rCCR_HRT = 1000;
+
+ /* generate an update event; reloads the counter, all registers */
+ rEGR = GTIM_EGR_UG;
+
+ /* enable the timer */
+ rCR1 = GTIM_CR1_CEN;
+
+ /* enable interrupts */
+ up_enable_irq(HRT_TIMER_VECTOR);
+}
+
+#ifdef CONFIG_HRT_PPM
+/*
+ * Handle the PPM decoder state machine.
+ */
+static void
+hrt_ppm_decode(uint32_t status)
+{
+ uint16_t count = rCCR_PPM;
+ uint16_t width;
+ uint16_t interval;
+ unsigned i;
+
+ /* if we missed an edge, we have to give up */
+ if (status & SR_OVF_PPM)
+ goto error;
+
+ /* how long since the last edge? */
+ width = count - ppm.last_edge;
+ ppm.last_edge = count;
+
+ ppm_edge_history[ppm_edge_next++] = width;
+ if (ppm_edge_next >= 32)
+ ppm_edge_next = 0;
+
+ /*
+ * if this looks like a start pulse, then push the last set of values
+ * and reset the state machine
+ */
+ if (width >= PPM_MIN_START) {
+
+ /* export the last set of samples if we got something sensible */
+ if (ppm.next_channel > 4) {
+ for (i = 0; i < ppm.next_channel && i < PPM_MAX_CHANNELS; i++)
+ ppm_buffer[i] = ppm_temp_buffer[i];
+ ppm_decoded_channels = i;
+ }
+
+ /* reset for the next frame */
+ ppm.next_channel = 0;
+
+ /* next edge is the reference for the first channel */
+ ppm.phase = ARM;
+
+ return;
+ }
+
+ switch (ppm.phase) {
+ case UNSYNCH:
+ /* we are waiting for a start pulse - nothing useful to do here */
+ return;
+
+ case ARM:
+ /* we expect a pulse giving us the first mark */
+ if (width > PPM_MAX_PULSE_WIDTH)
+ goto error; /* pulse was too long */
+
+ /* record the mark timing, expect an inactive edge */
+ ppm.last_mark = count;
+ ppm.phase = INACTIVE;
+ return;
+
+ case INACTIVE:
+ /* this edge is not interesting, but now we are ready for the next mark */
+ ppm.phase = ACTIVE;
+ return;
+
+ case ACTIVE:
+ /* determine the interval from the last mark */
+ interval = count - ppm.last_mark;
+ ppm.last_mark = count;
+
+ ppm_pulse_history[ppm_pulse_next++] = interval;
+ if (ppm_pulse_next >= 32)
+ ppm_pulse_next = 0;
+
+ /* if the mark-mark timing is out of bounds, abandon the frame */
+ if ((interval < PPM_MIN_CHANNEL_VALUE) || (interval > PPM_MAX_CHANNEL_VALUE))
+ goto error;
+
+ /* if we have room to store the value, do so */
+ if (ppm.next_channel < PPM_MAX_CHANNELS)
+ ppm_temp_buffer[ppm.next_channel++] = interval;
+
+ ppm.phase = INACTIVE;
+ return;
+
+ }
+
+ /* the state machine is corrupted; reset it */
+
+error:
+ /* we don't like the state of the decoder, reset it and try again */
+ ppm.phase = UNSYNCH;
+}
+#endif /* CONFIG_HRT_PPM */
+
+/*
+ * Handle the compare interupt by calling the callout dispatcher
+ * and then re-scheduling the next deadline.
+ */
+static int
+hrt_tim_isr(int irq, void *context)
+{
+ uint32_t status;
+
+ /* copy interrupt status */
+ status = rSR;
+
+ /* ack the interrupts we just read */
+ rSR = ~status;
+
+#ifdef CONFIG_HRT_PPM
+ /* was this a PPM edge? */
+ if (status & (SR_INT_PPM | SR_OVF_PPM))
+ hrt_ppm_decode(status);
+#endif
+
+ /* was this a timer tick? */
+ if (status & SR_INT_HRT) {
+ /* run any callouts that have met their deadline */
+ hrt_call_invoke();
+
+ /* and schedule the next interrupt */
+ hrt_call_reschedule();
+ }
+
+ return OK;
+}
+
+/*
+ * Fetch a never-wrapping absolute time value in microseconds from
+ * some arbitrary epoch shortly after system start.
+ */
+hrt_abstime
+hrt_absolute_time(void)
+{
+ hrt_abstime abstime;
+ uint32_t count;
+ uint32_t flags;
+
+ /*
+ * Counter state. Marked volatile as they may change
+ * inside this routine but outside the irqsave/restore
+ * pair. Discourage the compiler from moving loads/stores
+ * to these outside of the protected range.
+ */
+ static volatile hrt_abstime base_time;
+ static volatile uint32_t last_count;
+
+ /* prevent re-entry */
+ flags = irqsave();
+
+ /* get the current counter value */
+ count = rCNT;
+
+ /*
+ * Determine whether the counter has wrapped since the
+ * last time we're called.
+ *
+ * This simple test is sufficient due to the guarantee that
+ * we are always called at least once per counter period.
+ */
+ if (count < last_count)
+ base_time += HRT_COUNTER_PERIOD;
+
+ /* save the count for next time */
+ last_count = count;
+
+ /* compute the current time */
+ abstime = HRT_COUNTER_SCALE(base_time + count);
+
+ irqrestore(flags);
+
+ return abstime;
+}
+
+/*
+ * Convert a timespec to absolute time
+ */
+hrt_abstime
+ts_to_abstime(struct timespec *ts)
+{
+ hrt_abstime result;
+
+ result = (hrt_abstime)(ts->tv_sec) * 1000000;
+ result += ts->tv_nsec / 1000;
+
+ return result;
+}
+
+/*
+ * Convert absolute time to a timespec.
+ */
+void
+abstime_to_ts(struct timespec *ts, hrt_abstime abstime)
+{
+ ts->tv_sec = abstime / 1000000;
+ abstime -= ts->tv_sec * 1000000;
+ ts->tv_nsec = abstime * 1000;
+}
+
+/*
+ * Initalise the high-resolution timing module.
+ */
+void
+hrt_init(void)
+{
+ sq_init(&callout_queue);
+ hrt_tim_init();
+
+#ifdef CONFIG_HRT_PPM
+ /* configure the PPM input pin */
+ stm32_configgpio(GPIO_PPM_IN);
+#endif
+}
+
+/*
+ * Call callout(arg) after interval has elapsed.
+ */
+void
+hrt_call_after(struct hrt_call *entry, hrt_abstime delay, hrt_callout callout, void *arg)
+{
+ hrt_call_internal(entry,
+ hrt_absolute_time() + delay,
+ 0,
+ callout,
+ arg);
+}
+
+/*
+ * Call callout(arg) at calltime.
+ */
+void
+hrt_call_at(struct hrt_call *entry, hrt_abstime calltime, hrt_callout callout, void *arg)
+{
+ hrt_call_internal(entry, calltime, 0, callout, arg);
+}
+
+/*
+ * Call callout(arg) every period.
+ */
+void
+hrt_call_every(struct hrt_call *entry, hrt_abstime delay, hrt_abstime interval, hrt_callout callout, void *arg)
+{
+ hrt_call_internal(entry,
+ hrt_absolute_time() + delay,
+ interval,
+ callout,
+ arg);
+}
+
+static void
+hrt_call_internal(struct hrt_call *entry, hrt_abstime deadline, hrt_abstime interval, hrt_callout callout, void *arg)
+{
+ irqstate_t flags = irqsave();
+
+ /* if the entry is currently queued, remove it */
+ if (entry->deadline != 0)
+ sq_rem(&entry->link, &callout_queue);
+
+ entry->deadline = deadline;
+ entry->period = interval;
+ entry->callout = callout;
+ entry->arg = arg;
+
+ hrt_call_enter(entry);
+
+ irqrestore(flags);
+}
+
+/*
+ * If this returns true, the call has been invoked and removed from the callout list.
+ *
+ * Always returns false for repeating callouts.
+ */
+bool
+hrt_called(struct hrt_call *entry)
+{
+ return (entry->deadline == 0);
+}
+
+/*
+ * Remove the entry from the callout list.
+ */
+void
+hrt_cancel(struct hrt_call *entry)
+{
+ irqstate_t flags = irqsave();
+
+ sq_rem(&entry->link, &callout_queue);
+ entry->deadline = 0;
+
+ /* if this is a periodic call being removed by the callout, prevent it from
+ * being re-entered when the callout returns.
+ */
+ entry->period = 0;
+
+ irqrestore(flags);
+}
+
+static void
+hrt_call_enter(struct hrt_call *entry)
+{
+ struct hrt_call *call, *next;
+
+ call = (struct hrt_call *)sq_peek(&callout_queue);
+
+ if ((call == NULL) || (entry->deadline < call->deadline)) {
+ sq_addfirst(&entry->link, &callout_queue);
+ //lldbg("call enter at head, reschedule\n");
+ /* we changed the next deadline, reschedule the timer event */
+ hrt_call_reschedule();
+ } else {
+ do {
+ next = (struct hrt_call *)sq_next(&call->link);
+ if ((next == NULL) || (entry->deadline < next->deadline)) {
+ //lldbg("call enter after head\n");
+ sq_addafter(&call->link, &entry->link, &callout_queue);
+ break;
+ }
+ } while ((call = next) != NULL);
+ }
+
+ //lldbg("scheduled\n");
+}
+
+static void
+hrt_call_invoke(void)
+{
+ struct hrt_call *call;
+ hrt_abstime deadline;
+
+ while (true) {
+ /* get the current time */
+ hrt_abstime now = hrt_absolute_time();
+
+ call = (struct hrt_call *)sq_peek(&callout_queue);
+ if (call == NULL)
+ break;
+ if (call->deadline > now)
+ break;
+
+ sq_rem(&call->link, &callout_queue);
+ //lldbg("call pop\n");
+
+ /* save the intended deadline for periodic calls */
+ deadline = call->deadline;
+
+ /* zero the deadline, as the call has occurred */
+ call->deadline = 0;
+
+ /* invoke the callout (if there is one) */
+ if (call->callout) {
+ //lldbg("call %p: %p(%p)\n", call, call->callout, call->arg);
+ call->callout(call->arg);
+ }
+
+ /* if the callout has a non-zero period, it has to be re-entered */
+ if (call->period != 0) {
+ call->deadline = deadline + call->period;
+ hrt_call_enter(call);
+ }
+ }
+}
+
+/*
+ * Reschedule the next timer interrupt.
+ *
+ * This routine must be called with interrupts disabled.
+ */
+static void
+hrt_call_reschedule()
+{
+ hrt_abstime now = hrt_absolute_time();
+ struct hrt_call *next = (struct hrt_call *)sq_peek(&callout_queue);
+ hrt_abstime deadline = now + HRT_INTERVAL_MAX;
+
+ /*
+ * Determine what the next deadline will be.
+ *
+ * Note that we ensure that this will be within the counter
+ * period, so that when we truncate all but the low 16 bits
+ * the next time the compare matches it will be the deadline
+ * we want.
+ *
+ * It is important for accurate timekeeping that the compare
+ * interrupt fires sufficiently often that the base_time update in
+ * hrt_absolute_time runs at least once per timer period.
+ */
+ if (next != NULL) {
+ //lldbg("entry in queue\n");
+ if (next->deadline <= (now + HRT_INTERVAL_MIN)) {
+ //lldbg("pre-expired\n");
+ /* set a minimal deadline so that we call ASAP */
+ deadline = now + HRT_INTERVAL_MIN;
+ } else if (next->deadline < deadline) {
+ //lldbg("due soon\n");
+ deadline = next->deadline;
+ }
+ }
+ //lldbg("schedule for %u at %u\n", (unsigned)(deadline & 0xffffffff), (unsigned)(now & 0xffffffff));
+
+ /* set the new compare value */
+ rCCR_HRT = deadline & 0xffff;
+}
+
+#endif /* CONFIG_HRT_TIMER */
diff --git a/nuttx/configs/px4fmu/src/up_leds.c b/nuttx/configs/px4fmu/src/up_leds.c
new file mode 100644
index 000000000..f7b76aa58
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_leds.c
@@ -0,0 +1,127 @@
+/****************************************************************************
+ * configs/px4fmu/src/up_leds.c
+ * arch/arm/src/board/up_leds.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+#include "up_internal.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* Enables debug output from this file (needs CONFIG_DEBUG with
+ * CONFIG_DEBUG_VERBOSE too)
+ */
+
+#undef LED_DEBUG /* Define to enable debug */
+
+#ifdef LED_DEBUG
+# define leddbg lldbg
+# define ledvdbg llvdbg
+#else
+# define leddbg(x...)
+# define ledvdbg(x...)
+#endif
+
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_ledinit
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_LEDS
+void up_ledinit(void)
+{
+ /* Configure LED1-2 GPIOs for output */
+
+ stm32_configgpio(GPIO_LED1);
+ stm32_configgpio(GPIO_LED2);
+}
+
+/****************************************************************************
+ * Name: up_ledon
+ ****************************************************************************/
+
+void up_ledon(int led)
+{
+ if (led == 0)
+ {
+ /* Pull down to switch on */
+ stm32_gpiowrite(GPIO_LED1, false);
+ }
+ if (led == 1)
+ {
+ /* Pull down to switch on */
+ stm32_gpiowrite(GPIO_LED2, false);
+ }
+}
+
+/****************************************************************************
+ * Name: up_ledoff
+ ****************************************************************************/
+
+void up_ledoff(int led)
+{
+ if (led == 0)
+ {
+ /* Pull up to switch off */
+ stm32_gpiowrite(GPIO_LED1, true);
+ }
+ if (led == 1)
+ {
+ /* Pull up to switch off */
+ stm32_gpiowrite(GPIO_LED2, true);
+ }
+}
+
+#endif /* CONFIG_ARCH_LEDS */
diff --git a/nuttx/configs/px4fmu/src/up_nsh.c b/nuttx/configs/px4fmu/src/up_nsh.c
new file mode 100644
index 000000000..6e092e3b4
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_nsh.c
@@ -0,0 +1,392 @@
+/****************************************************************************
+ * config/stm3210e_eval/src/up_nsh.c
+ * arch/arm/src/board/up_nsh.c
+ *
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/spi.h>
+#include <nuttx/i2c.h>
+#include <nuttx/mmcsd.h>
+#include <nuttx/analog/adc.h>
+#include <nuttx/arch.h>
+
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+#include "stm32_uart.h"
+
+#include <arch/board/up_hrt.h>
+#include <arch/board/up_cpuload.h>
+#include <arch/board/drv_tone_alarm.h>
+#include <arch/board/up_adc.h>
+#include <arch/board/board.h>
+#include <arch/board/drv_bma180.h>
+#include <arch/board/drv_l3gd20.h>
+#include <arch/board/drv_hmc5883l.h>
+#include <arch/board/drv_mpu6000.h>
+#include <arch/board/drv_ms5611.h>
+#include <arch/board/drv_eeprom.h>
+#include <arch/board/drv_led.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lib_lowprintf(__VA_ARGS__)
+# else
+# define message(...) printf(__VA_ARGS__)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lib_lowprintf
+# else
+# define message printf
+# endif
+#endif
+
+/****************************************************************************
+ * Protected Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: multiport_setup
+ *
+ * Description:
+ * Perform setup of the PX4FMU's multi function ports
+ *
+ ****************************************************************************/
+int multiport_setup(void)
+{
+ int result = OK;
+
+ return result;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+static struct spi_dev_s *spi1;
+static struct spi_dev_s *spi3;
+static struct i2c_dev_s *i2c1;
+static struct i2c_dev_s *i2c2;
+static struct i2c_dev_s *i2c3;
+
+#include <math.h>
+
+#ifdef __cplusplus
+int matherr(struct __exception *e) {
+ return 1;
+}
+#else
+int matherr(struct exception *e) {
+ return 1;
+}
+#endif
+
+int nsh_archinitialize(void)
+{
+ int result;
+
+ /* INIT 1 Lowest level NuttX initialization has been done at this point, LEDs and UARTs are configured */
+
+ /* INIT 2 Configuring PX4 low-level peripherals, these will be always needed */
+
+ /* configure the high-resolution time/callout interface */
+#ifdef CONFIG_HRT_TIMER
+ hrt_init();
+#endif
+
+ /* configure CPU load estimation */
+ #ifdef CONFIG_SCHED_INSTRUMENTATION
+ cpuload_initialize_once();
+ #endif
+
+ /* set up the serial DMA polling */
+#ifdef SERIAL_HAVE_DMA
+ {
+ static struct hrt_call serial_dma_call;
+ struct timespec ts;
+
+ /*
+ * Poll at 1ms intervals for received bytes that have not triggered
+ * a DMA event.
+ */
+ ts.tv_sec = 0;
+ ts.tv_nsec = 1000000;
+
+ hrt_call_every(&serial_dma_call,
+ ts_to_abstime(&ts),
+ ts_to_abstime(&ts),
+ (hrt_callout)stm32_serial_dma_poll,
+ NULL);
+ }
+#endif
+
+ message("\r\n");
+
+ up_ledoff(LED_BLUE);
+ up_ledoff(LED_AMBER);
+
+ up_ledon(LED_BLUE);
+
+ /* Configure user-space led driver */
+ px4fmu_led_init();
+
+ /* Configure SPI-based devices */
+
+ spi1 = up_spiinitialize(1);
+ if (!spi1)
+ {
+ message("[boot] FAILED to initialize SPI port 1\r\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+
+ // Setup 10 MHz clock (maximum rate the BMA180 can sustain)
+ SPI_SETFREQUENCY(spi1, 10000000);
+ SPI_SETBITS(spi1, 8);
+ SPI_SETMODE(spi1, SPIDEV_MODE3);
+ SPI_SELECT(spi1, PX4_SPIDEV_GYRO, false);
+ SPI_SELECT(spi1, PX4_SPIDEV_ACCEL, false);
+ SPI_SELECT(spi1, PX4_SPIDEV_MPU, false);
+ up_udelay(20);
+
+ message("[boot] Successfully initialized SPI port 1\r\n");
+
+ /* initialize SPI peripherals redundantly */
+ int gyro_attempts = 0;
+ int gyro_fail = 0;
+
+ while (gyro_attempts < 5)
+ {
+ gyro_fail = l3gd20_attach(spi1, PX4_SPIDEV_GYRO);
+ gyro_attempts++;
+ if (gyro_fail == 0) break;
+ up_udelay(1000);
+ }
+
+ if (gyro_fail) message("[boot] FAILED to attach L3GD20 gyro\r\n");
+
+ int acc_attempts = 0;
+ int acc_fail = 0;
+
+ while (acc_attempts < 5)
+ {
+ acc_fail = bma180_attach(spi1, PX4_SPIDEV_ACCEL);
+ acc_attempts++;
+ if (acc_fail == 0) break;
+ up_udelay(1000);
+ }
+
+ if (acc_fail) message("[boot] FAILED to attach BMA180 accelerometer\r\n");
+
+ int mpu_attempts = 0;
+ int mpu_fail = 0;
+
+ while (mpu_attempts < 1)
+ {
+ mpu_fail = mpu6000_attach(spi1, PX4_SPIDEV_MPU);
+ mpu_attempts++;
+ if (mpu_fail == 0) break;
+ up_udelay(200);
+ }
+
+ if (mpu_fail) message("[boot] FAILED to attach MPU 6000 gyro/acc\r\n");
+
+ /* initialize I2C2 bus */
+
+ i2c2 = up_i2cinitialize(2);
+ if (!i2c2) {
+ message("[boot] FAILED to initialize I2C bus 2\r\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+
+ /* set I2C2 speed */
+ I2C_SETFREQUENCY(i2c2, 400000);
+
+
+ i2c3 = up_i2cinitialize(3);
+ if (!i2c3) {
+ message("[boot] FAILED to initialize I2C bus 3\r\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+
+ /* set I2C3 speed */
+ I2C_SETFREQUENCY(i2c3, 400000);
+
+ int mag_attempts = 0;
+ int mag_fail = 0;
+
+ while (mag_attempts < 5)
+ {
+ mag_fail = hmc5883l_attach(i2c2);
+ mag_attempts++;
+ if (mag_fail == 0) break;
+ up_udelay(1000);
+ }
+
+ if (mag_fail) message("[boot] FAILED to attach HMC5883L magnetometer\r\n");
+
+ int baro_attempts = 0;
+ int baro_fail = 0;
+ while (baro_attempts < 5)
+ {
+ baro_fail = ms5611_attach(i2c2);
+ baro_attempts++;
+ if (baro_fail == 0) break;
+ up_udelay(1000);
+ }
+
+ if (baro_fail) message("[boot] FAILED to attach MS5611 baro at addr #1 or #2 (0x76 or 0x77)\r\n");
+
+ /* try to attach, don't fail if device is not responding */
+ (void)eeprom_attach(i2c3, FMU_BASEBOARD_EEPROM_ADDRESS,
+ FMU_BASEBOARD_EEPROM_TOTAL_SIZE_BYTES,
+ FMU_BASEBOARD_EEPROM_PAGE_SIZE_BYTES,
+ FMU_BASEBOARD_EEPROM_PAGE_WRITE_TIME_US, "/dev/baseboard_eeprom", 1);
+
+ int eeprom_attempts = 0;
+ int eeprom_fail;
+ while (eeprom_attempts < 5)
+ {
+ /* try to attach, fail if device does not respond */
+ eeprom_fail = eeprom_attach(i2c2, FMU_ONBOARD_EEPROM_ADDRESS,
+ FMU_ONBOARD_EEPROM_TOTAL_SIZE_BYTES,
+ FMU_ONBOARD_EEPROM_PAGE_SIZE_BYTES,
+ FMU_ONBOARD_EEPROM_PAGE_WRITE_TIME_US, "/dev/eeprom", 1);
+ eeprom_attempts++;
+ if (eeprom_fail == OK) break;
+ up_udelay(1000);
+ }
+
+ if (eeprom_fail) message("[boot] FAILED to attach FMU EEPROM\r\n");
+
+ /* Report back sensor status */
+ if (acc_fail || gyro_fail || mag_fail || baro_fail || eeprom_fail)
+ {
+ up_ledon(LED_AMBER);
+ }
+
+#if defined(CONFIG_STM32_SPI3)
+ /* Get the SPI port */
+
+ message("[boot] Initializing SPI port 3\r\n");
+ spi3 = up_spiinitialize(3);
+ if (!spi3)
+ {
+ message("[boot] FAILED to initialize SPI port 3\r\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+ message("[boot] Successfully initialized SPI port 3\r\n");
+
+ /* Now bind the SPI interface to the MMCSD driver */
+ result = mmcsd_spislotinitialize(CONFIG_NSH_MMCSDMINOR, CONFIG_NSH_MMCSDSLOTNO, spi3);
+ if (result != OK)
+ {
+ message("[boot] FAILED to bind SPI port 3 to the MMCSD driver\r\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+ message("[boot] Successfully bound SPI port 3 to the MMCSD driver\r\n");
+#endif /* SPI3 */
+
+ /* initialize I2C1 bus */
+
+ i2c1 = up_i2cinitialize(1);
+ if (!i2c1) {
+ message("[boot] FAILED to initialize I2C bus 1\r\n");
+ up_ledon(LED_AMBER);
+ return -ENODEV;
+ }
+
+ /* set I2C1 speed */
+ I2C_SETFREQUENCY(i2c1, 400000);
+
+ /* INIT 3: MULTIPORT-DEPENDENT INITIALIZATION */
+
+ /* Get board information if available */
+
+ /* Initialize the user GPIOs */
+ px4fmu_gpio_init();
+
+#ifdef CONFIG_ADC
+ int adc_state = adc_devinit();
+ if (adc_state != OK)
+ {
+ /* Try again */
+ adc_state = adc_devinit();
+ if (adc_state != OK)
+ {
+ /* Give up */
+ message("[boot] FAILED adc_devinit: %d\r\n", adc_state);
+ return -ENODEV;
+ }
+ }
+#endif
+
+ /* configure the tone generator */
+#ifdef CONFIG_TONE_ALARM
+ tone_alarm_init();
+#endif
+
+ return OK;
+}
diff --git a/nuttx/configs/px4fmu/src/up_pwm_servo.c b/nuttx/configs/px4fmu/src/up_pwm_servo.c
new file mode 100644
index 000000000..05daf1e97
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_pwm_servo.c
@@ -0,0 +1,344 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/*
+ * Servo driver supporting PWM servos connected to STM32 timer blocks.
+ *
+ * Works with any of the 'generic' or 'advanced' STM32 timers that
+ * have output pins, does not require an interrupt.
+ */
+
+#include <nuttx/config.h>
+#include <nuttx/arch.h>
+#include <nuttx/irq.h>
+
+#include <sys/types.h>
+#include <stdbool.h>
+
+#include <assert.h>
+#include <debug.h>
+#include <time.h>
+#include <queue.h>
+#include <errno.h>
+#include <string.h>
+#include <stdio.h>
+
+#include <arch/board/board.h>
+#include <arch/board/up_pwm_servo.h>
+
+#include "chip.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+#include "stm32_internal.h"
+#include "stm32_gpio.h"
+#include "stm32_tim.h"
+
+/* configuration limits */
+#define PWM_SERVO_MAX_TIMERS 2
+#define PWM_SERVO_MAX_CHANNELS 8
+
+/* default rate (in Hz) of PWM updates */
+static uint32_t pwm_update_rate = 50;
+
+/*
+ * Servo configuration for all of the pins that can be used as
+ * PWM outputs on FMU.
+ */
+
+/* array of timers dedicated to PWM servo use */
+static const struct pwm_servo_timer {
+ uint32_t base;
+ uint32_t clock_register;
+ uint32_t clock_bit;
+ uint32_t clock_freq;
+} pwm_timers[] = {
+ {
+ .base = STM32_TIM2_BASE,
+ .clock_register = STM32_RCC_APB1ENR,
+ .clock_bit = RCC_APB1ENR_TIM2EN,
+ .clock_freq = STM32_APB1_TIM2_CLKIN
+ }
+};
+
+/* array of channels in logical order */
+static const struct pwm_servo_channel {
+ uint32_t gpio;
+ uint8_t timer_index;
+ uint8_t timer_channel;
+ servo_position_t default_value;
+} pwm_channels[] = {
+ {
+ .gpio = GPIO_TIM2_CH1OUT,
+ .timer_index = 0,
+ .timer_channel = 1,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM2_CH2OUT,
+ .timer_index = 0,
+ .timer_channel = 2,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM2_CH3OUT,
+ .timer_index = 0,
+ .timer_channel = 3,
+ .default_value = 1000,
+ },
+ {
+ .gpio = GPIO_TIM2_CH4OUT,
+ .timer_index = 0,
+ .timer_channel = 4,
+ .default_value = 1000,
+ }
+};
+
+
+#define REG(_tmr, _reg) (*(volatile uint32_t *)(pwm_timers[_tmr].base + _reg))
+
+#define rCR1(_tmr) REG(_tmr, STM32_GTIM_CR1_OFFSET)
+#define rCR2(_tmr) REG(_tmr, STM32_GTIM_CR2_OFFSET)
+#define rSMCR(_tmr) REG(_tmr, STM32_GTIM_SMCR_OFFSET)
+#define rDIER(_tmr) REG(_tmr, STM32_GTIM_DIER_OFFSET)
+#define rSR(_tmr) REG(_tmr, STM32_GTIM_SR_OFFSET)
+#define rEGR(_tmr) REG(_tmr, STM32_GTIM_EGR_OFFSET)
+#define rCCMR1(_tmr) REG(_tmr, STM32_GTIM_CCMR1_OFFSET)
+#define rCCMR2(_tmr) REG(_tmr, STM32_GTIM_CCMR2_OFFSET)
+#define rCCER(_tmr) REG(_tmr, STM32_GTIM_CCER_OFFSET)
+#define rCNT(_tmr) REG(_tmr, STM32_GTIM_CNT_OFFSET)
+#define rPSC(_tmr) REG(_tmr, STM32_GTIM_PSC_OFFSET)
+#define rARR(_tmr) REG(_tmr, STM32_GTIM_ARR_OFFSET)
+#define rCCR1(_tmr) REG(_tmr, STM32_GTIM_CCR1_OFFSET)
+#define rCCR2(_tmr) REG(_tmr, STM32_GTIM_CCR2_OFFSET)
+#define rCCR3(_tmr) REG(_tmr, STM32_GTIM_CCR3_OFFSET)
+#define rCCR4(_tmr) REG(_tmr, STM32_GTIM_CCR4_OFFSET)
+#define rDCR(_tmr) REG(_tmr, STM32_GTIM_DCR_OFFSET)
+#define rDMAR(_tmr) REG(_tmr, STM32_GTIM_DMAR_OFFSET)
+
+static void
+pwm_timer_init(unsigned timer)
+{
+ /* enable the timer clock before we try to talk to it */
+ modifyreg32(pwm_timers[timer].clock_register, 0, pwm_timers[timer].clock_bit);
+
+ /* disable and configure the timer */
+ rCR1(timer) = 0;
+ rCR2(timer) = 0;
+ rSMCR(timer) = 0;
+ rDIER(timer) = 0;
+ rCCER(timer) = 0;
+ rCCMR1(timer) = 0;
+ rCCMR2(timer) = 0;
+ rCCER(timer) = 0;
+ rDCR(timer) = 0;
+
+ /* configure the timer to free-run at 1MHz */
+ rPSC(timer) = pwm_timers[timer].clock_freq / 1000000;
+
+ /* and update at the desired rate */
+ rARR(timer) = 1000000 / pwm_update_rate;
+
+ /* generate an update event; reloads the counter and all registers */
+ rEGR(timer) = GTIM_EGR_UG;
+
+ /* note that the timer is left disabled - arming is performed separately */
+}
+
+static void
+pwm_timer_set_rate(unsigned timer, unsigned rate)
+{
+ /* configure the timer to update at the desired rate */
+ rARR(timer) = 1000000 / pwm_update_rate;
+
+ /* generate an update event; reloads the counter and all registers */
+ rEGR(timer) = GTIM_EGR_UG;
+}
+
+static void
+pwm_channel_init(unsigned channel)
+{
+ unsigned timer = pwm_channels[channel].timer_index;
+
+ /* configure the GPIO first */
+ stm32_configgpio(pwm_channels[channel].gpio);
+
+ /* configure the channel */
+ switch (pwm_channels[channel].timer_channel) {
+ case 1:
+ rCCMR1(timer) |= (6 << 4);
+ rCCR1(timer) = pwm_channels[channel].default_value;
+ rCCER(timer) |= (1 << 0);
+ break;
+ case 2:
+ rCCMR1(timer) |= (6 << 12);
+ rCCR2(timer) = pwm_channels[channel].default_value;
+ rCCER(timer) |= (1 << 4);
+ break;
+ case 3:
+ rCCMR2(timer) |= (6 << 4);
+ rCCR3(timer) = pwm_channels[channel].default_value;
+ rCCER(timer) |= (1 << 8);
+ break;
+ case 4:
+ rCCMR2(timer) |= (6 << 12);
+ rCCR4(timer) = pwm_channels[channel].default_value;
+ rCCER(timer) |= (1 << 12);
+ break;
+ }
+}
+
+int
+up_pwm_servo_set(unsigned channel, servo_position_t value)
+{
+ if (channel >= PWM_SERVO_MAX_CHANNELS) {
+ lldbg("pwm_channel_set: bogus channel %u\n", channel);
+ return -1;
+ }
+
+ unsigned timer = pwm_channels[channel].timer_index;
+
+ /* test timer for validity */
+ if ((pwm_timers[timer].base == 0) ||
+ (pwm_channels[channel].gpio == 0))
+ return -1;
+
+ /* configure the channel */
+ switch (pwm_channels[channel].timer_channel) {
+ case 1:
+ rCCR1(timer) = value;
+ break;
+ case 2:
+ rCCR2(timer) = value;
+ break;
+ case 3:
+ rCCR3(timer) = value;
+ break;
+ case 4:
+ rCCR4(timer) = value;
+ break;
+ default:
+ return -1;
+ }
+ return 0;
+}
+
+servo_position_t
+up_pwm_servo_get(unsigned channel)
+{
+ if (channel >= PWM_SERVO_MAX_CHANNELS) {
+ lldbg("pwm_channel_get: bogus channel %u\n", channel);
+ return 0;
+ }
+
+ unsigned timer = pwm_channels[channel].timer_index;
+ servo_position_t value = 0;
+
+ /* test timer for validity */
+ if ((pwm_timers[timer].base == 0) ||
+ (pwm_channels[channel].gpio == 0))
+ return 0;
+
+ /* configure the channel */
+ switch (pwm_channels[channel].timer_channel) {
+ case 1:
+ value = rCCR1(timer);
+ break;
+ case 2:
+ value = rCCR2(timer);
+ break;
+ case 3:
+ value = rCCR3(timer);
+ break;
+ case 4:
+ value = rCCR4(timer);
+ break;
+ }
+ return value;
+}
+
+int
+up_pwm_servo_init(uint32_t channel_mask)
+{
+ /* do basic timer initialisation first */
+ for (unsigned i = 0; i < PWM_SERVO_MAX_TIMERS; i++) {
+ if (pwm_timers[i].base != 0)
+ pwm_timer_init(i);
+ }
+
+ /* now init channels */
+ for (unsigned i = 0; i < PWM_SERVO_MAX_CHANNELS; i++) {
+ /* don't do init for disabled channels; this leaves the pin configs alone */
+ if (((1<<i) & channel_mask) && (pwm_channels[i].gpio != 0))
+ pwm_channel_init(i);
+ }
+ return OK;
+}
+
+void
+up_pwm_servo_deinit(void)
+{
+ /* disable the timers */
+ up_pwm_servo_arm(false);
+}
+
+int
+up_pwm_servo_set_rate(unsigned rate)
+{
+ if ((rate < 50) || (rate > 400))
+ return -ERANGE;
+
+ for (unsigned i = 0; i < PWM_SERVO_MAX_TIMERS; i++) {
+ if (pwm_timers[i].base != 0)
+ pwm_timer_set_rate(i, rate);
+ }
+ return OK;
+}
+
+void
+up_pwm_servo_arm(bool armed)
+{
+ /*
+ * XXX this is inelgant and in particular will either jam outputs at whatever level
+ * they happen to be at at the time the timers stop or generate runts.
+ * The right thing is almost certainly to kill auto-reload on the timers so that
+ * they just stop at the end of their count for disable, and to reset/restart them
+ * for enable.
+ */
+
+ /* iterate timers and arm/disarm appropriately */
+ for (unsigned i = 0; i < PWM_SERVO_MAX_TIMERS; i++) {
+ if (pwm_timers[i].base != 0)
+ rCR1(i) = armed ? GTIM_CR1_CEN : 0;
+ }
+}
diff --git a/nuttx/configs/px4fmu/src/up_spi.c b/nuttx/configs/px4fmu/src/up_spi.c
new file mode 100644
index 000000000..ea34c30ce
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_spi.c
@@ -0,0 +1,192 @@
+/************************************************************************************
+ * configs/px4fmu/src/up_spi.c
+ * arch/arm/src/board/up_spi.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/spi.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+#include "chip.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3)
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Enables debug output from this file (needs CONFIG_DEBUG too) */
+
+#undef SPI_DEBUG /* Define to enable debug */
+#undef SPI_VERBOSE /* Define to enable verbose debug */
+
+#ifdef SPI_DEBUG
+# define spidbg lldbg
+# ifdef SPI_VERBOSE
+# define spivdbg lldbg
+# else
+# define spivdbg(x...)
+# endif
+#else
+# undef SPI_VERBOSE
+# define spidbg(x...)
+# define spivdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the PX4FMU board.
+ *
+ ************************************************************************************/
+
+void weak_function stm32_spiinitialize(void)
+{
+ stm32_configgpio(GPIO_SPI_CS_GYRO);
+ stm32_configgpio(GPIO_SPI_CS_ACCEL);
+ stm32_configgpio(GPIO_SPI_CS_MPU);
+ stm32_configgpio(GPIO_SPI_CS_SDCARD);
+
+ /* De-activate all peripherals,
+ * required for some peripheral
+ * state machines
+ */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
+ stm32_gpiowrite(GPIO_SPI_CS_SDCARD, 1);
+}
+
+/****************************************************************************
+ * Name: stm32_spi1/2/3select and stm32_spi1/2/3status
+ *
+ * Description:
+ * The external functions, stm32_spi1/2/3select and stm32_spi1/2/3status must be
+ * provided by board-specific logic. They are implementations of the select
+ * and status methods of the SPI interface defined by struct spi_ops_s (see
+ * include/nuttx/spi.h). All other methods (including up_spiinitialize())
+ * are provided by common STM32 logic. To use this common SPI logic on your
+ * board:
+ *
+ * 1. Provide logic in stm32_boardinitialize() to configure SPI chip select
+ * pins.
+ * 2. Provide stm32_spi1/2/3select() and stm32_spi1/2/3status() functions in your
+ * board-specific logic. These functions will perform chip selection and
+ * status operations using GPIOs in the way your board is configured.
+ * 3. Add a calls to up_spiinitialize() in your low level application
+ * initialization logic
+ * 4. The handle returned by up_spiinitialize() may then be used to bind the
+ * SPI driver to higher level logic (e.g., calling
+ * mmcsd_spislotinitialize(), for example, will bind the SPI driver to
+ * the SPI MMC/SD driver).
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_STM32_SPI1
+void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
+
+ /* SPI select is active low, so write !selected to select the device */
+
+ switch (devid) {
+ case PX4_SPIDEV_GYRO:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_MPU, selected);
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL, selected);
+ break;
+ case PX4_SPIDEV_ACCEL:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL, !selected);
+ stm32_gpiowrite(GPIO_SPI_CS_MPU, selected);
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, selected);
+ break;
+ case PX4_SPIDEV_MPU:
+ /* Making sure the other peripherals are not selected */
+ stm32_gpiowrite(GPIO_SPI_CS_ACCEL, selected);
+ stm32_gpiowrite(GPIO_SPI_CS_GYRO, selected);
+ stm32_gpiowrite(GPIO_SPI_CS_MPU, !selected);
+ break;
+ default:
+ spidbg("devid: %d - unexpected\n", devid);
+ break;
+
+ }
+}
+
+uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+#ifdef CONFIG_STM32_SPI3
+void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
+
+ /* there can only be one device on this bus, so always select it */
+ stm32_gpiowrite(GPIO_SPI_CS_SDCARD, 0);
+}
+
+uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ /* this is actually bogus, but PX4 has no way to sense the presence of an SD card */
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+#endif /* CONFIG_STM32_SPI1 || CONFIG_STM32_SPI2 */
diff --git a/nuttx/configs/px4fmu/src/up_usbdev.c b/nuttx/configs/px4fmu/src/up_usbdev.c
new file mode 100644
index 000000000..4ef105e91
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/up_usbdev.c
@@ -0,0 +1,105 @@
+/************************************************************************************
+ * configs/stm32f4discovery/src/up_usbdev.c
+ * arch/arm/src/board/up_boot.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <nuttx/usb/usbdev.h>
+#include <nuttx/usb/usbdev_trace.h>
+
+#include "up_arch.h"
+#include "stm32_internal.h"
+#include "px4fmu-internal.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_usbinitialize
+ *
+ * Description:
+ * Called to setup USB-related GPIO pins for the STM3210E-EVAL board.
+ *
+ ************************************************************************************/
+
+void stm32_usbinitialize(void)
+{
+ /* The OTG FS has an internal soft pull-up */
+
+ /* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */
+
+#ifdef CONFIG_STM32_OTGFS
+ stm32_configgpio(GPIO_OTGFS_VBUS);
+ /* XXX We only support device mode
+ stm32_configgpio(GPIO_OTGFS_PWRON);
+ stm32_configgpio(GPIO_OTGFS_OVER);
+ */
+#endif
+}
+
+/************************************************************************************
+ * Name: stm32_usbsuspend
+ *
+ * Description:
+ * Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is
+ * used. This function is called whenever the USB enters or leaves suspend mode.
+ * This is an opportunity for the board logic to shutdown clocks, power, etc.
+ * while the USB is suspended.
+ *
+ ************************************************************************************/
+
+void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume)
+{
+ ulldbg("resume: %d\n", resume);
+}
+