aboutsummaryrefslogtreecommitdiff
path: root/nuttx/configs/px4fmu/include
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/include
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/include')
-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
17 files changed, 2320 insertions, 0 deletions
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 */